AP_RCProtocol: add is_detected() so that telemetry implementations can defer actions

This commit is contained in:
Andy Piper 2024-01-14 13:38:02 +00:00 committed by Andrew Tridgell
parent efd5fec24d
commit 407b8a6003
2 changed files with 5 additions and 1 deletions

View File

@ -95,6 +95,10 @@ public:
return true; return true;
} }
bool is_detected() const {
return frontend._detected_protocol != AP_RCProtocol::NONE && frontend.backend[frontend._detected_protocol] == this;
}
#if AP_VIDEOTX_ENABLED #if AP_VIDEOTX_ENABLED
// called by static methods to confiig video transmitters: // called by static methods to confiig video transmitters:
static void configure_vtx(uint8_t band, uint8_t channel, uint8_t power, uint8_t pitmode); static void configure_vtx(uint8_t band, uint8_t channel, uint8_t power, uint8_t pitmode);

View File

@ -302,7 +302,7 @@ void AP_RCProtocol_CRSF::update(void)
// never received RC frames, but have received CRSF frames so make sure we give the telemetry opportunity to run // never received RC frames, but have received CRSF frames so make sure we give the telemetry opportunity to run
uint32_t now = AP_HAL::micros(); uint32_t now = AP_HAL::micros();
if (_last_frame_time_us > 0 && (!get_rc_frame_count() || !is_tx_active()) if (_last_frame_time_us > 0 && (!get_rc_input_count() || !is_tx_active())
&& now - _last_frame_time_us > CRSF_INTER_FRAME_TIME_US_250HZ) { && now - _last_frame_time_us > CRSF_INTER_FRAME_TIME_US_250HZ) {
process_telemetry(false); process_telemetry(false);
_last_frame_time_us = now; _last_frame_time_us = now;