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/Blimp/ekf_check.cpp
Views: 1798
#include "Blimp.h"12/**3*4* Detects failures of the ekf or inertial nav system triggers an alert5* to the pilot and helps take countermeasures6*7*/89#ifndef EKF_CHECK_ITERATIONS_MAX10# define EKF_CHECK_ITERATIONS_MAX 10 // 1 second (ie. 10 iterations at 10hz) of bad variances signals a failure11#endif1213#ifndef EKF_CHECK_WARNING_TIME14# define EKF_CHECK_WARNING_TIME (30*1000) // warning text messages are sent to ground no more than every 30 seconds15#endif1617////////////////////////////////////////////////////////////////////////////////18// EKF_check structure19////////////////////////////////////////////////////////////////////////////////20static struct {21uint8_t fail_count; // number of iterations ekf or dcm have been out of tolerances22uint8_t bad_variance : 1; // true if ekf should be considered untrusted (fail_count has exceeded EKF_CHECK_ITERATIONS_MAX)23uint32_t last_warn_time; // system time of last warning in milliseconds. Used to throttle text warnings sent to GCS24} ekf_check_state;2526// ekf_check - detects if ekf variance are out of tolerance and triggers failsafe27// should be called at 10hz28void Blimp::ekf_check()29{30// ensure EKF_CHECK_ITERATIONS_MAX is at least 731static_assert(EKF_CHECK_ITERATIONS_MAX >= 7, "EKF_CHECK_ITERATIONS_MAX must be at least 7");3233// exit immediately if ekf has no origin yet - this assumes the origin can never become unset34Location temp_loc;35if (!ahrs.get_origin(temp_loc)) {36return;37}3839// return immediately if motors are not armed, or ekf check is disabled40if (!motors->armed() || (g.fs_ekf_thresh <= 0.0f)) {41ekf_check_state.fail_count = 0;42ekf_check_state.bad_variance = false;43AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;44failsafe_ekf_off_event(); // clear failsafe45return;46}4748// compare compass and velocity variance vs threshold and also check49// if we are still navigating50bool is_navigating = ekf_has_relative_position() || ekf_has_absolute_position();51if (ekf_over_threshold() || !is_navigating) {52// if compass is not yet flagged as bad53if (!ekf_check_state.bad_variance) {54// increase counter55ekf_check_state.fail_count++;56if (ekf_check_state.fail_count == (EKF_CHECK_ITERATIONS_MAX-2) && ekf_over_threshold()) {57// we are two iterations away from declaring an EKF failsafe, ask the EKF if we can reset58// yaw to resolve the issue59ahrs.request_yaw_reset();60}61if (ekf_check_state.fail_count == (EKF_CHECK_ITERATIONS_MAX-1)) {62// we are just about to declare a EKF failsafe, ask the EKF if we can63// change lanes to resolve the issue64ahrs.check_lane_switch();65}66// if counter above max then trigger failsafe67if (ekf_check_state.fail_count >= EKF_CHECK_ITERATIONS_MAX) {68// limit count from climbing too high69ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX;70ekf_check_state.bad_variance = true;71LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE);72// send message to gcs73if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) {74gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF variance");75ekf_check_state.last_warn_time = AP_HAL::millis();76}77failsafe_ekf_event();78}79}80} else {81// reduce counter82if (ekf_check_state.fail_count > 0) {83ekf_check_state.fail_count--;8485// if compass is flagged as bad and the counter reaches zero then clear flag86if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) {87ekf_check_state.bad_variance = false;88LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED);89// clear failsafe90failsafe_ekf_off_event();91}92}93}9495// set AP_Notify flags96AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;9798// To-Do: add ekf variances to extended status99}100101// ekf_over_threshold - returns true if the ekf's variance are over the tolerance102bool Blimp::ekf_over_threshold()103{104// return false immediately if disabled105if (g.fs_ekf_thresh <= 0.0f) {106return false;107}108109// use EKF to get variance110float position_variance, vel_variance, height_variance, tas_variance;111Vector3f mag_variance;112ahrs.get_variances(vel_variance, position_variance, height_variance, mag_variance, tas_variance);113114const float mag_max = fmaxf(fmaxf(mag_variance.x,mag_variance.y),mag_variance.z);115116// return true if two of compass, velocity and position variances are over the threshold OR velocity variance is twice the threshold117uint8_t over_thresh_count = 0;118if (mag_max >= g.fs_ekf_thresh) {119over_thresh_count++;120}121122bool optflow_healthy = false;123if (!optflow_healthy && (vel_variance >= (2.0f * g.fs_ekf_thresh))) {124over_thresh_count += 2;125} else if (vel_variance >= g.fs_ekf_thresh) {126over_thresh_count++;127}128129if ((position_variance >= g.fs_ekf_thresh && over_thresh_count >= 1) || over_thresh_count >= 2) {130return true;131}132133return false;134}135136137// failsafe_ekf_event - perform ekf failsafe138void Blimp::failsafe_ekf_event()139{140// return immediately if ekf failsafe already triggered141if (failsafe.ekf) {142return;143}144145// EKF failsafe event has occurred146failsafe.ekf = true;147LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED);148149// does this mode require position?150if (!blimp.flightmode->requires_GPS() && (g.fs_ekf_action != FS_EKF_ACTION_LAND_EVEN_MANUAL)) {151return;152}153154// take action based on fs_ekf_action parameter155switch (g.fs_ekf_action) {156case FS_EKF_ACTION_LAND:157case FS_EKF_ACTION_LAND_EVEN_MANUAL:158default:159set_mode_land_failsafe(ModeReason::EKF_FAILSAFE);160break;161}162}163164// failsafe_ekf_off_event - actions to take when EKF failsafe is cleared165void Blimp::failsafe_ekf_off_event(void)166{167// return immediately if not in ekf failsafe168if (!failsafe.ekf) {169return;170}171172failsafe.ekf = false;173LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED);174}175176// check for ekf yaw reset and adjust target heading, also log position reset177void Blimp::check_ekf_reset()178{179// check for yaw reset180float yaw_angle_change_rad;181uint32_t new_ekfYawReset_ms = ahrs.getLastYawResetAngle(yaw_angle_change_rad);182if (new_ekfYawReset_ms != ekfYawReset_ms) {183ekfYawReset_ms = new_ekfYawReset_ms;184LOGGER_WRITE_EVENT(LogEvent::EKF_YAW_RESET);185}186187// check for change in primary EKF, reset attitude target and log. AC_PosControl handles position target adjustment188if ((ahrs.get_primary_core_index() != ekf_primary_core) && (ahrs.get_primary_core_index() != -1)) {189ekf_primary_core = ahrs.get_primary_core_index();190LOGGER_WRITE_ERROR(LogErrorSubsystem::EKF_PRIMARY, LogErrorCode(ekf_primary_core));191gcs().send_text(MAV_SEVERITY_WARNING, "EKF primary changed:%d", (unsigned)ekf_primary_core);192}193}194195// check for high vibrations affecting altitude control196void Blimp::check_vibration()197{198uint32_t now = AP_HAL::millis();199200// assume checks will succeed201bool checks_succeeded = true;202203// check if vertical velocity and position innovations are positive (NKF3.IVD & NKF3.IPD are both positive)204Vector3f vel_innovation;205Vector3f pos_innovation;206Vector3f mag_innovation;207float tas_innovation;208float yaw_innovation;209if (!ahrs.get_innovations(vel_innovation, pos_innovation, mag_innovation, tas_innovation, yaw_innovation)) {210checks_succeeded = false;211}212const bool innov_velD_posD_positive = is_positive(vel_innovation.z) && is_positive(pos_innovation.z);213214// check if vertical velocity variance is at least 1 (NK4.SV >= 1.0)215float position_variance, vel_variance, height_variance, tas_variance;216Vector3f mag_variance;217if (!ahrs.get_variances(vel_variance, position_variance, height_variance, mag_variance, tas_variance)) {218checks_succeeded = false;219}220221// if no failure222if ((g2.fs_vibe_enabled == 0) || !checks_succeeded || !motors->armed() || !innov_velD_posD_positive || (vel_variance < 1.0f)) {223if (vibration_check.high_vibes) {224// start clear time225if (vibration_check.clear_ms == 0) {226vibration_check.clear_ms = now;227return;228}229// turn off vibration compensation after 15 seconds230if (now - vibration_check.clear_ms > 15000) {231// restore ekf gains, reset timers and update user232vibration_check.high_vibes = false;233vibration_check.clear_ms = 0;234LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_RESOLVED);235gcs().send_text(MAV_SEVERITY_CRITICAL, "Vibration compensation OFF");236}237}238vibration_check.start_ms = 0;239return;240}241242// start timer243if (vibration_check.start_ms == 0) {244vibration_check.start_ms = now;245vibration_check.clear_ms = 0;246return;247}248249// check if failure has persisted for at least 1 second250if (now - vibration_check.start_ms > 1000) {251if (!vibration_check.high_vibes) {252// switch ekf to use resistant gains253vibration_check.high_vibes = true;254LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_OCCURRED);255gcs().send_text(MAV_SEVERITY_CRITICAL, "Vibration compensation ON");256}257}258}259260261