Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added RC option for allowing RC protocol switching #18889

Merged
merged 2 commits into from
Oct 15, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 13 additions & 3 deletions libraries/AP_RCProtocol/AP_RCProtocol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,10 +63,20 @@ AP_RCProtocol::~AP_RCProtocol()
}
}

bool AP_RCProtocol::should_search(uint32_t now_ms) const
{
#ifndef IOMCU_FW
if (_detected_protocol != AP_RCProtocol::NONE && !rc().multiple_receiver_support()) {
return false;
}
#endif
return (now_ms - _last_input_ms >= 200);
}

void AP_RCProtocol::process_pulse(uint32_t width_s0, uint32_t width_s1)
{
uint32_t now = AP_HAL::millis();
bool searching = (now - _last_input_ms >= 200);
bool searching = should_search(now);

#ifndef IOMCU_FW
rc_protocols_mask = rc().enabled_protocols();
Expand Down Expand Up @@ -150,7 +160,7 @@ void AP_RCProtocol::process_pulse_list(const uint32_t *widths, uint16_t n, bool
bool AP_RCProtocol::process_byte(uint8_t byte, uint32_t baudrate)
{
uint32_t now = AP_HAL::millis();
bool searching = (now - _last_input_ms >= 200);
bool searching = should_search(now);

#ifndef IOMCU_FW
rc_protocols_mask = rc().enabled_protocols();
Expand Down Expand Up @@ -234,7 +244,7 @@ void AP_RCProtocol::check_added_uart(void)
return;
}
uint32_t now = AP_HAL::millis();
bool searching = (now - _last_input_ms >= 200);
bool searching = should_search(now);
tridge marked this conversation as resolved.
Show resolved Hide resolved
if (!searching && !_detected_with_bytes) {
// not using this uart
return;
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_RCProtocol/AP_RCProtocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ class AP_RCProtocol {
{
return _valid_serial_prot;
}
bool should_search(uint32_t now_ms) const;
void process_pulse(uint32_t width_s0, uint32_t width_s1);
void process_pulse_list(const uint32_t *widths, uint16_t n, bool need_swap);
bool process_byte(uint8_t byte, uint32_t baudrate);
Expand Down
5 changes: 4 additions & 1 deletion libraries/RC_Channel/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -496,7 +496,9 @@ class RC_Channels {
return get_singleton() != nullptr && (_options & uint32_t(Option::SUPPRESS_CRSF_MESSAGE));
}


bool multiple_receiver_support() const {
return _options & uint32_t(Option::MULTI_RECEIVER_SUPPORT);
}

// returns true if overrides should time out. If true is returned
// then returned_timeout_ms will contain the timeout in
Expand Down Expand Up @@ -556,6 +558,7 @@ class RC_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
};

void new_override_received() {
Expand Down
2 changes: 1 addition & 1 deletion libraries/RC_Channel/RC_Channels_VarInfo.h
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ const AP_Param::GroupInfo RC_Channels::var_info[] = {
// @DisplayName: RC options
// @Description: RC input options
// @User: Advanced
// @Bitmask: 0:Ignore RC Receiver, 1:Ignore MAVLink Overrides, 2:Ignore Receiver Failsafe bit but allow other RC failsafes if setup, 3:FPort Pad, 4:Log RC input bytes, 5:Arming check throttle for 0 input, 6:Skip the arming check for neutral Roll/Pitch/Yaw sticks, 7:Allow Switch reverse, 8:Use passthrough for CRSF telemetry, 9:Suppress CRSF mode/rate message for ELRS systems
// @Bitmask: 0:Ignore RC Receiver, 1:Ignore MAVLink Overrides, 2:Ignore Receiver Failsafe bit but allow other RC failsafes if setup, 3:FPort Pad, 4:Log RC input bytes, 5:Arming check throttle for 0 input, 6:Skip the arming check for neutral Roll/Pitch/Yaw sticks, 7:Allow Switch reverse, 8:Use passthrough for CRSF telemetry, 9:Suppress CRSF mode/rate message for ELRS systems,10:Enable multiple receiver support
AP_GROUPINFO("_OPTIONS", 33, RC_CHANNELS_SUBCLASS, _options, (uint32_t)RC_Channels::Option::ARMING_CHECK_THROTTLE),

// @Param: _PROTOCOLS
Expand Down