mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: add option to support ELRS at 420kbaud
This commit is contained in:
parent
7206e49c0c
commit
5477acf3b4
|
@ -540,6 +540,10 @@ public:
|
|||
return get_singleton() != nullptr && (_options & uint32_t(Option::USE_CRSF_LQ_AS_RSSI)) != 0;
|
||||
}
|
||||
|
||||
bool use_420kbaud_for_elrs(void) const {
|
||||
return get_singleton() != nullptr && (_options & uint32_t(Option::ELRS_420KBAUD)) != 0;
|
||||
}
|
||||
|
||||
// returns true if overrides should time out. If true is returned
|
||||
// then returned_timeout_ms will contain the timeout in
|
||||
// milliseconds, with 0 meaning overrides are disabled.
|
||||
|
@ -609,6 +613,7 @@ protected:
|
|||
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
|
||||
ELRS_420KBAUD = (1U << 13), // use 420kbaud for ELRS protocol
|
||||
};
|
||||
|
||||
void new_override_received() {
|
||||
|
|
|
@ -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,10:Enable multiple receiver support, 11:CRSF RSSI shows Link Quality
|
||||
// @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, 11:Use Link Quality for RSSI with CRSF, 13: Use 420kbaud for ELRS protocol
|
||||
AP_GROUPINFO("_OPTIONS", 33, RC_CHANNELS_SUBCLASS, _options, (uint32_t)RC_Channels::Option::ARMING_CHECK_THROTTLE),
|
||||
|
||||
// @Param: _PROTOCOLS
|
||||
|
|
Loading…
Reference in New Issue