Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Rover/ekf_check.cpp
Views: 1798
#include "Rover.h"12/**3*4* Detects failures of the ekf and triggers a failsafe5*6*/78#ifndef EKF_CHECK_ITERATIONS_MAX9# define EKF_CHECK_ITERATIONS_MAX 10 // 1 second (ie. 10 iterations at 10hz) of bad variances signals a failure10#endif1112#ifndef EKF_CHECK_WARNING_TIME13# define EKF_CHECK_WARNING_TIME (30*1000) // warning text messages are sent to ground no more than every 30 seconds14#endif151617// EKF_check structure18static struct {19uint8_t fail_count; // number of iterations ekf or dcm have been out of tolerances20uint8_t bad_variance : 1; // true if ekf should be considered untrusted (fail_count has exceeded EKF_CHECK_ITERATIONS_MAX)21uint32_t last_warn_time; // system time of last warning in milliseconds. Used to throttle text warnings sent to GCS22} ekf_check_state;2324// ekf_check - detects if ekf variance are out of tolerance and triggers failsafe25// should be called at 10hz26void Rover::ekf_check()27{28// exit immediately if ekf has no origin yet - this assumes the origin can never become unset29Location temp_loc;30if (!ahrs.get_origin(temp_loc)) {31return;32}3334// return immediately if motors are not armed, or ekf check is disabled35if (!arming.is_armed() || (g.fs_ekf_thresh <= 0.0f)) {36ekf_check_state.fail_count = 0;37ekf_check_state.bad_variance = false;38AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;39failsafe_ekf_off_event(); // clear failsafe40return;41}4243// compare compass and velocity variance vs threshold44if (ekf_over_threshold()) {45// if compass is not yet flagged as bad46if (!ekf_check_state.bad_variance) {47// increase counter48ekf_check_state.fail_count++;49// if counter above max then trigger failsafe50if (ekf_check_state.fail_count >= EKF_CHECK_ITERATIONS_MAX) {51// limit count from climbing too high52ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX;53ekf_check_state.bad_variance = true;5455LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK,56LogErrorCode::EKFCHECK_BAD_VARIANCE);57// send message to gcs58if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) {59gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF variance");60ekf_check_state.last_warn_time = AP_HAL::millis();61}62failsafe_ekf_event();63}64}65} else {66// reduce counter67if (ekf_check_state.fail_count > 0) {68ekf_check_state.fail_count--;6970// if variance is flagged as bad and the counter reaches zero then clear flag71if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) {72ekf_check_state.bad_variance = false;73LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK,74LogErrorCode::EKFCHECK_VARIANCE_CLEARED);75// clear failsafe76failsafe_ekf_off_event();77}78}79}8081// set AP_Notify flags82AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;83}8485// returns true if the ekf's variance are over the tolerance86bool Rover::ekf_over_threshold()87{88// return false immediately if disabled89if (g.fs_ekf_thresh <= 0.0f) {90return false;91}9293// use EKF to get variance94float position_variance, vel_variance, height_variance, tas_variance;95Vector3f mag_variance;96ahrs.get_variances(vel_variance, position_variance, height_variance, mag_variance, tas_variance);9798// return true if two of compass, velocity and position variances are over the threshold99uint8_t over_thresh_count = 0;100if (mag_variance.length() >= g.fs_ekf_thresh) {101over_thresh_count++;102}103if (vel_variance >= g.fs_ekf_thresh) {104over_thresh_count++;105}106if (position_variance >= g.fs_ekf_thresh) {107over_thresh_count++;108}109110bool optflow_healthy = false;111#if AP_OPTICALFLOW_ENABLED112optflow_healthy = optflow.healthy();113#endif114if (!optflow_healthy && (vel_variance >= (2.0f * g.fs_ekf_thresh))) {115over_thresh_count += 2;116} else if (vel_variance >= g.fs_ekf_thresh) {117over_thresh_count++;118}119120if (over_thresh_count >= 2) {121return true;122}123124return !ekf_position_ok();125}126127// ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set128bool Rover::ekf_position_ok()129{130if (!ahrs.have_inertial_nav()) {131// do not allow navigation with dcm position132return false;133}134135// get EKF filter status136nav_filter_status filt_status;137rover.ahrs.get_filter_status(filt_status);138139// if disarmed we accept a predicted horizontal absolute or relative position140if (!arming.is_armed()) {141return (filt_status.flags.horiz_pos_abs || filt_status.flags.pred_horiz_pos_abs || filt_status.flags.horiz_pos_rel || filt_status.flags.pred_horiz_pos_rel);142} else {143// once armed we require a good absolute or relative position and EKF must not be in const_pos_mode144return ((filt_status.flags.horiz_pos_abs || filt_status.flags.horiz_pos_rel) && !filt_status.flags.const_pos_mode);145}146}147148// perform ekf failsafe149void Rover::failsafe_ekf_event()150{151// return immediately if ekf failsafe already triggered152if (failsafe.ekf) {153return;154}155156// EKF failsafe event has occurred157failsafe.ekf = true;158LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV,159LogErrorCode::FAILSAFE_OCCURRED);160161// does this mode require position?162if (!control_mode->requires_position()) {163return;164}165166// take action based on fs_ekf_action parameter167switch ((enum fs_ekf_action)g.fs_ekf_action.get()) {168case FS_EKF_DISABLE:169// do nothing170return;171case FS_EKF_REPORT_ONLY:172break;173case FS_EKF_HOLD:174default:175set_mode(mode_hold, ModeReason::EKF_FAILSAFE);176break;177}178179gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF failsafe");180}181182// failsafe_ekf_off_event - actions to take when EKF failsafe is cleared183void Rover::failsafe_ekf_off_event(void)184{185// return immediately if not in ekf failsafe186if (!failsafe.ekf) {187return;188}189190failsafe.ekf = false;191LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV,192LogErrorCode::FAILSAFE_RESOLVED);193gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF failsafe cleared");194}195196197