AP_RCProtocol: remove intermediate option_is_enabled methods for RC_Channel

This commit is contained in:
Peter Barker 2023-06-11 15:13:42 +10:00 committed by Randy Mackay
parent 53b99dd17a
commit f75c905d25
5 changed files with 6 additions and 6 deletions

View File

@ -93,7 +93,7 @@ AP_RCProtocol::~AP_RCProtocol()
bool AP_RCProtocol::should_search(uint32_t now_ms) const bool AP_RCProtocol::should_search(uint32_t now_ms) const
{ {
#if AP_RC_CHANNEL_ENABLED && !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) #if AP_RC_CHANNEL_ENABLED && !APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
if (_detected_protocol != AP_RCProtocol::NONE && !rc().multiple_receiver_support()) { if (_detected_protocol != AP_RCProtocol::NONE && !rc().option_is_enabled(RC_Channels::Option::MULTI_RECEIVER_SUPPORT)) {
return false; return false;
} }
#else #else

View File

@ -82,7 +82,7 @@ void AP_RCProtocol_Backend::add_input(uint8_t num_values, uint16_t *values, bool
// failsafed is sorted out in AP_IOMCU.cpp // failsafed is sorted out in AP_IOMCU.cpp
in_failsafe = false; in_failsafe = false;
#else #else
if (rc().ignore_rc_failsafe()) { if (rc().option_is_enabled(RC_Channels::Option::IGNORE_FAILSAFE)) {
in_failsafe = false; in_failsafe = false;
} }
#endif #endif
@ -179,7 +179,7 @@ void AP_RCProtocol_Backend::configure_vtx(uint8_t band, uint8_t channel, uint8_t
void AP_RCProtocol_Backend::log_data(AP_RCProtocol::rcprotocol_t prot, uint32_t timestamp, const uint8_t *data, uint8_t len) const void AP_RCProtocol_Backend::log_data(AP_RCProtocol::rcprotocol_t prot, uint32_t timestamp, const uint8_t *data, uint8_t len) const
{ {
#if HAL_LOGGING_ENABLED #if HAL_LOGGING_ENABLED
if (rc().log_raw_data()) { if (rc().option_is_enabled(RC_Channels::Option::LOG_RAW_DATA)) {
uint32_t u32[10] {}; uint32_t u32[10] {};
if (len > sizeof(u32)) { if (len > sizeof(u32)) {
len = sizeof(u32); len = sizeof(u32);

View File

@ -306,7 +306,7 @@ void AP_RCProtocol_CRSF::update(void)
#if AP_RC_CHANNEL_ENABLED #if AP_RC_CHANNEL_ENABLED
//Check if LQ is to be reported in place of RSSI //Check if LQ is to be reported in place of RSSI
_use_lq_for_rssi = bool(rc().use_crsf_lq_as_rssi()); _use_lq_for_rssi = rc().option_is_enabled(RC_Channels::Option::USE_CRSF_LQ_AS_RSSI);
#endif #endif
} }

View File

@ -48,7 +48,7 @@ public:
// bootstrap baudrate // bootstrap baudrate
uint32_t get_bootstrap_baud_rate() const { uint32_t get_bootstrap_baud_rate() const {
#if AP_RC_CHANNEL_ENABLED #if AP_RC_CHANNEL_ENABLED
return rc().use_420kbaud_for_elrs() ? ELRS_BAUDRATE : CRSF_BAUDRATE; return rc().option_is_enabled(RC_Channels::Option::ELRS_420KBAUD) ? ELRS_BAUDRATE : CRSF_BAUDRATE;
#else #else
return CRSF_BAUDRATE; return CRSF_BAUDRATE;
#endif #endif

View File

@ -185,7 +185,7 @@ void AP_RCProtocol_FPort::decode_downlink(const FPort_Frame &frame)
uint8_t len = 0; uint8_t len = 0;
uint8_t buf2[sizeof(buf)*2+1]; uint8_t buf2[sizeof(buf)*2+1];
if (rc().fport_pad()) { if (rc().option_is_enabled(RC_Channels::Option::FPORT_PAD)) {
// this padding helps on some uarts that have hw pullups // this padding helps on some uarts that have hw pullups
buf2[len++] = 0xff; buf2[len++] = 0xff;
} }