Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AHRS: add option to disable EKF innovation check for airspeed #28257

Merged
merged 2 commits into from
Sep 29, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -6175,11 +6175,16 @@ def GliderPullup(self):
defaults_filepath="Tools/autotest/default_params/glider.parm",
wipe=True)

self.set_parameter('LOG_DISARMED', 1)

self.set_parameters({
"PUP_ENABLE": 1,
"SERVO6_FUNCTION": 0, # balloon lift
"SERVO10_FUNCTION": 156, # lift release
"EK3_IMU_MASK": 1, # lane switches just make log harder to read
"AHRS_OPTIONS": 4, # don't disable airspeed based on EKF checks
"ARSPD_OPTIONS": 0, # don't disable airspeed
"ARSPD_WIND_GATE": 0,
})

self.set_servo(6, 1000)
Expand Down
7 changes: 4 additions & 3 deletions libraries/AP_AHRS/AP_AHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -189,8 +189,8 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] = {

// @Param: OPTIONS
// @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.
// @Bitmask: 0:DisableDCMFallbackFW, 1:DisableDCMFallbackVTOL
// @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, 2:DontDisableAirspeedUsingEKF
// @User: Advanced
AP_GROUPINFO("OPTIONS", 18, AP_AHRS, _options, 0),

Expand Down Expand Up @@ -915,7 +915,8 @@ bool AP_AHRS::_should_use_airspeed_sensor(uint8_t airspeed_index) const
return false;
}
nav_filter_status filter_status;
if (fly_forward &&
if (!option_set(Options::DISABLE_AIRSPEED_EKF_CHECK) &&
fly_forward &&
hal.util->get_soft_armed() &&
get_filter_status(filter_status) &&
(filter_status.flags.rejecting_airspeed && !filter_status.flags.dead_reckoning)) {
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_AHRS/AP_AHRS.h
Original file line number Diff line number Diff line change
Expand Up @@ -1018,6 +1018,7 @@ class AP_AHRS {
enum class Options : uint16_t {
DISABLE_DCM_FALLBACK_FW=(1U<<0),
DISABLE_DCM_FALLBACK_VTOL=(1U<<1),
DISABLE_AIRSPEED_EKF_CHECK=(1U<<2),
};
AP_Int16 _options;

Expand Down
Loading