mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: add option to disable the EKF check for airspeed
for some flight profiles (such as glider pullup) the EKF airpeed consistency check may be triggered, leading to a valid airspeed being ignored, which can lead TECS to be in non-airspeed mode
This commit is contained in:
parent
413452aa1a
commit
1e310ac86f
|
@ -189,8 +189,8 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] = {
|
||||||
|
|
||||||
// @Param: OPTIONS
|
// @Param: OPTIONS
|
||||||
// @DisplayName: Optional AHRS behaviour
|
// @DisplayName: Optional AHRS behaviour
|
||||||
// @Description: This controls optional AHRS behaviour. Setting DisableDCMFallbackFW will change the AHRS behaviour for fixed wing aircraft in fly-forward flight to not fall back to DCM when the EKF stops navigating. Setting DisableDCMFallbackVTOL will change the AHRS behaviour for fixed wing aircraft in non fly-forward (VTOL) flight to not fall back to DCM when the EKF stops navigating.
|
// @Description: This controls optional AHRS behaviour. Setting DisableDCMFallbackFW will change the AHRS behaviour for fixed wing aircraft in fly-forward flight to not fall back to DCM when the EKF stops navigating. Setting DisableDCMFallbackVTOL will change the AHRS behaviour for fixed wing aircraft in non fly-forward (VTOL) flight to not fall back to DCM when the EKF stops navigating. Setting DontDisableAirspeedUsingEKF disables the EKF based innovation check for airspeed consistency
|
||||||
// @Bitmask: 0:DisableDCMFallbackFW, 1:DisableDCMFallbackVTOL
|
// @Bitmask: 0:DisableDCMFallbackFW, 1:DisableDCMFallbackVTOL, 2:DontDisableAirspeedUsingEKF
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("OPTIONS", 18, AP_AHRS, _options, 0),
|
AP_GROUPINFO("OPTIONS", 18, AP_AHRS, _options, 0),
|
||||||
|
|
||||||
|
@ -915,7 +915,8 @@ bool AP_AHRS::_should_use_airspeed_sensor(uint8_t airspeed_index) const
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
nav_filter_status filter_status;
|
nav_filter_status filter_status;
|
||||||
if (fly_forward &&
|
if (!option_set(Options::DISABLE_AIRSPEED_EKF_CHECK) &&
|
||||||
|
fly_forward &&
|
||||||
hal.util->get_soft_armed() &&
|
hal.util->get_soft_armed() &&
|
||||||
get_filter_status(filter_status) &&
|
get_filter_status(filter_status) &&
|
||||||
(filter_status.flags.rejecting_airspeed && !filter_status.flags.dead_reckoning)) {
|
(filter_status.flags.rejecting_airspeed && !filter_status.flags.dead_reckoning)) {
|
||||||
|
|
|
@ -1018,6 +1018,7 @@ private:
|
||||||
enum class Options : uint16_t {
|
enum class Options : uint16_t {
|
||||||
DISABLE_DCM_FALLBACK_FW=(1U<<0),
|
DISABLE_DCM_FALLBACK_FW=(1U<<0),
|
||||||
DISABLE_DCM_FALLBACK_VTOL=(1U<<1),
|
DISABLE_DCM_FALLBACK_VTOL=(1U<<1),
|
||||||
|
DISABLE_AIRSPEED_EKF_CHECK=(1U<<2),
|
||||||
};
|
};
|
||||||
AP_Int16 _options;
|
AP_Int16 _options;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue