Browse Source

px4fmu-v4 Remove GPIO_RC_OUT and vetted RC_IN wiring

Removed the legacy FMUv4 define that was activating a nonexistent
   pull up and on some HW driving the PPM_IN aka RC_IN aka SPEKTRUM_RX
   to VDD.

   Also detailed the connections of this pins for the board.

   The simplest connection is RC_IN to a timer capture pin
   and a UART.
   In this case the UART_RX pin and just be left as is.
   While the pin can be configured as the PPM_IN (Timer capture)
   or as SPEKTRUM_RX_AS_GPIO_OUTPUT to use it as and GPIO to
   facilitate binding.

  Renamed the macros and defines to be more explicit as to what
  Is being done and the sense of the parameters
sbg
David Sidrane 8 years ago
parent
commit
a161c05dc6
  1. 27
      src/drivers/boards/px4fmu-v4/board_config.h
  2. 5
      src/drivers/boards/px4fmu-v4/px4fmu_init.c

27
src/drivers/boards/px4fmu-v4/board_config.h

@ -236,10 +236,10 @@ @@ -236,10 +236,10 @@
#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
/* High-resolution timer */
#define HRT_TIMER 3 /* use timer8 for the HRT */
#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel */
#define HRT_TIMER 3 /* use timer 3 for the HRT */
#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel 4 */
#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 2 */
#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */
#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF2|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0)
#define RC_SERIAL_PORT "/dev/ttyS4"
@ -255,7 +255,7 @@ @@ -255,7 +255,7 @@
#define GPIO_PERIPH_3V3_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5)
/* for R12, this signal is active high */
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
#define INVERT_RC_INPUT(_s) px4_arch_gpiowrite(GPIO_SBUS_INV, _s)
#define INVERT_RC_INPUT(_invert_true) px4_arch_gpiowrite(GPIO_SBUS_INV, _invert_true)
#define GPIO_8266_GPIO0 (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN2)
#define GPIO_SPEKTRUM_PWR_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4)
@ -264,14 +264,21 @@ @@ -264,14 +264,21 @@
/* Power switch controls ******************************************************/
#define POWER_SPEKTRUM(_s) px4_arch_gpiowrite(GPIO_SPEKTRUM_PWR_EN, (1-_s))
#define SPEKTRUM_RX_AS_UART() px4_arch_configgpio(GPIO_USART1_RX)
#define SPEKTRUM_POWER(_on_true) px4_arch_gpiowrite(GPIO_SPEKTRUM_PWR_EN, (!_on_true))
// FMUv4 has a separate GPIO for serial RC output
#define GPIO_RC_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define SPEKTRUM_RX_AS_GPIO() px4_arch_configgpio(GPIO_RC_OUT)
#define SPEKTRUM_RX_HIGH(_s) px4_arch_gpiowrite(GPIO_RC_OUT, (_s))
/*
* FMUv4 has separate RC_IN
*
* GPIO PPM_IN on PB0 T3C3
* SPEKTRUM_RX (it's TX or RX in Bind) on UART6 PC7
* Inversion is possible via the 74LVC2G86 controlled by the FMU
* The FMU can drive GPIO PPM_IN as an output
*/
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define BOARD_NAME "PX4FMU_V4"

5
src/drivers/boards/px4fmu-v4/px4fmu_init.c

@ -182,11 +182,6 @@ stm32_boardinitialize(void) @@ -182,11 +182,6 @@ stm32_boardinitialize(void)
stm32_configgpio(GPIO_8266_RST);
stm32_configgpio(GPIO_BTN_SAFETY);
#ifdef GPIO_RC_OUT
stm32_configgpio(GPIO_RC_OUT); /* Serial RC output pin */
stm32_gpiowrite(GPIO_RC_OUT, 1); /* set it high to pull RC input up */
#endif
/* configure the GPIO pins to outputs and keep them low */
stm32_configgpio(GPIO_GPIO0_OUTPUT);
stm32_configgpio(GPIO_GPIO1_OUTPUT);

Loading…
Cancel
Save