aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2013-07-04 23:16:13 -0700
committerpx4dev <px4@purgatory.org>2013-07-04 23:16:13 -0700
commitc21237667bc2802f675c74641d25f538db5f2c0c (patch)
tree0ce875a7fc6361fcb298e19e4f6a582ae168ba7c
parentf7963a8c84792ff6d95fa52d92f308c596e309e4 (diff)
downloadpx4-firmware-c21237667bc2802f675c74641d25f538db5f2c0c.tar.gz
px4-firmware-c21237667bc2802f675c74641d25f538db5f2c0c.tar.bz2
px4-firmware-c21237667bc2802f675c74641d25f538db5f2c0c.zip
iov2 pin definition cleanup sweep
-rw-r--r--src/drivers/boards/px4iov2/px4iov2_init.c19
-rwxr-xr-xsrc/drivers/boards/px4iov2/px4iov2_internal.h19
-rw-r--r--src/modules/px4iofirmware/controls.c4
-rw-r--r--src/modules/px4iofirmware/px4io.c2
-rw-r--r--src/modules/px4iofirmware/px4io.h4
5 files changed, 19 insertions, 29 deletions
diff --git a/src/drivers/boards/px4iov2/px4iov2_init.c b/src/drivers/boards/px4iov2/px4iov2_init.c
index 09469d7e8..5d7b22560 100644
--- a/src/drivers/boards/px4iov2/px4iov2_init.c
+++ b/src/drivers/boards/px4iov2/px4iov2_init.c
@@ -104,31 +104,25 @@ __EXPORT void stm32_boardinitialize(void)
/* configure GPIOs */
- /* turn off - all leds are active low */
- stm32_gpiowrite(GPIO_LED1, true);
- stm32_gpiowrite(GPIO_LED2, true);
- stm32_gpiowrite(GPIO_LED3, true);
+ /* LEDS - default to off */
stm32_configgpio(GPIO_LED1);
stm32_configgpio(GPIO_LED2);
stm32_configgpio(GPIO_LED3);
-
stm32_configgpio(GPIO_BTN_SAFETY);
/* spektrum power enable is active high - disable it by default */
+ /* XXX might not want to do this on warm restart? */
stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, false);
stm32_configgpio(GPIO_SPEKTRUM_PWR_EN);
- /* servo power enable is active low, and has a pull down resistor
- * to keep it low during boot (since it may power the whole board.)
- */
- stm32_gpiowrite(GPIO_SERVO_PWR_EN, false);
- stm32_configgpio(GPIO_SERVO_PWR_EN);
-
stm32_configgpio(GPIO_SERVO_FAULT_DETECT);
+ /* RSSI inputs */
stm32_configgpio(GPIO_TIM_RSSI); /* xxx alternate function */
stm32_configgpio(GPIO_ADC_RSSI);
+
+ /* servo rail voltage */
stm32_configgpio(GPIO_ADC_VSERVO);
stm32_configgpio(GPIO_SBUS_INPUT); /* xxx alternate function */
@@ -140,7 +134,6 @@ __EXPORT void stm32_boardinitialize(void)
stm32_gpiowrite(GPIO_SBUS_OENABLE, true);
stm32_configgpio(GPIO_SBUS_OENABLE);
-
stm32_configgpio(GPIO_PPM); /* xxx alternate function */
stm32_gpiowrite(GPIO_PWM1, false);
@@ -166,6 +159,4 @@ __EXPORT void stm32_boardinitialize(void)
stm32_gpiowrite(GPIO_PWM8, false);
stm32_configgpio(GPIO_PWM8);
-
-// message("[boot] Successfully initialized px4iov2 gpios\n");
}
diff --git a/src/drivers/boards/px4iov2/px4iov2_internal.h b/src/drivers/boards/px4iov2/px4iov2_internal.h
index b8aa6d053..81a75431c 100755
--- a/src/drivers/boards/px4iov2/px4iov2_internal.h
+++ b/src/drivers/boards/px4iov2/px4iov2_internal.h
@@ -60,6 +60,7 @@
* Serial
******************************************************************************/
#define PX4FMU_SERIAL_BASE STM32_USART2_BASE
+#define PX4FMU_SERIAL_VECTOR STM32_IRQ_USART2
#define PX4FMU_SERIAL_TX_GPIO GPIO_USART2_TX
#define PX4FMU_SERIAL_RX_GPIO GPIO_USART2_RX
#define PX4FMU_SERIAL_TX_DMA DMACHAN_USART2_TX
@@ -73,13 +74,9 @@
/* LEDS **********************************************************************/
-#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN14)
-#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN15)
-#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13)
-
-#define GPIO_LED_BLUE BOARD_GPIO_LED1
-#define GPIO_LED_AMBER BOARD_GPIO_LED2
-#define GPIO_LED_SAFETY BOARD_GPIO_LED3
+#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN14)
+#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15)
+#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN13)
/* Safety switch button *******************************************************/
@@ -89,17 +86,14 @@
#define GPIO_SPEKTRUM_PWR_EN (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
-#define GPIO_SERVO_PWR_EN (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN15)
-
-#define GPIO_SERVO_FAULT_DETECT (GPIO_INPUT|GPIO_CNF_INPULLUP|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN13)
-
+#define GPIO_SERVO_FAULT_DETECT (GPIO_INPUT|GPIO_CNF_INPULLUP|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN15)
/* Analog inputs **************************************************************/
#define GPIO_ADC_VSERVO (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN4)
+
/* the same rssi signal goes to both an adc and a timer input */
#define GPIO_ADC_RSSI (GPIO_INPUT|GPIO_CNF_ANALOGIN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN5)
-/* floating pin */
#define GPIO_TIM_RSSI (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN12)
/* PWM pins **************************************************************/
@@ -117,6 +111,7 @@
/* SBUS pins *************************************************************/
+/* XXX these should be UART pins */
#define GPIO_SBUS_INPUT (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
#define GPIO_SBUS_OUTPUT (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
#define GPIO_SBUS_OENABLE (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN4)
diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c
index 3cf9ca149..95103964e 100644
--- a/src/modules/px4iofirmware/controls.c
+++ b/src/modules/px4iofirmware/controls.c
@@ -59,10 +59,10 @@ static perf_counter_t c_gather_ppm;
void
controls_init(void)
{
- /* DSM input */
+ /* DSM input (USART1) */
dsm_init("/dev/ttyS0");
- /* S.bus input */
+ /* S.bus input (USART3) */
sbus_init("/dev/ttyS2");
/* default to a 1:1 input map, all enabled */
diff --git a/src/modules/px4iofirmware/px4io.c b/src/modules/px4iofirmware/px4io.c
index 385920d53..e70b3fe88 100644
--- a/src/modules/px4iofirmware/px4io.c
+++ b/src/modules/px4iofirmware/px4io.c
@@ -143,7 +143,9 @@ user_start(int argc, char *argv[])
LED_SAFETY(false);
/* turn on servo power (if supported) */
+#ifdef POWER_SERVO
POWER_SERVO(true);
+#endif
/* start the safety switch handler */
safety_init();
diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h
index 47bcb8ddf..4965d0724 100644
--- a/src/modules/px4iofirmware/px4io.h
+++ b/src/modules/px4iofirmware/px4io.h
@@ -128,7 +128,9 @@ extern struct sys_state_s system_state;
#define LED_AMBER(_s) stm32_gpiowrite(GPIO_LED2, !(_s))
#define LED_SAFETY(_s) stm32_gpiowrite(GPIO_LED3, !(_s))
-#define POWER_SERVO(_s) stm32_gpiowrite(GPIO_SERVO_PWR_EN, (_s))
+#ifdef GPIO_SERVO_PWR_EN
+# define POWER_SERVO(_s) stm32_gpiowrite(GPIO_SERVO_PWR_EN, (_s))
+#endif
#ifdef GPIO_ACC1_PWR_EN
# define POWER_ACC1(_s) stm32_gpiowrite(GPIO_ACC1_PWR_EN, (_s))
#endif