mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
HAL_ChibiOS: display source of RC input
distinguish between IOMCU, RCInput with bytes and RCInput with pulses
This commit is contained in:
parent
b46b0d61a6
commit
4564140745
@ -150,6 +150,7 @@ void RCInput::_timer_tick(void)
|
||||
}
|
||||
#ifndef HAL_NO_UARTDRIVER
|
||||
const char *rc_protocol = nullptr;
|
||||
RCSource source = last_source;
|
||||
#endif
|
||||
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
@ -191,12 +192,13 @@ void RCInput::_timer_tick(void)
|
||||
_rx_link_quality = rcprot.get_rx_link_quality();
|
||||
#ifndef HAL_NO_UARTDRIVER
|
||||
rc_protocol = rcprot.protocol_name();
|
||||
source = rcprot.using_uart() ? RCSource::RCPROT_BYTES : RCSource::RCPROT_PULSES;
|
||||
#endif
|
||||
}
|
||||
#endif // HAL_BUILD_AP_PERIPH
|
||||
|
||||
#if HAL_RCINPUT_WITH_AP_RADIO
|
||||
if (radio && radio->last_recv_us() != last_radio_us) {
|
||||
if (radio && radio->last_recv_us() != last_radio_us && !have_iocmu_rc) {
|
||||
last_radio_us = radio->last_recv_us();
|
||||
WITH_SEMAPHORE(rcin_mutex);
|
||||
_rcin_timestamp_last_signal = last_radio_us;
|
||||
@ -205,6 +207,9 @@ void RCInput::_timer_tick(void)
|
||||
for (uint8_t i=0; i<_num_channels; i++) {
|
||||
_rc_values[i] = radio->read(i);
|
||||
}
|
||||
#ifndef HAL_NO_UARTDRIVER
|
||||
source = RCSource::APRADIO;
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
@ -218,15 +223,17 @@ void RCInput::_timer_tick(void)
|
||||
#ifndef HAL_NO_UARTDRIVER
|
||||
rc_protocol = iomcu.get_rc_protocol();
|
||||
_rssi = iomcu.get_RSSI();
|
||||
source = RCSource::IOMCU;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifndef HAL_NO_UARTDRIVER
|
||||
if (rc_protocol && rc_protocol != last_protocol) {
|
||||
if (rc_protocol && (rc_protocol != last_protocol || source != last_source)) {
|
||||
last_protocol = rc_protocol;
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "RCInput: decoding %s", last_protocol);
|
||||
last_source = source;
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "RCInput: decoding %s(%u)", last_protocol, unsigned(source));
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -72,6 +72,15 @@ private:
|
||||
uint32_t _rcin_last_iomcu_ms;
|
||||
bool _init;
|
||||
const char *last_protocol;
|
||||
|
||||
enum class RCSource {
|
||||
NONE = 0,
|
||||
IOMCU = 1,
|
||||
RCPROT_PULSES = 2,
|
||||
RCPROT_BYTES = 3,
|
||||
APRADIO = 4,
|
||||
} last_source;
|
||||
|
||||
bool pulse_input_enabled;
|
||||
|
||||
#if HAL_RCINPUT_WITH_AP_RADIO
|
||||
|
Loading…
Reference in New Issue
Block a user