APM:Copter
ekf_check.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
10 #ifndef EKF_CHECK_ITERATIONS_MAX
11  # define EKF_CHECK_ITERATIONS_MAX 10 // 1 second (ie. 10 iterations at 10hz) of bad variances signals a failure
12 #endif
13 
14 #ifndef EKF_CHECK_WARNING_TIME
15  # define EKF_CHECK_WARNING_TIME (30*1000) // warning text messages are sent to ground no more than every 30 seconds
16 #endif
17 
19 // EKF_check strucutre
21 static struct {
22  uint8_t fail_count; // number of iterations ekf or dcm have been out of tolerances
23  uint8_t bad_variance : 1; // true if ekf should be considered untrusted (fail_count has exceeded EKF_CHECK_ITERATIONS_MAX)
24  uint32_t last_warn_time; // system time of last warning in milliseconds. Used to throttle text warnings sent to GCS
26 
27 // ekf_check - detects if ekf variance are out of tolerance and triggers failsafe
28 // should be called at 10hz
30 {
31  // exit immediately if ekf has no origin yet - this assumes the origin can never become unset
32  Location temp_loc;
33  if (!ahrs.get_origin(temp_loc)) {
34  return;
35  }
36 
37  // return immediately if motors are not armed, ekf check is disabled, not using ekf or usb is connected
38  if (!motors->armed() || ap.usb_connected || (g.fs_ekf_thresh <= 0.0f)) {
39  ekf_check_state.fail_count = 0;
40  ekf_check_state.bad_variance = false;
42  failsafe_ekf_off_event(); // clear failsafe
43  return;
44  }
45 
46  // compare compass and velocity variance vs threshold
47  if (ekf_over_threshold()) {
48  // if compass is not yet flagged as bad
49  if (!ekf_check_state.bad_variance) {
50  // increase counter
51  ekf_check_state.fail_count++;
52  // if counter above max then trigger failsafe
53  if (ekf_check_state.fail_count >= EKF_CHECK_ITERATIONS_MAX) {
54  // limit count from climbing too high
56  ekf_check_state.bad_variance = true;
57  // log an error in the dataflash
59  // send message to gcs
60  if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) {
61  gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF variance");
62  ekf_check_state.last_warn_time = AP_HAL::millis();
63  }
64  failsafe_ekf_event();
65  }
66  }
67  } else {
68  // reduce counter
69  if (ekf_check_state.fail_count > 0) {
70  ekf_check_state.fail_count--;
71 
72  // if compass is flagged as bad and the counter reaches zero then clear flag
73  if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) {
74  ekf_check_state.bad_variance = false;
75  // log recovery in the dataflash
77  // clear failsafe
78  failsafe_ekf_off_event();
79  }
80  }
81  }
82 
83  // set AP_Notify flags
85 
86  // To-Do: add ekf variances to extended status
87 }
88 
89 // ekf_over_threshold - returns true if the ekf's variance are over the tolerance
91 {
92  // return false immediately if disabled
93  if (g.fs_ekf_thresh <= 0.0f) {
94  return false;
95  }
96 
97  // use EKF to get variance
98  float position_variance, vel_variance, height_variance, tas_variance;
99  Vector3f mag_variance;
100  Vector2f offset;
101  ahrs.get_variances(vel_variance, position_variance, height_variance, mag_variance, tas_variance, offset);
102 
103  // return true if two of compass, velocity and position variances are over the threshold
104  uint8_t over_thresh_count = 0;
105  if (mag_variance.length() >= g.fs_ekf_thresh) {
106  over_thresh_count++;
107  }
108  if (vel_variance >= g.fs_ekf_thresh) {
109  over_thresh_count++;
110  }
111  if (position_variance >= g.fs_ekf_thresh) {
112  over_thresh_count++;
113  }
114 
115  if (over_thresh_count >= 2) {
116  return true;
117  }
118 
119  // either optflow relative or absolute position estimate OK
120  if (optflow_position_ok() || ekf_position_ok()) {
121  return false;
122  }
123  return true;
124 }
125 
126 
127 // failsafe_ekf_event - perform ekf failsafe
129 {
130  // return immediately if ekf failsafe already triggered
131  if (failsafe.ekf) {
132  return;
133  }
134 
135  // EKF failsafe event has occurred
136  failsafe.ekf = true;
138 
139  // sometimes LAND *does* require GPS so ensure we are in non-GPS land
140  if (control_mode == LAND && landing_with_GPS()) {
141  mode_land.do_not_use_GPS();
142  return;
143  }
144 
145  // does this mode require position?
146  if (!copter.flightmode->requires_GPS() && (g.fs_ekf_action != FS_EKF_ACTION_LAND_EVEN_STABILIZE)) {
147  return;
148  }
149 
150  // take action based on fs_ekf_action parameter
151  switch (g.fs_ekf_action) {
153  // AltHold
154  if (failsafe.radio || !set_mode(ALT_HOLD, MODE_REASON_EKF_FAILSAFE)) {
155  set_mode_land_with_pause(MODE_REASON_EKF_FAILSAFE);
156  }
157  break;
158  case FS_EKF_ACTION_LAND:
160  default:
161  set_mode_land_with_pause(MODE_REASON_EKF_FAILSAFE);
162  break;
163  }
164 }
165 
166 // failsafe_ekf_off_event - actions to take when EKF failsafe is cleared
168 {
169  // return immediately if not in ekf failsafe
170  if (!failsafe.ekf) {
171  return;
172  }
173 
174  // clear flag and log recovery
175  failsafe.ekf = false;
177 }
178 
179 // check for ekf yaw reset and adjust target heading, also log position reset
181 {
182  // check for yaw reset
183  float yaw_angle_change_rad;
184  uint32_t new_ekfYawReset_ms = ahrs.getLastYawResetAngle(yaw_angle_change_rad);
185  if (new_ekfYawReset_ms != ekfYawReset_ms) {
186  attitude_control->inertial_frame_reset();
187  ekfYawReset_ms = new_ekfYawReset_ms;
188  Log_Write_Event(DATA_EKF_YAW_RESET);
189  }
190 
191 #if AP_AHRS_NAVEKF_AVAILABLE
192  // check for change in primary EKF (log only, AC_WPNav handles position target adjustment)
193  if ((EKF2.getPrimaryCoreIndex() != ekf_primary_core) && (EKF2.getPrimaryCoreIndex() != -1)) {
194  attitude_control->inertial_frame_reset();
195  ekf_primary_core = EKF2.getPrimaryCoreIndex();
196  Log_Write_Error(ERROR_SUBSYSTEM_EKF_PRIMARY, ekf_primary_core);
197  gcs().send_text(MAV_SEVERITY_WARNING, "EKF primary changed:%d", (unsigned)ekf_primary_core);
198  }
199 #endif
200 }
#define DATA_EKF_YAW_RESET
Definition: defines.h:382
uint8_t fail_count
Definition: ekf_check.cpp:22
#define ERROR_CODE_FAILSAFE_RESOLVED
Definition: defines.h:424
#define ERROR_CODE_FAILSAFE_OCCURRED
Definition: defines.h:425
AP_AHRS_NavEKF & ahrs
bool ekf_over_threshold()
Definition: ekf_check.cpp:90
#define ERROR_SUBSYSTEM_FAILSAFE_EKFINAV
Definition: defines.h:409
uint32_t last_warn_time
Definition: ekf_check.cpp:24
Definition: defines.h:100
#define EKF_CHECK_WARNING_TIME
Definition: ekf_check.cpp:15
GCS & gcs()
#define ERROR_SUBSYSTEM_EKFCHECK
Definition: defines.h:408
bool get_origin(Location &ret) const override
AP_MotorsMatrix motors(400)
uint32_t getLastYawResetAngle(float &yawAng) const override
void failsafe_ekf_event()
Definition: ekf_check.cpp:128
bool armed() const
#define ERROR_CODE_EKFCHECK_VARIANCE_CLEARED
Definition: defines.h:448
uint32_t millis()
bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const override
void failsafe_ekf_off_event(void)
Definition: ekf_check.cpp:167
void send_text(MAV_SEVERITY severity, const char *fmt,...)
float length(void) const
static struct @10 ekf_check_state
static struct notify_flags_and_values_type flags
void check_ekf_reset()
Definition: ekf_check.cpp:180
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
#define EKF_CHECK_ITERATIONS_MAX
Definition: ekf_check.cpp:11
#define ERROR_SUBSYSTEM_EKF_PRIMARY
Definition: defines.h:416
uint8_t bad_variance
Definition: ekf_check.cpp:23
void ekf_check()
Definition: ekf_check.cpp:29
#define FS_EKF_ACTION_ALTHOLD
Definition: defines.h:471
#define FS_EKF_ACTION_LAND
Definition: defines.h:470
#define FS_EKF_ACTION_LAND_EVEN_STABILIZE
Definition: defines.h:472
#define ERROR_CODE_EKFCHECK_BAD_VARIANCE
Definition: defines.h:447