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/ArduCopter/ekf_check.cpp
Views: 1798
#include "Copter.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 tolerances22bool bad_variance; // true if ekf should be considered untrusted (fail_count has exceeded EKF_CHECK_ITERATIONS_MAX)23bool has_ever_passed; // true if the ekf checks have ever passed24uint32_t last_warn_time; // system time of last warning in milliseconds. Used to throttle text warnings sent to GCS25} ekf_check_state;2627// ekf_check - detects if ekf variance are out of tolerance and triggers failsafe28// should be called at 10hz29void Copter::ekf_check()30{31// ensure EKF_CHECK_ITERATIONS_MAX is at least 732static_assert(EKF_CHECK_ITERATIONS_MAX >= 7, "EKF_CHECK_ITERATIONS_MAX must be at least 7");3334// exit immediately if ekf has no origin yet - this assumes the origin can never become unset35Location temp_loc;36if (!ahrs.get_origin(temp_loc)) {37return;38}3940// return immediately if ekf check is disabled41if (g.fs_ekf_thresh <= 0.0f) {42ekf_check_state.fail_count = 0;43ekf_check_state.bad_variance = false;44AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;45failsafe_ekf_off_event(); // clear failsafe46return;47}4849// compare compass and velocity variance vs threshold and also check50// if we has a position estimate51const bool over_threshold = ekf_over_threshold();52const bool has_position = ekf_has_relative_position() || ekf_has_absolute_position();53const bool checks_passed = !over_threshold && has_position;5455// return if ekf checks have never passed56ekf_check_state.has_ever_passed |= checks_passed;57if (!ekf_check_state.has_ever_passed) {58return;59}6061// increment or decrement counters and take action62if (!checks_passed) {63// if variances are not yet flagged as bad64if (!ekf_check_state.bad_variance) {65// increase counter66ekf_check_state.fail_count++;67if (ekf_check_state.fail_count == (EKF_CHECK_ITERATIONS_MAX-2) && over_threshold) {68// we are two iterations away from declaring an EKF failsafe, ask the EKF if we can reset69// yaw to resolve the issue70ahrs.request_yaw_reset();71}72if (ekf_check_state.fail_count == (EKF_CHECK_ITERATIONS_MAX-1)) {73// we are just about to declare a EKF failsafe, ask the EKF if we can74// change lanes to resolve the issue75ahrs.check_lane_switch();76}77// if counter above max then trigger failsafe78if (ekf_check_state.fail_count >= EKF_CHECK_ITERATIONS_MAX) {79// limit count from climbing too high80ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX;81ekf_check_state.bad_variance = true;82LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE);83// send message to gcs84if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) {85gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF variance");86ekf_check_state.last_warn_time = AP_HAL::millis();87}88failsafe_ekf_event();89}90}91} else {92// reduce counter93if (ekf_check_state.fail_count > 0) {94ekf_check_state.fail_count--;9596// if variances are flagged as bad and the counter reaches zero then clear flag97if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) {98ekf_check_state.bad_variance = false;99LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED);100// clear failsafe101failsafe_ekf_off_event();102}103}104}105106// set AP_Notify flags107AP_Notify::flags.ekf_bad = ekf_check_state.bad_variance;108109// To-Do: add ekf variances to extended status110}111112// ekf_over_threshold - returns true if the ekf's variance are over the tolerance113bool Copter::ekf_over_threshold()114{115// use EKF to get variance116float position_var, vel_var, height_var, tas_variance;117Vector3f mag_variance;118variances_valid = ahrs.get_variances(vel_var, position_var, height_var, mag_variance, tas_variance);119120if (!variances_valid) {121return false;122}123124uint32_t now_us = AP_HAL::micros();125float dt = (now_us - last_ekf_check_us) * 1e-6f;126127// always update filtered values as this serves the vibration check as well128position_var = pos_variance_filt.apply(position_var, dt);129vel_var = vel_variance_filt.apply(vel_var, dt);130height_var = hgt_variance_filt.apply(height_var, dt);131132last_ekf_check_us = now_us;133134// return false if disabled135if (g.fs_ekf_thresh <= 0.0f) {136return false;137}138139const float mag_max = fmaxf(fmaxf(mag_variance.x,mag_variance.y),mag_variance.z);140141// return true if two of compass, velocity and position variances are over the threshold OR velocity variance is twice the threshold142uint8_t over_thresh_count = 0;143if (mag_max >= g.fs_ekf_thresh) {144over_thresh_count++;145}146147bool optflow_healthy = false;148#if AP_OPTICALFLOW_ENABLED149optflow_healthy = optflow.healthy();150#endif151if (!optflow_healthy && (vel_var >= (2.0f * g.fs_ekf_thresh))) {152over_thresh_count += 2;153} else if (vel_var >= g.fs_ekf_thresh) {154over_thresh_count++;155}156157if ((position_var >= g.fs_ekf_thresh && over_thresh_count >= 1) || over_thresh_count >= 2) {158return true;159}160161return false;162}163164165// failsafe_ekf_event - perform ekf failsafe166void Copter::failsafe_ekf_event()167{168// EKF failsafe event has occurred169failsafe.ekf = true;170LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED);171172// if disarmed take no action173if (!motors->armed()) {174return;175}176177// sometimes LAND *does* require GPS so ensure we are in non-GPS land178if (flightmode->mode_number() == Mode::Number::LAND && landing_with_GPS()) {179mode_land.do_not_use_GPS();180return;181}182183// does this mode require position?184if (!copter.flightmode->requires_GPS() && (g.fs_ekf_action != FS_EKF_ACTION_LAND_EVEN_STABILIZE)) {185return;186}187188// take action based on fs_ekf_action parameter189switch (g.fs_ekf_action) {190case FS_EKF_ACTION_ALTHOLD:191// AltHold192if (failsafe.radio || !set_mode(Mode::Number::ALT_HOLD, ModeReason::EKF_FAILSAFE)) {193set_mode_land_with_pause(ModeReason::EKF_FAILSAFE);194}195break;196case FS_EKF_ACTION_LAND:197case FS_EKF_ACTION_LAND_EVEN_STABILIZE:198default:199set_mode_land_with_pause(ModeReason::EKF_FAILSAFE);200break;201}202203// set true if ekf action is triggered204AP_Notify::flags.failsafe_ekf = true;205gcs().send_text(MAV_SEVERITY_CRITICAL, "EKF Failsafe: changed to %s Mode", flightmode->name());206}207208// failsafe_ekf_off_event - actions to take when EKF failsafe is cleared209void Copter::failsafe_ekf_off_event(void)210{211// return immediately if not in ekf failsafe212if (!failsafe.ekf) {213return;214}215216failsafe.ekf = false;217if (AP_Notify::flags.failsafe_ekf) {218AP_Notify::flags.failsafe_ekf = false;219gcs().send_text(MAV_SEVERITY_CRITICAL, "EKF Failsafe Cleared");220}221LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED);222}223224// re-check if the flight mode requires GPS but EKF failsafe is active225// this should be called by flight modes that are changing their submode from one that does NOT require a position estimate to one that does226void Copter::failsafe_ekf_recheck()227{228// return immediately if not in ekf failsafe229if (!failsafe.ekf) {230return;231}232233// trigger EKF failsafe action234failsafe_ekf_event();235}236237// check for ekf yaw reset and adjust target heading, also log position reset238void Copter::check_ekf_reset()239{240// check for yaw reset241float yaw_angle_change_rad;242uint32_t new_ekfYawReset_ms = ahrs.getLastYawResetAngle(yaw_angle_change_rad);243if (new_ekfYawReset_ms != ekfYawReset_ms) {244attitude_control->inertial_frame_reset();245ekfYawReset_ms = new_ekfYawReset_ms;246LOGGER_WRITE_EVENT(LogEvent::EKF_YAW_RESET);247}248249// check for change in primary EKF, reset attitude target and log. AC_PosControl handles position target adjustment250if ((ahrs.get_primary_core_index() != ekf_primary_core) && (ahrs.get_primary_core_index() != -1)) {251attitude_control->inertial_frame_reset();252ekf_primary_core = ahrs.get_primary_core_index();253LOGGER_WRITE_ERROR(LogErrorSubsystem::EKF_PRIMARY, LogErrorCode(ekf_primary_core));254gcs().send_text(MAV_SEVERITY_WARNING, "EKF primary changed:%d", (unsigned)ekf_primary_core);255}256}257258// check for high vibrations affecting altitude control259void Copter::check_vibration()260{261uint32_t now = AP_HAL::millis();262263// assume checks will succeed264bool innovation_checks_valid = true;265266// check if vertical velocity and position innovations are positive (NKF3.IVD & NKF3.IPD are both positive)267Vector3f vel_innovation;268Vector3f pos_innovation;269Vector3f mag_innovation;270float tas_innovation;271float yaw_innovation;272if (!ahrs.get_innovations(vel_innovation, pos_innovation, mag_innovation, tas_innovation, yaw_innovation)) {273innovation_checks_valid = false;274}275const bool innov_velD_posD_positive = is_positive(vel_innovation.z) && is_positive(pos_innovation.z);276277// check if vertical velocity variance is at least 1 (NK4.SV >= 1.0)278// filtered variances are updated in ekf_check() which runs at the same rate (10Hz) as this check279if (!variances_valid) {280innovation_checks_valid = false;281}282const bool is_vibration_affected = ahrs.is_vibration_affected();283const bool bad_vibe_detected = (innovation_checks_valid && innov_velD_posD_positive && (vel_variance_filt.get() > 1.0f)) || is_vibration_affected;284const bool do_bad_vibe_actions = (g2.fs_vibe_enabled == 1) && bad_vibe_detected && motors->armed() && !flightmode->has_manual_throttle();285286if (!vibration_check.high_vibes) {287// initialise timers288if (!do_bad_vibe_actions) {289vibration_check.start_ms = now;290}291// check if failure has persisted for at least 1 second292if (now - vibration_check.start_ms > 1000) {293// switch position controller to use resistant gains294vibration_check.clear_ms = 0;295vibration_check.high_vibes = true;296pos_control->set_vibe_comp(true);297LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_OCCURRED);298gcs().send_text(MAV_SEVERITY_CRITICAL, "Vibration compensation ON");299}300} else {301// initialise timer302if (do_bad_vibe_actions) {303vibration_check.clear_ms = now;304}305// turn off vibration compensation after 15 seconds306if (now - vibration_check.clear_ms > 15000) {307// restore position controller gains, reset timers and update user308vibration_check.start_ms = 0;309vibration_check.high_vibes = false;310pos_control->set_vibe_comp(false);311vibration_check.clear_ms = 0;312LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_RESOLVED);313gcs().send_text(MAV_SEVERITY_CRITICAL, "Vibration compensation OFF");314}315}316317return;318}319320321