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

Reduce false positives in pre-flight accel bias check #11350

Merged
merged 3 commits into from
Feb 4, 2019
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
13 changes: 13 additions & 0 deletions src/modules/commander/PreflightCheck.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -576,6 +576,19 @@ static bool ekf2Check(orb_advert_t *mavlink_log_pub, vehicle_status_s &vehicle_s

// check accelerometer delta velocity bias estimates
param_get(param_find("COM_ARM_EKF_AB"), &test_limit);
for (uint8_t index=13; index<16; index++) {
// allow for higher uncertainty in estimates for axes that are less observable to prevent false positives
// adjust test threshold by 3-sigma
float test_uncertainty = 3.0f * sqrtf(fmaxf(status.covariances[index],0.0f));
if (fabsf(status.states[index]) > test_limit + test_uncertainty) {
if (report_fail) {
mavlink_log_critical(mavlink_log_pub, "Preflight Fail: High Accelerometer Bias");
}

success = false;
goto out;
}
}

if (fabsf(status.states[13]) > test_limit || fabsf(status.states[14]) > test_limit
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Remove the original "High Accelerometer Bias" check?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reporting the reason for failure if report_fail is true is consistent with the way other test failures are handled.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Isn't this new "High Accelerometer Bias" check with uncertainty a replacement for the existing "High Accelerometer Bias"? The existing check is still going to trigger, and hence not reduce the number of false positives.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Will fix.

|| fabsf(status.states[15]) > test_limit) {
Expand Down
2 changes: 1 addition & 1 deletion src/modules/commander/commander_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -575,7 +575,7 @@ PARAM_DEFINE_FLOAT(COM_ARM_EKF_YAW, 0.5f);
* @decimal 4
* @increment 0.0001
*/
PARAM_DEFINE_FLOAT(COM_ARM_EKF_AB, 2.4e-3f);
PARAM_DEFINE_FLOAT(COM_ARM_EKF_AB, 1.73e-3f);

/**
* Maximum value of EKF gyro delta angle bias estimate that will allow arming
Expand Down