mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Airspeed: add rc channel option to disable all airspeed sensors
This commit is contained in:
parent
1281033931
commit
6da68e39f8
@ -623,6 +623,9 @@ void AP_Airspeed::Log_Airspeed()
|
||||
|
||||
bool AP_Airspeed::use(uint8_t i) const
|
||||
{
|
||||
if (_force_disable_use) {
|
||||
return false;
|
||||
}
|
||||
if (!enabled(i) || !param[i].use) {
|
||||
return false;
|
||||
}
|
||||
|
@ -96,6 +96,11 @@ public:
|
||||
bool use(uint8_t i) const;
|
||||
bool use(void) const { return use(primary); }
|
||||
|
||||
// force disabling of all airspeed sensors
|
||||
void force_disable_use(bool value) {
|
||||
_force_disable_use = value;
|
||||
}
|
||||
|
||||
// return true if airspeed is enabled
|
||||
bool enabled(uint8_t i) const {
|
||||
if (i < AIRSPEED_MAX_SENSORS) {
|
||||
@ -236,6 +241,9 @@ private:
|
||||
|
||||
bool calibration_enabled;
|
||||
|
||||
// can be set to true to disable the use of the airspeed sensor
|
||||
bool _force_disable_use;
|
||||
|
||||
// current primary sensor
|
||||
uint8_t primary;
|
||||
uint8_t num_sensors;
|
||||
|
Loading…
Reference in New Issue
Block a user