mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
RC_Channel: add RC option to report CRSF LQ as RSSI
Co-author: Jules Gilson <julesgilson@yahoo.co.uk>
This commit is contained in:
parent
a18a4e5719
commit
ff3c4b8bda
@ -507,6 +507,10 @@ public:
|
||||
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;
|
||||
}
|
||||
|
||||
// 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.
|
||||
@ -570,6 +574,7 @@ protected:
|
||||
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
|
||||
};
|
||||
|
||||
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
|
||||
// @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
|
||||
AP_GROUPINFO("_OPTIONS", 33, RC_CHANNELS_SUBCLASS, _options, (uint32_t)RC_Channels::Option::ARMING_CHECK_THROTTLE),
|
||||
|
||||
// @Param: _PROTOCOLS
|
||||
|
Loading…
Reference in New Issue
Block a user