RC_Channel: remove intermediate option_is_enabled methods for RC_Channel
This commit is contained in:
parent
8dad537b6f
commit
7ccf8e62ce
@ -285,9 +285,9 @@ bool RC_Channel::get_reverse(void) const
|
||||
// read input from hal.rcin or overrides
|
||||
bool RC_Channel::update(void)
|
||||
{
|
||||
if (has_override() && !rc().ignore_overrides()) {
|
||||
if (has_override() && !rc().option_is_enabled(RC_Channels::Option::IGNORE_OVERRIDES)) {
|
||||
radio_in = override_value;
|
||||
} else if (rc().has_had_rc_receiver() && !rc().ignore_receiver()) {
|
||||
} else if (rc().has_had_rc_receiver() && !rc().option_is_enabled(RC_Channels::Option::IGNORE_RECEIVER)) {
|
||||
radio_in = hal.rcin->read(ch_in);
|
||||
} else {
|
||||
return false;
|
||||
@ -1656,7 +1656,7 @@ bool RC_Channel::read_3pos_switch(RC_Channel::AuxSwitchPos &ret) const
|
||||
}
|
||||
|
||||
// switch is reversed if 'reversed' option set on channel and switches reverse is allowed by RC_OPTIONS
|
||||
bool switch_reversed = reversed && rc().switch_reverse_allowed();
|
||||
bool switch_reversed = reversed && rc().option_is_enabled(RC_Channels::Option::ALLOW_SWITCH_REV);
|
||||
|
||||
if (in < AUX_SWITCH_PWM_TRIGGER_LOW) {
|
||||
ret = switch_reversed ? AuxSwitchPos::HIGH : AuxSwitchPos::LOW;
|
||||
|
@ -504,64 +504,29 @@ public:
|
||||
}
|
||||
}
|
||||
|
||||
// should we ignore RC failsafe bits from receivers?
|
||||
bool ignore_rc_failsafe(void) const {
|
||||
return get_singleton() != nullptr && (_options & uint32_t(Option::IGNORE_FAILSAFE));
|
||||
enum class Option {
|
||||
IGNORE_RECEIVER = (1U << 0), // RC receiver modules
|
||||
IGNORE_OVERRIDES = (1U << 1), // MAVLink overrides
|
||||
IGNORE_FAILSAFE = (1U << 2), // ignore RC failsafe bits
|
||||
FPORT_PAD = (1U << 3), // pad fport telem output
|
||||
LOG_RAW_DATA = (1U << 4), // log rc input bytes
|
||||
ARMING_CHECK_THROTTLE = (1U << 5), // run an arming check for neutral throttle
|
||||
ARMING_SKIP_CHECK_RPY = (1U << 6), // skip the an arming checks for the roll/pitch/yaw channels
|
||||
ALLOW_SWITCH_REV = (1U << 7), // honor the reversed flag on switches
|
||||
CRSF_CUSTOM_TELEMETRY = (1U << 8), // use passthrough data for crsf telemetry
|
||||
SUPPRESS_CRSF_MESSAGE = (1U << 9), // suppress CRSF mode/rate message for ELRS systems
|
||||
MULTI_RECEIVER_SUPPORT = (1U << 10), // allow multiple receivers
|
||||
USE_CRSF_LQ_AS_RSSI = (1U << 11), // returns CRSF link quality as RSSI value, instead of RSSI
|
||||
CRSF_FM_DISARM_STAR = (1U << 12), // when disarmed, add a star at the end of the flight mode in CRSF telemetry
|
||||
ELRS_420KBAUD = (1U << 13), // use 420kbaud for ELRS protocol
|
||||
};
|
||||
|
||||
bool option_is_enabled(Option option) const {
|
||||
return _options & uint32_t(option);
|
||||
}
|
||||
|
||||
// should we add a pad byte to Fport data
|
||||
bool fport_pad(void) const {
|
||||
return get_singleton() != nullptr && (_options & uint32_t(Option::FPORT_PAD));
|
||||
}
|
||||
|
||||
// returns true if we should pass through data for crsf telemetry
|
||||
bool crsf_custom_telemetry(void) const {
|
||||
return get_singleton() != nullptr && (_options & uint32_t(Option::CRSF_CUSTOM_TELEMETRY));
|
||||
}
|
||||
|
||||
// should a channel reverse option affect aux switches
|
||||
bool switch_reverse_allowed(void) const {
|
||||
return get_singleton() != nullptr && (_options & uint32_t(Option::ALLOW_SWITCH_REV));
|
||||
}
|
||||
|
||||
bool ignore_overrides() const {
|
||||
return _options & uint32_t(Option::IGNORE_OVERRIDES);
|
||||
}
|
||||
|
||||
bool ignore_receiver() const {
|
||||
return _options & uint32_t(Option::IGNORE_RECEIVER);
|
||||
}
|
||||
|
||||
bool log_raw_data() const {
|
||||
return _options & uint32_t(Option::LOG_DATA);
|
||||
}
|
||||
|
||||
virtual bool arming_check_throttle() const {
|
||||
return _options & uint32_t(Option::ARMING_CHECK_THROTTLE);
|
||||
}
|
||||
|
||||
bool arming_skip_checks_rpy() const {
|
||||
return _options & uint32_t(Option::ARMING_SKIP_CHECK_RPY);
|
||||
}
|
||||
|
||||
bool suppress_crsf_message(void) const {
|
||||
return get_singleton() != nullptr && (_options & uint32_t(Option::SUPPRESS_CRSF_MESSAGE));
|
||||
}
|
||||
|
||||
bool multiple_receiver_support() const {
|
||||
return _options & uint32_t(Option::MULTI_RECEIVER_SUPPORT);
|
||||
}
|
||||
|
||||
bool use_crsf_lq_as_rssi(void) const {
|
||||
return get_singleton() != nullptr && (_options & uint32_t(Option::USE_CRSF_LQ_AS_RSSI)) != 0;
|
||||
}
|
||||
|
||||
bool crsf_fm_disarm_star(void) const {
|
||||
return get_singleton() != nullptr && (_options & uint32_t(Option::CRSF_FM_DISARM_STAR)) != 0;
|
||||
}
|
||||
|
||||
bool use_420kbaud_for_elrs(void) const {
|
||||
return get_singleton() != nullptr && (_options & uint32_t(Option::ELRS_420KBAUD)) != 0;
|
||||
return option_is_enabled(Option::ARMING_CHECK_THROTTLE);
|
||||
}
|
||||
|
||||
// returns true if overrides should time out. If true is returned
|
||||
@ -626,23 +591,6 @@ public:
|
||||
|
||||
protected:
|
||||
|
||||
enum class Option {
|
||||
IGNORE_RECEIVER = (1U << 0), // RC receiver modules
|
||||
IGNORE_OVERRIDES = (1U << 1), // MAVLink overrides
|
||||
IGNORE_FAILSAFE = (1U << 2), // ignore RC failsafe bits
|
||||
FPORT_PAD = (1U << 3), // pad fport telem output
|
||||
LOG_DATA = (1U << 4), // log rc input bytes
|
||||
ARMING_CHECK_THROTTLE = (1U << 5), // run an arming check for neutral throttle
|
||||
ARMING_SKIP_CHECK_RPY = (1U << 6), // skip the an arming checks for the roll/pitch/yaw channels
|
||||
ALLOW_SWITCH_REV = (1U << 7), // honor the reversed flag on switches
|
||||
CRSF_CUSTOM_TELEMETRY = (1U << 8), // use passthrough data for crsf telemetry
|
||||
SUPPRESS_CRSF_MESSAGE = (1U << 9), // suppress CRSF mode/rate message for ELRS systems
|
||||
MULTI_RECEIVER_SUPPORT = (1U << 10), // allow multiple receivers
|
||||
USE_CRSF_LQ_AS_RSSI = (1U << 11), // returns CRSF link quality as RSSI value, instead of RSSI
|
||||
CRSF_FM_DISARM_STAR = (1U << 12), // when disarmed, add a star at the end of the flight mode in CRSF telemetry
|
||||
ELRS_420KBAUD = (1U << 13), // use 420kbaud for ELRS protocol
|
||||
};
|
||||
|
||||
void new_override_received() {
|
||||
has_new_overrides = true;
|
||||
_has_had_override = true;
|
||||
|
Loading…
Reference in New Issue
Block a user