rc_input: correctly init SBUS inversion for other RC protocols

This commit is contained in:
Daniel Agar 2022-04-29 19:29:28 -04:00
parent 7784cd1f40
commit 9acd39521d
No known key found for this signature in database
GPG Key ID: FD3CBA98017A69DE
27 changed files with 105 additions and 224 deletions

View File

@ -113,7 +113,7 @@
#define RC_SERIAL_PORT "/dev/ttyS0"
// #define GPIO_RSSI_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN1)
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN10)
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN10)
#define RC_INVERT_INPUT(_invert_true) px4_arch_gpiowrite(GPIO_SBUS_INV, _invert_true);
#define GPIO_FRSKY_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN12)

View File

@ -149,7 +149,6 @@
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
/* power on/off */
#define MS_PWR_BUTTON_DOWN 750

View File

@ -160,7 +160,6 @@
#define HRT_PPM_CHANNEL /* T3C1 */ 1 /* use capture/compare channel 1 */
#define GPIO_PPM_IN /* PB4 T3C1 */ GPIO_TIM3_CH1IN_2
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
/**
* GPIO PPM_IN on PB4 T3C1
@ -169,7 +168,6 @@
*/
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN4)
#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))
/* RSSI_IN */

View File

@ -160,7 +160,6 @@
#define HRT_PPM_CHANNEL /* T3C1 */ 1 /* use capture/compare channel 1 */
#define GPIO_PPM_IN /* PB4 T3C1 */ GPIO_TIM3_CH1IN_2
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
/**
* GPIO PPM_IN on PB4 T3C1
@ -169,7 +168,6 @@
*/
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN4)
#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))
/* RSSI_IN */

View File

@ -141,12 +141,6 @@
* SPEKTRUM_RX (it's TX or RX in Bind) on PA10 UART1
* The FMU can drive GPIO PPM_IN as an output
*/
// TODO?
//#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN6)
//#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT)
//#define SPEKTRUM_RX_AS_UART() px4_arch_configgpio(GPIO_USART1_RX)
//#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true))
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
/* This board provides a DMA pool and APIs */

View File

@ -281,9 +281,7 @@
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS4"
#define RC_SERIAL_SINGLEWIRE
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
#define PWMIN_TIMER 4
@ -327,7 +325,6 @@
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
#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 SDIO_SLOTNO 0 /* Only one slot */

View File

@ -205,7 +205,6 @@
#define SPEKTRUM_RX_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN7)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(SPEKTRUM_RX_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(SPEKTRUM_RX_AS_OUT, (_one_true))
#define SDIO_SLOTNO 0 /* Only one slot */

View File

@ -264,7 +264,6 @@
#define SPEKTRUM_RX_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN7)
#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(SPEKTRUM_RX_AS_OUT)
#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */
#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(SPEKTRUM_RX_AS_OUT, (_one_true))
#define SDIO_SLOTNO 0 /* Only one slot */

View File

@ -135,7 +135,6 @@
*/
#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))
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)

View File

@ -158,7 +158,6 @@
*/
#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 SDIO_SLOTNO 0 /* Only one slot */

View File

@ -157,7 +157,6 @@
*/
#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 SDIO_SLOTNO 0 /* Only one slot */

View File

@ -134,7 +134,6 @@
*/
#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))
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)

View File

@ -134,7 +134,6 @@
*/
#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))
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)

View File

@ -134,7 +134,6 @@
*/
#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))
/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)

View File

@ -312,7 +312,6 @@
#define GPIO_PPM_IN /* GPIO_B1_06 GPT1_CAPTURE2 */ (GPIO_GPT1_CAPTURE2_2 | GENERAL_INPUT_IOMUX)
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
/* PWM input driver. Use FMU AUX5 pins attached to GPIO_EMC_33 GPIO3_IO19 FLEXPWM3_PWMA2 */

View File

