mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_IOMCU: added access to RC protocol name
This commit is contained in:
parent
a8e6a09903
commit
5771e0a90e
@ -16,6 +16,7 @@
|
||||
#include <AP_Math/crc.h>
|
||||
#include <SRV_Channel/SRV_Channel.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include <AP_RCProtocol/AP_RCProtocol.h>
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
@ -858,4 +859,15 @@ bool AP_IOMCU::setup_mixing(RCMapper *rcmap, int8_t override_chan,
|
||||
return true;
|
||||
}
|
||||
|
||||
/*
|
||||
return the RC protocol name
|
||||
*/
|
||||
const char *AP_IOMCU::get_rc_protocol(void)
|
||||
{
|
||||
if (!is_chibios_backend) {
|
||||
return nullptr;
|
||||
}
|
||||
return AP_RCProtocol::protocol_name_from_protocol((AP_RCProtocol::rcprotocol_t)rc_input.data);
|
||||
}
|
||||
|
||||
#endif // HAL_WITH_IO_MCU
|
||||
|
@ -68,6 +68,9 @@ public:
|
||||
// Do DSM receiver binding
|
||||
void bind_dsm(uint8_t mode);
|
||||
|
||||
// get the name of the RC protocol
|
||||
const char *get_rc_protocol(void);
|
||||
|
||||
/*
|
||||
get servo rail voltage
|
||||
*/
|
||||
|
@ -288,6 +288,7 @@ void AP_IOMCU_FW::rcin_update()
|
||||
rc_input.pwm[i] = hal.rcin->read(i);
|
||||
}
|
||||
rc_input.last_input_ms = last_ms;
|
||||
rc_input.data = (uint16_t)rcprotocol->protocol_detected();
|
||||
} else if (last_ms - rc_input.last_input_ms > 200U) {
|
||||
rc_input.flags_rc_ok = false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user