commander: rework posvel validity checks

Move into functions.
Reset probation time and recalculate checks if a mode change is demanded to give the operator ability to regain control as soon as possible after nav performance is regained. (+11 squashed commits)
Squashed commits:
[a4bb800] commander: enable pilot to quickly recover from loss of position accuracy
[19e16a0] commander: rework postal probation time
[f96284e] commander: rework bad pos and vel test probation time
[00d5f0c] commander: Allow EKF preflight checks to pass with moving vehicle

Separates the 'is using GPS' and the GPS quality checks.
Uses a reasonable subset of the GPS quality checks which allows checks to pass if the vehicle is moving.
[4cdfb5c] commander: remove unused variable
[349385a] commander: add EKF GPS quality checks to pre-arm checking

Only perform check if GPs checking is activated by parameter setting.
Display fault messages that makes it clear if EKF quality checks are failing or the EKF is not using GPS for another reason. We do not want to confuse this with GPS lock.
[340ae29] commander: make position invalid fail-safe more sticky

Require check to pass for 7 seconds before exiting failsafe. This is required because if GPs is failing innovation tests for a prolonged period, the EKF will periodically reset to the GPS and report good accuracy at the time of reset.
Adding this delay gives time for an underlying error condition (eg bad IMU or compass) to be re-detected.
[b04ac95] commander: Increase RAM allocation to eliminate low stack warnings
[9dca12f] commander: add missing position invalid fail-safe responses
[69f264d] commander: Update position invalid fail-safe responses

Replace separate logic for each case with a generic function
Add velocity checks.
[8e8cef1] commander: rework position validity checks

Consolidate existing checks for global and local position validity and add checking of velocity accuracy.
Enable checks to be bypassed using the CBRK_VELPOSERR parameter.
This commit is contained in:
priseborough
2017-03-08 11:03:27 +11:00
committed by Lorenz Meier
parent 40160c4488
commit 8ea0b2d3c5
4 changed files with 400 additions and 142 deletions

View File

@@ -448,7 +448,7 @@ static bool gnssCheck(orb_advert_t *mavlink_log_pub, bool report_fail)
return success;
}
static bool ekf2Check(orb_advert_t *mavlink_log_pub, bool optional, bool report_fail)
static bool ekf2Check(orb_advert_t *mavlink_log_pub, bool optional, bool report_fail, bool enforce_gps_required)
{
// Get estimator status data if available and exit with a fail recorded if not
int sub = orb_subscribe(ORB_ID(estimator_status));
@@ -491,6 +491,31 @@ static bool ekf2Check(orb_advert_t *mavlink_log_pub, bool optional, bool report_
goto out;
}
// If GPS aiding is required, declare fault condition if the EKF is not using GPS
if (enforce_gps_required) {
if (!(status.control_mode_flags & 2)) {
if (report_fail) {
mavlink_log_critical(mavlink_log_pub, "PREFLIGHT FAIL: EKF NOT USING GPS");
}
success = false;
goto out;
}
}
// If GPS aiding is required, declare fault condition if the required GPS quality checks are failing
if (enforce_gps_required) {
if ((status.gps_check_fail_flags & (estimator_status_s::GPS_CHECK_FAIL_MIN_SAT_COUNT
| estimator_status_s::GPS_CHECK_FAIL_MIN_GDOP
| estimator_status_s::GPS_CHECK_FAIL_MAX_HORZ_ERR
| estimator_status_s::GPS_CHECK_FAIL_MAX_VERT_ERR)) > 0) {
if (report_fail) {
mavlink_log_critical(mavlink_log_pub, "PREFLIGHT FAIL: GPS QUALITY CHECKS");
}
success = false;
goto out;
}
}
// check magnetometer innovation test ratio
param_get(param_find("COM_ARM_EKF_YAW"), &test_limit);
if (status.mag_test_ratio > test_limit) {
@@ -694,7 +719,7 @@ bool preflightCheck(orb_advert_t *mavlink_log_pub, bool checkMag, bool checkAcc,
int32_t estimator_type;
param_get(param_find("SYS_MC_EST_GROUP"), &estimator_type);
if (estimator_type == 2 && checkGNSS) {
if (!ekf2Check(mavlink_log_pub, true, reportFailures)) {
if (!ekf2Check(mavlink_log_pub, true, reportFailures, checkGNSS)) {
failed = true;
}
}