@ -128,7 +128,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 GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
#define RC_INVERT_INPUT(_invert_true) px4_arch_gpiowrite(GPIO_SBUS_INV, _invert_true)
#define GPIO_SPEKTRUM_PWR_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4)
@ -158,7 +158,6 @@
#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))
/**

View File

@ -274,7 +274,6 @@ static inline bool board_get_external_lockout_state(void)
#define GPIO_nVDD_5V_HIPOWER_EN /* PF12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTF|GPIO_PIN12)
#define GPIO_nVDD_5V_HIPOWER_OC /* PF13 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTF|GPIO_PIN13)
#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4)
#define GPIO_VDD_3V3_SPEKTRUM_PASSIVE /* PE4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN4)
#define GPIO_VDD_5V_RC_EN /* PG5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN5)
#define GPIO_VDD_5V_WIFI_EN /* PG6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN5)
#define GPIO_VDD_3V3_SD_CARD_EN /* PG7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN7)
@ -314,9 +313,7 @@ static inline bool board_get_external_lockout_state(void)
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS4"
#define RC_SERIAL_SINGLEWIRE
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
@ -349,7 +346,6 @@ static inline bool board_get_external_lockout_state(void)
/* Power switch controls ******************************************************/
#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true)
#define SPEKTRUM_POWER_PASSIVE() px4_arch_configgpio(GPIO_VDD_3V3_SPEKTRUM_PASSIVE)
#define SPEKTRUM_POWER_CONFIG() px4_arch_configgpio(GPIO_VDD_3V3_SPEKTRUM_POWER_EN)
/*
@ -363,7 +359,6 @@ static inline bool board_get_external_lockout_state(void)
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
#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 SDIO_SLOTNO 0 /* Only one slot */

View File

@ -212,10 +212,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
VDD_5V_PERIPH_EN(true);
VDD_5V_HIPOWER_EN(true);
board_control_spi_sensors_power(true, 0xffff);
#ifdef SPEKTRUM_POWER_PASSIVE
// Turn power controls to passive
SPEKTRUM_POWER_PASSIVE();
#endif
VDD_5V_RC_EN(true);
VDD_5V_WIFI_EN(true);

View File

@ -292,9 +292,7 @@
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
/* Input Capture Channels. */
#define INPUT_CAP1_TIMER 5
@ -334,7 +332,6 @@
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
#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 SDIO_SLOTNO 0 /* Only one slot */

View File

@ -258,10 +258,7 @@
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
#define RC_SERIAL_SWAP_RXTX
/* Input Capture Channels. */
#define INPUT_CAP1_TIMER 1
@ -302,7 +299,6 @@
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
#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 SDIO_SLOTNO 0 /* Only one slot */

View File

@ -316,9 +316,7 @@
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
/* Input Capture Channels. */
#define INPUT_CAP1_TIMER 1
@ -359,7 +357,6 @@
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
#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 SDIO_SLOTNO 0 /* Only one slot */

View File

@ -253,9 +253,7 @@
#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS5"
#define RC_SERIAL_SINGLEWIRE
/* Input Capture Channels. */
#define INPUT_CAP1_TIMER 5
@ -293,7 +291,6 @@
#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5)
#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 SDIO_SLOTNO 0 /* Only one slot */

View File

