RC_Channel: log which RC channels are being overridden

This commit is contained in:
Peter Barker 2021-05-15 13:45:43 +10:00 committed by Peter Barker
parent f30ad1d2dc
commit 3de3f57501
2 changed files with 16 additions and 0 deletions

View File

@ -399,6 +399,10 @@ public:
static void set_override(const uint8_t chan, const int16_t value, const uint32_t timestamp_ms = 0); // set a channels override value static void set_override(const uint8_t chan, const int16_t value, const uint32_t timestamp_ms = 0); // set a channels override value
static bool has_active_overrides(void); // returns true if there are overrides applied that are valid static bool has_active_overrides(void); // returns true if there are overrides applied that are valid
// returns a mask indicating which channels have overrides. Bit 0
// is RC channel 1. Beware this is not a cheap call.
static uint16_t get_override_mask();
class RC_Channel *find_channel_for_option(const RC_Channel::aux_func_t option); class RC_Channel *find_channel_for_option(const RC_Channel::aux_func_t option);
bool duplicate_options_exist(); bool duplicate_options_exist();
RC_Channel::AuxSwitchPos get_channel_pos(const uint8_t rcmapchan) const; RC_Channel::AuxSwitchPos get_channel_pos(const uint8_t rcmapchan) const;

View File

@ -107,6 +107,18 @@ void RC_Channels::clear_overrides(void)
// copter and plane, RC_Channels needs to control failsafes to resolve this // copter and plane, RC_Channels needs to control failsafes to resolve this
} }
uint16_t RC_Channels::get_override_mask(void)
{
uint16_t ret = 0;
RC_Channels &_rc = rc();
for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {
if (_rc.channel(i)->has_override()) {
ret |= (1U << i);
}
}
return ret;
}
void RC_Channels::set_override(const uint8_t chan, const int16_t value, const uint32_t timestamp_ms) void RC_Channels::set_override(const uint8_t chan, const int16_t value, const uint32_t timestamp_ms)
{ {
RC_Channels &_rc = rc(); RC_Channels &_rc = rc();