mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
AP_RCProtocol: allow DSM bind using uart RX pin directly
This commit is contained in:
parent
6fa9768eab
commit
d8c0d82857
libraries/AP_RCProtocol
@ -353,6 +353,11 @@ bool AP_RCProtocol_DSM::dsm_decode(uint32_t frame_time_ms, const uint8_t dsm_fra
|
||||
*/
|
||||
void AP_RCProtocol_DSM::start_bind(void)
|
||||
{
|
||||
#if defined(HAL_GPIO_SPEKTRUM_RC) && HAL_GPIO_SPEKTRUM_RC
|
||||
if (!hal.gpio->get_mode(HAL_GPIO_SPEKTRUM_RC, bind_mode_saved)) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
bind_state = BIND_STATE1;
|
||||
}
|
||||
|
||||
@ -408,6 +413,7 @@ void AP_RCProtocol_DSM::update(void)
|
||||
if (now - bind_last_ms > 50) {
|
||||
hal.gpio->pinMode(HAL_GPIO_SPEKTRUM_RC, 0);
|
||||
bind_state = BIND_STATE_NONE;
|
||||
hal.gpio->set_mode(HAL_GPIO_SPEKTRUM_RC, bind_mode_saved);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
@ -57,6 +57,7 @@ private:
|
||||
BIND_STATE4,
|
||||
} bind_state;
|
||||
uint32_t bind_last_ms;
|
||||
uint32_t bind_mode_saved;
|
||||
|
||||
uint16_t last_values[AP_DSM_MAX_CHANNELS];
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user