@ -126,7 +126,7 @@
#define GPIO_PERIPH_3V3_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5)
/* For,this signal is active high. */
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
#define GPIO_SBUS_INV (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
#define RC_INVERT_INPUT(_invert_true) px4_arch_gpiowrite(GPIO_SBUS_INV, _invert_true)
#define GPIO_SPEKTRUM_PWR_EN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4)
@ -157,7 +157,6 @@
#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))
/**

View File

@ -411,79 +411,6 @@ typedef uint8_t px4_guid_t[PX4_GUID_BYTE_LENGTH];
************************************************************************************/
__BEGIN_DECLS
/************************************************************************************
* Name: board_rc_singlewire
*
* Description:
* A board may define RC_SERIAL_SINGLEWIRE, so that RC_SERIAL_PORT is configured
* as singlewire UART.
*
* Input Parameters:
* device: serial device, e.g. "/dev/ttyS0"
*
* Returned Value:
* true singlewire should be enabled.
* false if not.
*
************************************************************************************/
#if defined(RC_SERIAL_SINGLEWIRE)
static inline bool board_rc_singlewire(const char *device) { return strcmp(device, RC_SERIAL_PORT) == 0; }
#else
static inline bool board_rc_singlewire(const char *device) { return false; }
#endif
/************************************************************************************
* Name: board_rc_swap_rxtx
*
* Description:
* A board may define RC_SERIAL_SWAP_RXTX, so that RC_SERIAL_PORT is configured
* as UART with RX/TX swapped.
*
* Input Parameters:
* device: serial device, e.g. "/dev/ttyS0"
*
* Returned Value:
* true RX/RX should be swapped.
* false if not.
*
************************************************************************************/
#if defined(RC_SERIAL_SWAP_RXTX)
static inline bool board_rc_swap_rxtx(const char *device) { return strcmp(device, RC_SERIAL_PORT) == 0; }
#else
static inline bool board_rc_swap_rxtx(const char *device) { return false; }
#endif
/************************************************************************************
* Name: board_rc_invert_input
*
* Description:
* All boards may optionally define RC_INVERT_INPUT(bool invert) that is
* used to invert the RC_SERIAL_PORT RC port (e.g. to toggle an external XOR via
* GPIO).
*
* Input Parameters:
* invert_on - A positive logic value, that when true (on) will set the HW in
* inverted NRZ mode where a MARK will be 0 and SPACE will be a 1.
*
* Returned Value:
* true the UART inversion got set.
*
************************************************************************************/
#ifdef RC_INVERT_INPUT
static inline bool board_rc_invert_input(const char *device, bool invert)
{
if (strcmp(device, RC_SERIAL_PORT) == 0) { RC_INVERT_INPUT(invert); return true; }
return false;
}
#else
static inline bool board_rc_invert_input(const char *device, bool invert) { return false; }
#endif
/* Provide an interface for reading the connected state of VBUS */
/************************************************************************************

View File

@ -71,10 +71,6 @@ RCInput::RCInput(const char *device) :
RCInput::~RCInput()
{
#if defined(SPEKTRUM_POWER_PASSIVE)
// Disable power controls for Spektrum receiver
SPEKTRUM_POWER_PASSIVE();
#endif
dsm_deinit();
delete _crsf_telemetry;
@ -84,41 +80,6 @@ RCInput::~RCInput()
perf_free(_publish_interval_perf);
}
int
RCInput::init()
{
#ifdef RF_RADIO_POWER_CONTROL
// power radio on
RF_RADIO_POWER_CONTROL(true);
#endif // RF_RADIO_POWER_CONTROL
// dsm_init sets some file static variables and returns a file descriptor
// it also powers on the radio if needed
_rcs_fd = dsm_init(_device);
if (_rcs_fd < 0) {
return -errno;
}
if (board_rc_swap_rxtx(_device)) {
#if defined(TIOCSSWAP)
ioctl(_rcs_fd, TIOCSSWAP, SER_SWAP_ENABLED);
#endif // TIOCSSWAP
}
// assume SBUS input and immediately switch it to
// so that if Single wire mode on TX there will be only
// a short contention
sbus_config(_rcs_fd, board_rc_singlewire(_device));
#ifdef GPIO_PPM_IN
// disable CPPM input by mapping it away from the timer capture input
px4_arch_unconfiggpio(GPIO_PPM_IN);
#endif // GPIO_PPM_IN
return 0;
}
int
RCInput::task_spawn(int argc, char *argv[])
{
@ -277,20 +238,28 @@ void RCInput::set_rc_scan_state(RC_SCAN newState)
void RCInput::rc_io_invert(bool invert)
{
// First check if the board provides a board-specific inversion method (e.g. via GPIO),
// and if not use an IOCTL
if (!board_rc_invert_input(_device, invert)) {
#if defined(RC_SERIAL_PORT) && defined(RC_INVERT_INPUT)
if (strcmp(_device, RC_SERIAL_PORT) == 0) {
RC_INVERT_INPUT(invert);
}
#endif // RC_SERIAL_PORT && RC_INVERT_INPUT
#if defined(TIOCSINVERT)
if (_rcs_fd >= 0) {
if (invert) {
//int ret_invert = ioctl(_rcs_fd, TIOCSINVERT, SER_INVERT_ENABLED_RX | SER_INVERT_ENABLED_TX);
ioctl(_rcs_fd, TIOCSINVERT, SER_INVERT_ENABLED_RX | SER_INVERT_ENABLED_TX);
} else {
ioctl(_rcs_fd, TIOCSINVERT, 0);
}
}
#endif // TIOCSINVERT
}
}
void RCInput::Run()
@ -300,16 +269,7 @@ void RCInput::Run()
return;
}
if (!_initialized) {
if (init() == PX4_OK) {
_initialized = true;
} else {
PX4_ERR("init failed");
exit_and_cleanup();
}
} else {
{
perf_begin(_cycle_perf);
@ -345,6 +305,17 @@ void RCInput::Run()
if (!_rc_scan_locked && !_armed) {
if ((int)vcmd.param1 == 0) {
rc_io_invert(false);
if (_rcs_fd >= 0) {
close(_rcs_fd);
_rcs_fd = -1;
}
// Configure serial port for DSM
_rcs_fd = dsm_init(_device);
// DSM binding command
int dsm_bind_mode = (int)vcmd.param2;
@ -363,6 +334,8 @@ void RCInput::Run()
bind_spektrum(dsm_bind_pulses);
cmd_ret = vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED;
dsm_deinit();
}
} else {
@ -418,7 +391,7 @@ void RCInput::Run()
// This block scans for a supported serial RC input and locks onto the first one found
// Scan for 300 msec, then switch protocol
constexpr hrt_abstime rc_scan_max = 300_ms;
constexpr hrt_abstime rc_scan_max = 700_ms;
unsigned frame_drops = 0;
@ -428,7 +401,8 @@ void RCInput::Run()
// read all available data from the serial RC input UART
// read all available data from the serial RC input UART
int newBytes = ::read(_rcs_fd, &_rcs_buf[0], RC_MAX_BUFFER_SIZE);
uint8_t rcs_buf[RC_MAX_BUFFER_SIZE];
int newBytes = ::read(_rcs_fd, &rcs_buf[0], RC_MAX_BUFFER_SIZE);
if (newBytes > 0) {
_bytes_rx += newBytes;
@ -441,14 +415,24 @@ void RCInput::Run()
case RC_SCAN_SBUS:
if (_rc_scan_begin == 0) {
_rc_scan_begin = cycle_timestamp;
// Configure serial port for SBUS
sbus_config(_rcs_fd, board_rc_singlewire(_device));
if (_rcs_fd < 0) {
_rcs_fd = open(_device, O_RDWR | O_NONBLOCK);
}
// assume SBUS input and immediately switch it to
// so that if Single wire mode on TX there will be only
// a short contention
sbus_config(_rcs_fd, true);
#if defined(TIOCSSINGLEWIRE)
ioctl(_rcs_fd, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED);
#endif // TIOCSSINGLEWIRE
rc_io_invert(true);
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
memset(_rcs_buf, 0, sizeof(_rcs_buf));
_rc_scan_begin = hrt_absolute_time();
} else if (_rc_scan_locked
|| cycle_timestamp - _rc_scan_begin < rc_scan_max) {
@ -458,7 +442,7 @@ void RCInput::Run()
bool sbus_failsafe = false;
bool sbus_frame_drop = false;
rc_updated = sbus_parse(cycle_timestamp, &_rcs_buf[0], newBytes, &_raw_rc_values[0], &_raw_rc_count, &sbus_failsafe,
rc_updated = sbus_parse(cycle_timestamp, &rcs_buf[0], newBytes, &_raw_rc_values[0], &_raw_rc_count, &sbus_failsafe,
&sbus_frame_drop, &frame_drops, input_rc_s::RC_INPUT_MAX_CHANNELS);
if (rc_updated) {
@ -471,8 +455,16 @@ void RCInput::Run()
}
} else {
// Scan the next protocol
rc_io_invert(false);
#if defined(TIOCSSINGLEWIRE)
ioctl(_rcs_fd, TIOCSSINGLEWIRE, 0);
#endif // TIOCSSINGLEWIRE
::close(_rcs_fd);
_rcs_fd = -1;
// Scan the next protocol
set_rc_scan_state(RC_SCAN_DSM);
}
@ -480,13 +472,20 @@ void RCInput::Run()
case RC_SCAN_DSM:
if (_rc_scan_begin == 0) {
_rc_scan_begin = cycle_timestamp;
// Configure serial port for DSM
dsm_config(_rcs_fd);
// dsm_init sets some file static variables and returns a file descriptor
// it also powers on the radio if needed
if (_rcs_fd < 0) {
//_rcs_fd = open(_device, O_RDWR | O_NONBLOCK);
}
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
memset(_rcs_buf, 0, sizeof(_rcs_buf));
// Configure serial port for DSM
_rcs_fd = dsm_init(_device);
if (_rcs_fd < 0) {
PX4_ERR("dsm init failed");
}
_rc_scan_begin = hrt_absolute_time();
} else if (_rc_scan_locked
|| cycle_timestamp - _rc_scan_begin < rc_scan_max) {
@ -496,7 +495,7 @@ void RCInput::Run()
bool dsm_11_bit = false;
// parse new data
rc_updated = dsm_parse(cycle_timestamp, &_rcs_buf[0], newBytes, &_raw_rc_values[0], &_raw_rc_count,
rc_updated = dsm_parse(cycle_timestamp, &rcs_buf[0], newBytes, &_raw_rc_values[0], &_raw_rc_count,
&dsm_11_bit, &frame_drops, &dsm_rssi, input_rc_s::RC_INPUT_MAX_CHANNELS);
if (rc_updated) {
@ -509,6 +508,9 @@ void RCInput::Run()
}
} else {
dsm_deinit();
_rcs_fd = -1;
// Scan the next protocol
set_rc_scan_state(RC_SCAN_ST24);
}
@ -519,11 +521,7 @@ void RCInput::Run()
if (_rc_scan_begin == 0) {
_rc_scan_begin = cycle_timestamp;
// Configure serial port for DSM
dsm_config(_rcs_fd);
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
memset(_rcs_buf, 0, sizeof(_rcs_buf));
_rcs_fd = dsm_init(_device);
} else if (_rc_scan_locked
|| cycle_timestamp - _rc_scan_begin < rc_scan_max) {
@ -537,7 +535,7 @@ void RCInput::Run()
for (unsigned i = 0; i < (unsigned)newBytes; i++) {
/* set updated flag if one complete packet was parsed */
st24_rssi = input_rc_s::RSSI_MAX;
rc_updated = (OK == st24_decode(_rcs_buf[i], &st24_rssi, &lost_count,
rc_updated = (OK == st24_decode(rcs_buf[i], &st24_rssi, &lost_count,
&_raw_rc_count, _raw_rc_values, input_rc_s::RC_INPUT_MAX_CHANNELS));
}
@ -560,6 +558,8 @@ void RCInput::Run()
}
} else {
dsm_deinit();
_rcs_fd = -1;
// Scan the next protocol
set_rc_scan_state(RC_SCAN_SUMD);
}
@ -570,12 +570,9 @@ void RCInput::Run()
if (_rc_scan_begin == 0) {
_rc_scan_begin = cycle_timestamp;
// Configure serial port for DSM
_rcs_fd = dsm_init(_device);
dsm_config(_rcs_fd);
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
memset(_rcs_buf, 0, sizeof(_rcs_buf));
} else if (_rc_scan_locked
|| cycle_timestamp - _rc_scan_begin < rc_scan_max) {
@ -589,7 +586,7 @@ void RCInput::Run()
for (unsigned i = 0; i < (unsigned)newBytes; i++) {
/* set updated flag if one complete packet was parsed */
sumd_rssi = input_rc_s::RSSI_MAX;
rc_updated = (OK == sumd_decode(_rcs_buf[i], &sumd_rssi, &rx_count,
rc_updated = (OK == sumd_decode(rcs_buf[i], &sumd_rssi, &rx_count,
&_raw_rc_count, _raw_rc_values, input_rc_s::RC_INPUT_MAX_CHANNELS, &sumd_failsafe));
}
@ -603,6 +600,8 @@ void RCInput::Run()
}
} else {
::close(_rcs_fd);
_rcs_fd = -1;
// Scan the next protocol
set_rc_scan_state(RC_SCAN_PPM);
}
@ -647,19 +646,20 @@ void RCInput::Run()
case RC_SCAN_CRSF:
if (_rc_scan_begin == 0) {
_rc_scan_begin = cycle_timestamp;
if (_rcs_fd < 0) {
_rcs_fd = open(_device, O_RDWR | O_NONBLOCK);
}
// Configure serial port for CRSF
crsf_config(_rcs_fd);
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
memset(_rcs_buf, 0, sizeof(_rcs_buf));
} else if (_rc_scan_locked
|| cycle_timestamp - _rc_scan_begin < rc_scan_max) {
// parse new data
if (newBytes > 0) {
rc_updated = crsf_parse(cycle_timestamp, &_rcs_buf[0], newBytes, &_raw_rc_values[0], &_raw_rc_count,
rc_updated = crsf_parse(cycle_timestamp, &rcs_buf[0], newBytes, &_raw_rc_values[0], &_raw_rc_count,
input_rc_s::RC_INPUT_MAX_CHANNELS);
if (rc_updated) {
@ -686,6 +686,8 @@ void RCInput::Run()
}
} else {
::close(_rcs_fd);
_rcs_fd = -1;
// Scan the next protocol
set_rc_scan_state(RC_SCAN_GHST);
}
@ -695,12 +697,13 @@ void RCInput::Run()
case RC_SCAN_GHST:
if (_rc_scan_begin == 0) {
_rc_scan_begin = cycle_timestamp;
// Configure serial port for GHST
ghst_config(_rcs_fd);
// flush serial buffer and any existing buffered data
tcflush(_rcs_fd, TCIOFLUSH);
memset(_rcs_buf, 0, sizeof(_rcs_buf));
// Configure serial port for GHST
if (_rcs_fd < 0) {
_rcs_fd = open(_device, O_RDWR | O_NONBLOCK);
}
ghst_config(_rcs_fd);
} else if (_rc_scan_locked
|| cycle_timestamp - _rc_scan_begin < rc_scan_max) {
@ -708,7 +711,7 @@ void RCInput::Run()
// parse new data
if (newBytes > 0) {
int8_t ghst_rssi = -1;
rc_updated = ghst_parse(cycle_timestamp, &_rcs_buf[0], newBytes, &_raw_rc_values[0], &ghst_rssi,
rc_updated = ghst_parse(cycle_timestamp, &rcs_buf[0], newBytes, &_raw_rc_values[0], &ghst_rssi,
&_raw_rc_count, input_rc_s::RC_INPUT_MAX_CHANNELS);
if (rc_updated) {
@ -736,6 +739,8 @@ void RCInput::Run()
}
} else {
::close(_rcs_fd);
_rcs_fd = -1;
// Scan the next protocol
set_rc_scan_state(RC_SCAN_SBUS);
}

View File

@ -129,7 +129,6 @@ private:
hrt_abstime _rc_scan_begin{0};
bool _initialized{false};
bool _rc_scan_locked{false};
bool _report_lock{true};
@ -155,7 +154,6 @@ private:
char _device[20] {}; ///< device / serial port path
static constexpr size_t RC_MAX_BUFFER_SIZE{SBUS_BUFFER_SIZE};
uint8_t _rcs_buf[RC_MAX_BUFFER_SIZE] {};
uint16_t _raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS] {};
uint16_t _raw_rc_count{};

View File

@ -189,8 +189,6 @@ static bool dsm_decode_channel(uint16_t raw, unsigned shift, uint8_t &channel, u
static constexpr uint16_t offset = 903; // microseconds
value = roundf(servo_position * 0.583f) + offset;
PX4_DEBUG(stderr, "CH%d=%d(0x%02x), ", channel, value, raw);
return true;
}
@ -470,6 +468,9 @@ int dsm_config(int fd)
void dsm_proto_init()
{
memset(&dsm_frame, 0, sizeof(dsm_frame_t));
memset(&dsm_buf, 0, sizeof(dsm_buf_t));
dsm_channel_shift = 0;
dsm_frame_drops = 0;
dsm_chan_count = 0;
@ -509,11 +510,6 @@ int dsm_init(const char *device)
void dsm_deinit()
{
#ifdef SPEKTRUM_POWER_PASSIVE
// Turn power controls to passive
SPEKTRUM_POWER_PASSIVE();
#endif
if (dsm_fd >= 0) {
close(dsm_fd);
}
@ -580,7 +576,9 @@ void dsm_bind(uint16_t cmd, int pulses)
#if defined(DSM_DEBUG)
printf("DSM: DSM_CMD_BIND_REINIT_UART\n");
#endif
#if defined(SPEKTRUM_RX_AS_UART)
SPEKTRUM_RX_AS_UART();
#endif // SPEKTRUM_RX_AS_UART
break;
}