AP_Airspeed: added ARSPD_OPTIONS bit for disabling voltage correction

if the MS4525 has its own LDO then we are should disable the
correction
This commit is contained in:
Andrew Tridgell 2021-06-30 12:44:58 +10:00
parent d4d80f01bf
commit 0bdd8231cf
4 changed files with 11 additions and 3 deletions

View File

@ -168,7 +168,7 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
// @Param: _OPTIONS
// @DisplayName: Airspeed options bitmask
// @Description: Bitmask of options to use with airspeed. Disable and/or re-enable sensor based on the difference between airspeed and ground speed based on ARSPD_WIND_MAX threshold, if set
// @Bitmask: 0:Disable sensor, 1:Re-enable sensor
// @Bitmask: 0:Disable sensor, 1:Re-enable sensor, 2:DisableVoltageCorrection
// @User: Advanced
AP_GROUPINFO("_OPTIONS", 21, AP_Airspeed, _options, OPTIONS_DEFAULT),

View File

@ -145,6 +145,7 @@ public:
enum OptionsMask {
ON_FAILURE_AHRS_WIND_MAX_DO_DISABLE = (1<<0), // If set then use airspeed failure check
ON_FAILURE_AHRS_WIND_MAX_RECOVERY_DO_REENABLE = (1<<1), // If set then automatically enable the airspeed sensor use when healthy again.
DISABLE_VOLTAGE_CORRECTION = (1<<2),
};
enum airspeed_type {

View File

@ -55,6 +55,11 @@ protected:
return instance;
}
// see if voltage correction should be disabled
bool disable_voltage_correction(void) const {
return (frontend._options.get() & AP_Airspeed::OptionsMask::DISABLE_VOLTAGE_CORRECTION) != 0;
}
AP_Airspeed::pitot_tube_order get_tube_order(void) const {
return AP_Airspeed::pitot_tube_order(frontend.param[instance].tube_order.get());
}

View File

@ -193,8 +193,10 @@ void AP_Airspeed_MS4525::_collect()
float temp = _get_temperature(dT_raw);
float temp2 = _get_temperature(dT_raw2);
_voltage_correction(press, temp);
_voltage_correction(press2, temp2);
if (!disable_voltage_correction()) {
_voltage_correction(press, temp);
_voltage_correction(press2, temp2);
}
WITH_SEMAPHORE(sem);