Skip to content

AP_NavEKF3: added in a check for high velocity innovation #29434

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

Merged
merged 1 commit into from
Mar 12, 2025
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
4 changes: 4 additions & 0 deletions libraries/AP_NavEKF3/AP_NavEKF3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1157,6 +1157,10 @@ bool NavEKF3::pre_arm_check(bool requires_position, char *failure_msg, uint8_t f
}
return false;
}
// run per-core pre-arm checks
if (!core[i].pre_arm_check(requires_position, failure_msg, failure_msg_len)) {
return false;
}
}
return true;
}
Expand Down
25 changes: 25 additions & 0 deletions libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,31 @@ bool NavEKF3_core::healthy(void) const
return true;
}

/*
per-core pre-arm checks. returns false if we fail arming checks, in
which case the buffer will be populated with a failure message
requires_position should be true if horizontal position configuration should be checked
*/
bool NavEKF3_core::pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const
{
if (requires_position) {
// additional checks when position is required, used by pre-arm checks
const float max_vel_innovation = 2.0;
const float hvel_innovation = sqrtf(sq(innovVelPos[0])+sq(innovVelPos[1]));
if (onGround && PV_AidingMode == AID_ABSOLUTE &&
frontend->sources.useVelXYSource(AP_NavEKF_Source::SourceXY::GPS) &&
hvel_innovation > max_vel_innovation) {
// more than 2 m/s horizontal velocity innovation on the ground
dal.snprintf(failure_msg, failure_msg_len,
"EKF3[%u] vel error %.1f", unsigned(core_index)+1, hvel_innovation);
return false;
}
}

// all OK
return true;
}

// Return a consolidated error score where higher numbers represent larger errors
// Intended to be used by the front-end to determine which is the primary EKF
float NavEKF3_core::errorScore() const
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_NavEKF3/AP_NavEKF3_core.h
Original file line number Diff line number Diff line change
Expand Up @@ -464,6 +464,12 @@ class NavEKF3_core : public NavEKF_core_common
// get a yaw estimator instance
const EKFGSF_yaw *get_yawEstimator(void) const { return yawEstimator; }

// per-core pre-arm checks. returns false if we fail arming
// checks, in which case the buffer will be populated with a
// failure message
// requires_position should be true if horizontal position configuration should be checked
bool pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const;

private:
EKFGSF_yaw *yawEstimator;
AP_DAL &dal;
Expand Down
Loading