mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_RCProtocol: add and use RC_Channel_config.h
This commit is contained in:
parent
32086826de
commit
b26cd59da6
@ -74,7 +74,7 @@ AP_RCProtocol::~AP_RCProtocol()
|
||||
|
||||
bool AP_RCProtocol::should_search(uint32_t now_ms) const
|
||||
{
|
||||
#if !defined(IOMCU_FW) && !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()) {
|
||||
return false;
|
||||
}
|
||||
@ -92,7 +92,7 @@ void AP_RCProtocol::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
||||
uint32_t now = AP_HAL::millis();
|
||||
bool searching = should_search(now);
|
||||
|
||||
#ifndef IOMCU_FW
|
||||
#if AP_RC_CHANNEL_ENABLED
|
||||
rc_protocols_mask = rc().enabled_protocols();
|
||||
#endif
|
||||
|
||||
@ -176,7 +176,7 @@ bool AP_RCProtocol::process_byte(uint8_t byte, uint32_t baudrate)
|
||||
uint32_t now = AP_HAL::millis();
|
||||
bool searching = should_search(now);
|
||||
|
||||
#ifndef IOMCU_FW
|
||||
#if AP_RC_CHANNEL_ENABLED
|
||||
rc_protocols_mask = rc().enabled_protocols();
|
||||
#endif
|
||||
|
||||
@ -297,7 +297,7 @@ void AP_RCProtocol::check_added_uart(void)
|
||||
added.last_config_change_ms = AP_HAL::millis();
|
||||
serial_configs[added.config_num].apply_to_uart(added.uart);
|
||||
}
|
||||
#ifndef IOMCU_FW
|
||||
#if AP_RC_CHANNEL_ENABLED
|
||||
rc_protocols_mask = rc().enabled_protocols();
|
||||
#endif
|
||||
const uint32_t current_baud = serial_configs[added.config_num].baud;
|
||||
|
@ -65,7 +65,7 @@ void AP_RCProtocol_Backend::add_input(uint8_t num_values, uint16_t *values, bool
|
||||
_num_channels = num_values;
|
||||
rc_frame_count++;
|
||||
frontend.set_failsafe_active(in_failsafe);
|
||||
#if APM_BUILD_TYPE(APM_BUILD_iofirmware)
|
||||
#if !AP_RC_CHANNEL_ENABLED
|
||||
// failsafed is sorted out in AP_IOMCU.cpp
|
||||
in_failsafe = false;
|
||||
#else
|
||||
|
@ -301,8 +301,10 @@ void AP_RCProtocol_CRSF::update(void)
|
||||
_last_frame_time_us = now;
|
||||
}
|
||||
|
||||
#if AP_RC_CHANNEL_ENABLED
|
||||
//Check if LQ is to be reported in place of RSSI
|
||||
_use_lq_for_rssi = bool(rc().use_crsf_lq_as_rssi());
|
||||
#endif
|
||||
}
|
||||
|
||||
// write out a frame of any type
|
||||
|
@ -43,7 +43,11 @@ public:
|
||||
bool change_baud_rate(uint32_t baudrate);
|
||||
// bootstrap baudrate
|
||||
uint32_t get_bootstrap_baud_rate() const {
|
||||
#if AP_RC_CHANNEL_ENABLED
|
||||
return rc().use_420kbaud_for_elrs() ? ELRS_BAUDRATE : CRSF_BAUDRATE;
|
||||
#else
|
||||
return CRSF_BAUDRATE;
|
||||
#endif
|
||||
}
|
||||
|
||||
// is the receiver active, used to detect power loss and baudrate changes
|
||||
|
Loading…
Reference in New Issue
Block a user