APM:Libraries
AP_AHRS_NavEKF.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * NavEKF based AHRS (Attitude Heading Reference System) interface for
18  * ArduPilot
19  *
20  */
21 #include <AP_HAL/AP_HAL.h>
22 #include "AP_AHRS.h"
23 #include "AP_AHRS_View.h"
24 #include <AP_Vehicle/AP_Vehicle.h>
25 #include <GCS_MAVLink/GCS.h>
26 #include <AP_Module/AP_Module.h>
27 
28 #if AP_AHRS_NAVEKF_AVAILABLE
29 
30 extern const AP_HAL::HAL& hal;
31 
32 // constructor
34  NavEKF3 &_EKF3,
35  Flags flags) :
36  AP_AHRS_DCM(),
37  EKF2(_EKF2),
38  EKF3(_EKF3),
39  _ekf_flags(flags)
40 {
42 }
43 
44 // return the smoothed gyro vector corrected for drift
46 {
47  if (!active_EKF_type()) {
48  return AP_AHRS_DCM::get_gyro();
49  }
50  return _gyro_estimate;
51 }
52 
54 {
55  if (!active_EKF_type()) {
57  }
58  return _dcm_matrix;
59 }
60 
62 {
63  if (!active_EKF_type()) {
65  }
66  return _gyro_drift;
67 }
68 
69 // reset the current gyro drift estimate
70 // should be called if gyro offsets are recalculated
72 {
73  // update DCM
75 
76  // reset the EKF gyro bias states
79 }
80 
81 void AP_AHRS_NavEKF::update(bool skip_ins_update)
82 {
83  // drop back to normal priority if we were boosted by the INS
84  // calling delay_microseconds_boost()
85  hal.scheduler->boost_end();
86 
87  // EKF1 is no longer supported - handle case where it is selected
88  if (_ekf_type == 1) {
89  _ekf_type.set(2);
90  }
91 
92 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
93  update_SITL();
94 #endif
95 
96  update_DCM(skip_ins_update);
97  if (_ekf_type == 2) {
98  // if EK2 is primary then run EKF2 first to give it CPU
99  // priority
100  update_EKF2();
101  update_EKF3();
102  } else {
103  // otherwise run EKF3 first
104  update_EKF3();
105  update_EKF2();
106  }
107 
108 #if AP_MODULE_SUPPORTED
109  // call AHRS_update hook if any
110  AP_Module::call_hook_AHRS_update(*this);
111 #endif
112 
113  // push gyros if optical flow present
114  if (hal.opticalflow) {
115  const Vector3f &exported_gyro_bias = get_gyro_drift();
116  hal.opticalflow->push_gyro_bias(exported_gyro_bias.x, exported_gyro_bias.y);
117  }
118 
119  if (_view != nullptr) {
120  // update optional alternative attitude view
121  _view->update(skip_ins_update);
122  }
123 }
124 
125 void AP_AHRS_NavEKF::update_DCM(bool skip_ins_update)
126 {
127  // we need to restore the old DCM attitude values as these are
128  // used internally in DCM to calculate error values for gyro drift
129  // correction
130  roll = _dcm_attitude.x;
132  yaw = _dcm_attitude.z;
134 
135  AP_AHRS_DCM::update(skip_ins_update);
136 
137  // keep DCM attitude available for get_secondary_attitude()
139 }
140 
142 {
143  if (!_ekf2_started) {
144  // wait 1 second for DCM to output a valid tilt error estimate
145  if (start_time_ms == 0) {
147  }
150  if (_force_ekf) {
151  return;
152  }
153  }
154  }
155  if (_ekf2_started) {
156  EKF2.UpdateFilter();
157  if (active_EKF_type() == EKF_TYPE2) {
158  Vector3f eulers;
160  EKF2.getEulerAngles(-1,eulers);
161  roll = eulers.x;
162  pitch = eulers.y;
163  yaw = eulers.z;
164 
166  update_trig();
167 
168  // Use the primary EKF to select the primary gyro
169  const int8_t primary_imu = EKF2.getPrimaryCoreIMUIndex();
170 
171  const AP_InertialSensor &_ins = AP::ins();
172 
173  // get gyro bias for primary EKF and change sign to give gyro drift
174  // Note sign convention used by EKF is bias = measurement - truth
175  _gyro_drift.zero();
178 
179  // calculate corrected gyro estimate for get_gyro()
181  if (primary_imu == -1) {
182  // the primary IMU is undefined so use an uncorrected default value from the INS library
183  _gyro_estimate = _ins.get_gyro();
184  } else {
185  // use the same IMU as the primary EKF and correct for gyro drift
186  _gyro_estimate = _ins.get_gyro(primary_imu) + _gyro_drift;
187  }
188 
189  // get z accel bias estimate from active EKF (this is usually for the primary IMU)
190  float abias = 0;
191  EKF2.getAccelZBias(-1,abias);
192 
193  // This EKF is currently using primary_imu, and abias applies to only that IMU
194  for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
195  Vector3f accel = _ins.get_accel(i);
196  if (i == primary_imu) {
197  accel.z -= abias;
198  }
199  if (_ins.get_accel_health(i)) {
201  }
202  }
203  _accel_ef_ekf_blended = _accel_ef_ekf[primary_imu>=0?primary_imu:_ins.get_primary_accel()];
204  nav_filter_status filt_state;
205  EKF2.getFilterStatus(-1,filt_state);
206  AP_Notify::flags.gps_fusion = filt_state.flags.using_gps; // Drives AP_Notify flag for usable GPS.
209  }
210  }
211 }
212 
213 
215 {
216  if (!_ekf3_started) {
217  // wait 1 second for DCM to output a valid tilt error estimate
218  if (start_time_ms == 0) {
220  }
223  if (_force_ekf) {
224  return;
225  }
226  }
227  }
228  if (_ekf3_started) {
229  EKF3.UpdateFilter();
230  if (active_EKF_type() == EKF_TYPE3) {
231  Vector3f eulers;
233  EKF3.getEulerAngles(-1,eulers);
234  roll = eulers.x;
235  pitch = eulers.y;
236  yaw = eulers.z;
237 
239  update_trig();
240 
241  const AP_InertialSensor &_ins = AP::ins();
242 
243  // Use the primary EKF to select the primary gyro
244  const int8_t primary_imu = EKF3.getPrimaryCoreIMUIndex();
245 
246  // get gyro bias for primary EKF and change sign to give gyro drift
247  // Note sign convention used by EKF is bias = measurement - truth
248  _gyro_drift.zero();
251 
252  // calculate corrected gyro estimate for get_gyro()
254  if (primary_imu == -1) {
255  // the primary IMU is undefined so use an uncorrected default value from the INS library
256  _gyro_estimate = _ins.get_gyro();
257  } else {
258  // use the same IMU as the primary EKF and correct for gyro drift
259  _gyro_estimate = _ins.get_gyro(primary_imu) + _gyro_drift;
260  }
261 
262  // get 3-axis accel bias festimates for active EKF (this is usually for the primary IMU)
263  Vector3f abias;
264  EKF3.getAccelBias(-1,abias);
265 
266  // This EKF uses the primary IMU
267  // Eventually we will run a separate instance of the EKF for each IMU and do the selection and blending of EKF outputs upstream
268  // update _accel_ef_ekf
269  for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
270  Vector3f accel = _ins.get_accel(i);
271  if (i==_ins.get_primary_accel()) {
272  accel -= abias;
273  }
274  if (_ins.get_accel_health(i)) {
275  _accel_ef_ekf[i] = _dcm_matrix * accel;
276  }
277  }
279  nav_filter_status filt_state;
280  EKF3.getFilterStatus(-1,filt_state);
281  AP_Notify::flags.gps_fusion = filt_state.flags.using_gps; // Drives AP_Notify flag for usable GPS.
284  }
285  }
286 }
287 
288 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
290 {
291  if (_sitl == nullptr) {
293  if (_sitl == nullptr) {
294  return;
295  }
296  }
297 
298  const struct SITL::sitl_fdm &fdm = _sitl->state;
299 
300  if (active_EKF_type() == EKF_TYPE_SITL) {
301  roll = radians(fdm.rollDeg);
302  pitch = radians(fdm.pitchDeg);
303  yaw = radians(fdm.yawDeg);
304 
306 
308  update_trig();
309 
310  _gyro_drift.zero();
311 
313  radians(fdm.pitchRate),
314  radians(fdm.yawRate));
315 
316  for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
317  const Vector3f accel(fdm.xAccel,
318  fdm.yAccel,
319  fdm.zAccel);
321  }
323 
324  }
325 
326  if (_sitl->odom_enable) {
327  // use SITL states to write body frame odometry data at 20Hz
328  uint32_t timeStamp_ms = AP_HAL::millis();
329  if (timeStamp_ms - _last_body_odm_update_ms > 50) {
330  const float quality = 100.0f;
331  const Vector3f posOffset(0.0f, 0.0f, 0.0f);
332  const float delTime = 0.001f * (timeStamp_ms - _last_body_odm_update_ms);
333  _last_body_odm_update_ms = timeStamp_ms;
334  timeStamp_ms -= (timeStamp_ms - _last_body_odm_update_ms)/2; // correct for first order hold average delay
335  Vector3f delAng(radians(fdm.rollRate),
336  radians(fdm.pitchRate),
337  radians(fdm.yawRate));
338  delAng *= delTime;
339  // rotate earth velocity into body frame and calculate delta position
340  Matrix3f Tbn;
342  const Vector3f earth_vel(fdm.speedN,fdm.speedE,fdm.speedD);
343  const Vector3f delPos = Tbn.transposed() * (earth_vel * delTime);
344  // write to EKF
345  EKF3.writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, posOffset);
346  }
347  }
348 }
349 #endif // CONFIG_HAL_BOARD
350 
351 // accelerometer values in the earth frame in m/s/s
352 const Vector3f &AP_AHRS_NavEKF::get_accel_ef(uint8_t i) const
353 {
354  if (active_EKF_type() == EKF_TYPE_NONE) {
355  return AP_AHRS_DCM::get_accel_ef(i);
356  }
357  return _accel_ef_ekf[i];
358 }
359 
360 // blended accelerometer values in the earth frame in m/s/s
362 {
363  if (active_EKF_type() == EKF_TYPE_NONE) {
365  }
366  return _accel_ef_ekf_blended;
367 }
368 
369 void AP_AHRS_NavEKF::reset(bool recover_eulers)
370 {
371  AP_AHRS_DCM::reset(recover_eulers);
373  if (_ekf2_started) {
375  }
376  if (_ekf3_started) {
378  }
379 }
380 
381 // reset the current attitude, used on new IMU calibration
382 void AP_AHRS_NavEKF::reset_attitude(const float &_roll, const float &_pitch, const float &_yaw)
383 {
384  AP_AHRS_DCM::reset_attitude(_roll, _pitch, _yaw);
386  if (_ekf2_started) {
388  }
389  if (_ekf3_started) {
391  }
392 }
393 
394 // dead-reckoning support
395 bool AP_AHRS_NavEKF::get_position(struct Location &loc) const
396 {
397  Vector3f ned_pos;
398  Location origin;
399  switch (active_EKF_type()) {
400  case EKF_TYPE_NONE:
401  return AP_AHRS_DCM::get_position(loc);
402 
403  case EKF_TYPE2:
404  if (EKF2.getLLH(loc) && EKF2.getPosD(-1,ned_pos.z) && EKF2.getOriginLLH(-1,origin)) {
405  // fixup altitude using relative position from EKF origin
406  loc.alt = origin.alt - ned_pos.z*100;
407  return true;
408  }
409  break;
410 
411  case EKF_TYPE3:
412  if (EKF3.getLLH(loc) && EKF3.getPosD(-1,ned_pos.z) && EKF3.getOriginLLH(-1,origin)) {
413  // fixup altitude using relative position from EKF origin
414  loc.alt = origin.alt - ned_pos.z*100;
415  return true;
416  }
417  break;
418 
419 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
420  case EKF_TYPE_SITL: {
421  const struct SITL::sitl_fdm &fdm = _sitl->state;
422  memset(&loc, 0, sizeof(loc));
423  loc.lat = fdm.latitude * 1e7;
424  loc.lng = fdm.longitude * 1e7;
425  loc.alt = fdm.altitude*100;
426  return true;
427  }
428 #endif
429 
430  default:
431  break;
432  }
433  return AP_AHRS_DCM::get_position(loc);
434 }
435 
436 // status reporting of estimated errors
438 {
439  return AP_AHRS_DCM::get_error_rp();
440 }
441 
443 {
445 }
446 
447 // return a wind estimation vector, in m/s
449 {
450  Vector3f wind;
451  switch (active_EKF_type()) {
452  case EKF_TYPE_NONE:
454  break;
455 
456 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
457  case EKF_TYPE_SITL:
458  wind.zero();
459  break;
460 #endif
461 
462  case EKF_TYPE2:
463  EKF2.getWind(-1,wind);
464  break;
465 
466  case EKF_TYPE3:
467  EKF3.getWind(-1,wind);
468  break;
469 
470  }
471  return wind;
472 }
473 
474 // return an airspeed estimate if available. return true
475 // if we have an estimate
476 bool AP_AHRS_NavEKF::airspeed_estimate(float *airspeed_ret) const
477 {
478  return AP_AHRS_DCM::airspeed_estimate(airspeed_ret);
479 }
480 
481 // true if compass is being used
483 {
484  switch (active_EKF_type()) {
485  case EKF_TYPE_NONE:
486  break;
487  case EKF_TYPE2:
488  return EKF2.use_compass();
489 
490  case EKF_TYPE3:
491  return EKF3.use_compass();
492 
493 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
494  case EKF_TYPE_SITL:
495  return true;
496 #endif
497  }
498  return AP_AHRS_DCM::use_compass();
499 }
500 
501 
502 // return secondary attitude solution if available, as eulers in radians
504 {
505  switch (active_EKF_type()) {
506  case EKF_TYPE_NONE:
507  // EKF is secondary
508  EKF2.getEulerAngles(-1, eulers);
509  return _ekf2_started;
510 
511  case EKF_TYPE2:
512 
513  case EKF_TYPE3:
514 
515  default:
516  // DCM is secondary
517  eulers = _dcm_attitude;
518  return true;
519  }
520 }
521 
522 
523 // return secondary attitude solution if available, as quaternion
525 {
526  switch (active_EKF_type()) {
527  case EKF_TYPE_NONE:
528  // EKF is secondary
529  EKF2.getQuaternion(-1, quat);
530  return _ekf2_started;
531 
532  case EKF_TYPE2:
533 
534  case EKF_TYPE3:
535 
536  default:
537  // DCM is secondary
539  return true;
540  }
541 }
542 
543 // return secondary position solution if available
545 {
546  switch (active_EKF_type()) {
547  case EKF_TYPE_NONE:
548  // EKF is secondary
549  EKF2.getLLH(loc);
550  return _ekf2_started;
551 
552  case EKF_TYPE2:
553 
554  case EKF_TYPE3:
555 
556  default:
557  // return DCM position
559  return true;
560  }
561 }
562 
563 // EKF has a better ground speed vector estimate
565 {
566  Vector3f vec;
567 
568  switch (active_EKF_type()) {
569  case EKF_TYPE_NONE:
571 
572  case EKF_TYPE2:
573  default:
574  EKF2.getVelNED(-1,vec);
575  return Vector2f(vec.x, vec.y);
576 
577  case EKF_TYPE3:
578  EKF3.getVelNED(-1,vec);
579  return Vector2f(vec.x, vec.y);
580 
581 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
582  case EKF_TYPE_SITL: {
583  const struct SITL::sitl_fdm &fdm = _sitl->state;
584  return Vector2f(fdm.speedN, fdm.speedE);
585  }
586 #endif
587  }
588 }
589 
590 // set the EKF's origin location in 10e7 degrees. This should only
591 // be called when the EKF has no absolute position reference (i.e. GPS)
592 // from which to decide the origin on its own
594 {
595  const bool ret2 = EKF2.setOriginLLH(loc);
596  const bool ret3 = EKF3.setOriginLLH(loc);
597 
598  // return success if active EKF's origin was set
599  switch (active_EKF_type()) {
600  case EKF_TYPE2:
601  return ret2;
602 
603  case EKF_TYPE3:
604  return ret3;
605 
606 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
607  case EKF_TYPE_SITL: {
608  struct SITL::sitl_fdm &fdm = _sitl->state;
609  fdm.home = loc;
610  return true;
611  }
612 #endif
613 
614  default:
615  return false;
616  }
617 }
618 
619 // return true if inertial navigation is active
621 {
622  return active_EKF_type() != EKF_TYPE_NONE;
623 }
624 
625 // return a ground velocity in meters/second, North/East/Down
626 // order. Must only be called if have_inertial_nav() is true
628 {
629  switch (active_EKF_type()) {
630  case EKF_TYPE_NONE:
631  return false;
632 
633  case EKF_TYPE2:
634  default:
635  EKF2.getVelNED(-1,vec);
636  return true;
637 
638  case EKF_TYPE3:
639  EKF3.getVelNED(-1,vec);
640  return true;
641 
642 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
643  case EKF_TYPE_SITL:
644  const struct SITL::sitl_fdm &fdm = _sitl->state;
645  vec = Vector3f(fdm.speedN, fdm.speedE, fdm.speedD);
646  return true;
647 #endif
648  }
649 }
650 
651 // returns the expected NED magnetic field
653 {
654  switch (active_EKF_type()) {
655  case EKF_TYPE_NONE:
656  return false;
657 
658  case EKF_TYPE2:
659  default:
660  EKF2.getMagNED(-1,vec);
661  return true;
662 
663  case EKF_TYPE3:
664  EKF3.getMagNED(-1,vec);
665  return true;
666 
667 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
668  case EKF_TYPE_SITL:
669  return false;
670 #endif
671  }
672 }
673 
674 // returns the estimated magnetic field offsets in body frame
676 {
677  switch (active_EKF_type()) {
678  case EKF_TYPE_NONE:
679  return false;
680 
681  case EKF_TYPE2:
682  default:
683  EKF2.getMagXYZ(-1,vec);
684  return true;
685 
686  case EKF_TYPE3:
687  EKF3.getMagXYZ(-1,vec);
688  return true;
689 
690 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
691  case EKF_TYPE_SITL:
692  return false;
693 #endif
694  }
695 }
696 
697 // Get a derivative of the vertical position which is kinematically consistent with the vertical position is required by some control loops.
698 // This is different to the vertical velocity from the EKF which is not always consistent with the verical position due to the various errors that are being corrected for.
699 bool AP_AHRS_NavEKF::get_vert_pos_rate(float &velocity) const
700 {
701  switch (active_EKF_type()) {
702  case EKF_TYPE_NONE:
703  return false;
704 
705  case EKF_TYPE2:
706  default:
707  velocity = EKF2.getPosDownDerivative(-1);
708  return true;
709 
710  case EKF_TYPE3:
711  velocity = EKF3.getPosDownDerivative(-1);
712  return true;
713 
714 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
715  case EKF_TYPE_SITL: {
716  const struct SITL::sitl_fdm &fdm = _sitl->state;
717  velocity = fdm.speedD;
718  return true;
719  }
720 #endif
721  }
722 }
723 
724 // get latest height above ground level estimate in metres and a validity flag
725 bool AP_AHRS_NavEKF::get_hagl(float &height) const
726 {
727  switch (active_EKF_type()) {
728  case EKF_TYPE_NONE:
729  return false;
730 
731  case EKF_TYPE2:
732  default:
733  return EKF2.getHAGL(height);
734 
735  case EKF_TYPE3:
736  return EKF3.getHAGL(height);
737 
738 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
739  case EKF_TYPE_SITL: {
740  const struct SITL::sitl_fdm &fdm = _sitl->state;
741  height = fdm.altitude - get_home().alt*0.01f;
742  return true;
743  }
744 #endif
745  }
746 }
747 
748 // return a relative ground position to the origin in meters
749 // North/East/Down order.
751 {
752  switch (active_EKF_type()) {
753  case EKF_TYPE_NONE:
754  return false;
755 
756  case EKF_TYPE2:
757  default: {
758  Vector2f posNE;
759  float posD;
760  if (EKF2.getPosNE(-1,posNE) && EKF2.getPosD(-1,posD)) {
761  // position is valid
762  vec.x = posNE.x;
763  vec.y = posNE.y;
764  vec.z = posD;
765  return true;
766  }
767  return false;
768  }
769 
770  case EKF_TYPE3: {
771  Vector2f posNE;
772  float posD;
773  if (EKF3.getPosNE(-1,posNE) && EKF3.getPosD(-1,posD)) {
774  // position is valid
775  vec.x = posNE.x;
776  vec.y = posNE.y;
777  vec.z = posD;
778  return true;
779  }
780  return false;
781  }
782 
783 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
784  case EKF_TYPE_SITL: {
785  Location loc;
786  get_position(loc);
787  const Vector2f diff2d = location_diff(get_home(), loc);
788  const struct SITL::sitl_fdm &fdm = _sitl->state;
789  vec = Vector3f(diff2d.x, diff2d.y,
790  -(fdm.altitude - get_home().alt*0.01f));
791  return true;
792  }
793 #endif
794  }
795 }
796 
797 // return a relative ground position to the home in meters
798 // North/East/Down order.
800 {
801  Location originLLH;
802  Vector3f originNED;
803  if (!get_relative_position_NED_origin(originNED) ||
804  !get_origin(originLLH)) {
805  return false;
806  }
807 
808  const Vector3f offset = location_3d_diff_NED(originLLH, _home);
809 
810  vec.x = originNED.x - offset.x;
811  vec.y = originNED.y - offset.y;
812  vec.z = originNED.z - offset.z;
813  return true;
814 }
815 
816 // write a relative ground position estimate to the origin in meters, North/East order
817 // return true if estimate is valid
819 {
820  switch (active_EKF_type()) {
821  case EKF_TYPE_NONE:
822  return false;
823 
824  case EKF_TYPE2:
825  default: {
826  bool position_is_valid = EKF2.getPosNE(-1,posNE);
827  return position_is_valid;
828  }
829 
830  case EKF_TYPE3: {
831  bool position_is_valid = EKF3.getPosNE(-1,posNE);
832  return position_is_valid;
833  }
834 
835 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
836  case EKF_TYPE_SITL: {
837  Location loc;
838  get_position(loc);
839  posNE = location_diff(get_home(), loc);
840  return true;
841  }
842 #endif
843  }
844 }
845 
846 // return a relative ground position to the home in meters
847 // North/East order.
849 {
850  Location originLLH;
851  Vector2f originNE;
852  if (!get_relative_position_NE_origin(originNE) ||
853  !get_origin(originLLH)) {
854  return false;
855  }
856 
857  const Vector2f offset = location_diff(originLLH, _home);
858 
859  posNE.x = originNE.x - offset.x;
860  posNE.y = originNE.y - offset.y;
861  return true;
862 }
863 
864 // write a relative ground position estimate to the origin in meters, North/East order
865 
866 
867 // write a relative ground position to the origin in meters, Down
868 // return true if the estimate is valid
870 {
871  switch (active_EKF_type()) {
872  case EKF_TYPE_NONE:
873  return false;
874 
875  case EKF_TYPE2:
876  default: {
877  bool position_is_valid = EKF2.getPosD(-1,posD);
878  return position_is_valid;
879  }
880 
881  case EKF_TYPE3: {
882  bool position_is_valid = EKF3.getPosD(-1,posD);
883  return position_is_valid;
884  }
885 
886 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
887  case EKF_TYPE_SITL: {
888  const struct SITL::sitl_fdm &fdm = _sitl->state;
889  posD = -(fdm.altitude - get_home().alt*0.01f);
890  return true;
891  }
892 #endif
893  }
894 }
895 
896 // write a relative ground position to home in meters, Down
897 // will use the barometer if the EKF isn't available
899 {
900  Location originLLH;
901  float originD;
902  if (!get_relative_position_D_origin(originD) ||
903  !get_origin(originLLH)) {
904  posD = -AP::baro().get_altitude();
905  return;
906  }
907 
908  posD = originD - ((originLLH.alt - _home.alt) * 0.01f);
909  return;
910 }
911 /*
912  canonicalise _ekf_type, forcing it to be 0, 2 or 3
913  type 1 has been deprecated
914  */
915 uint8_t AP_AHRS_NavEKF::ekf_type(void) const
916 {
917  uint8_t type = _ekf_type;
918 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
919  if (type == EKF_TYPE_SITL) {
920  return type;
921  }
922 #endif
923  if ((always_use_EKF() && (type == 0)) || (type == 1) || (type > 3)) {
924  type = 2;
925  }
926  return type;
927 }
928 
930 {
931  EKF_TYPE ret = EKF_TYPE_NONE;
932 
933  switch (ekf_type()) {
934  case 0:
935  return EKF_TYPE_NONE;
936 
937  case 2: {
938  // do we have an EKF2 yet?
939  if (!_ekf2_started) {
940  return EKF_TYPE_NONE;
941  }
942  if (always_use_EKF()) {
943  uint16_t ekf2_faults;
944  EKF2.getFilterFaults(-1,ekf2_faults);
945  if (ekf2_faults == 0) {
946  ret = EKF_TYPE2;
947  }
948  } else if (EKF2.healthy()) {
949  ret = EKF_TYPE2;
950  }
951  break;
952  }
953 
954  case 3: {
955  // do we have an EKF3 yet?
956  if (!_ekf3_started) {
957  return EKF_TYPE_NONE;
958  }
959  if (always_use_EKF()) {
960  uint16_t ekf3_faults;
961  EKF3.getFilterFaults(-1,ekf3_faults);
962  if (ekf3_faults == 0) {
963  ret = EKF_TYPE3;
964  }
965  } else if (EKF3.healthy()) {
966  ret = EKF_TYPE3;
967  }
968  break;
969  }
970 
971 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
972  case EKF_TYPE_SITL:
973  ret = EKF_TYPE_SITL;
974  break;
975 #endif
976  }
977 
978  /*
979  fixed wing and rover when in fly_forward mode will fall back to
980  DCM if the EKF doesn't have GPS. This is the safest option as
981  DCM is very robust. Note that we also check the filter status
982  when fly_forward is false and we are disarmed. This is to ensure
983  that the arming checks do wait for good GPS position on fixed
984  wing and rover
985  */
986  if (ret != EKF_TYPE_NONE &&
989  (_flags.fly_forward || !hal.util->get_soft_armed())) {
990  nav_filter_status filt_state;
991  if (ret == EKF_TYPE2) {
992  EKF2.getFilterStatus(-1,filt_state);
993  } else if (ret == EKF_TYPE3) {
994  EKF3.getFilterStatus(-1,filt_state);
995 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
996  } else if (ret == EKF_TYPE_SITL) {
997  get_filter_status(filt_state);
998 #endif
999  }
1000  if (hal.util->get_soft_armed() && !filt_state.flags.using_gps && AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
1001  // if the EKF is not fusing GPS and we have a 3D lock, then
1002  // plane and rover would prefer to use the GPS position from
1003  // DCM. This is a safety net while some issues with the EKF
1004  // get sorted out
1005  return EKF_TYPE_NONE;
1006  }
1007  if (hal.util->get_soft_armed() && filt_state.flags.const_pos_mode) {
1008  return EKF_TYPE_NONE;
1009  }
1010  if (!filt_state.flags.attitude ||
1011  !filt_state.flags.vert_vel ||
1012  !filt_state.flags.vert_pos) {
1013  return EKF_TYPE_NONE;
1014  }
1015  if (!filt_state.flags.horiz_vel ||
1016  (!filt_state.flags.horiz_pos_abs && !filt_state.flags.horiz_pos_rel)) {
1017  if ((!_compass || !_compass->use_for_yaw()) &&
1019  AP::gps().ground_speed() < 2) {
1020  /*
1021  special handling for non-compass mode when sitting
1022  still. The EKF may not yet have aligned its yaw. We
1023  accept EKF as healthy to allow arming. Once we reach
1024  speed the EKF should get yaw alignment
1025  */
1026  if (filt_state.flags.pred_horiz_pos_abs &&
1027  filt_state.flags.pred_horiz_pos_rel) {
1028  return ret;
1029  }
1030  }
1031  return EKF_TYPE_NONE;
1032  }
1033  }
1034  return ret;
1035 }
1036 
1037 /*
1038  check if the AHRS subsystem is healthy
1039 */
1040 bool AP_AHRS_NavEKF::healthy(void) const
1041 {
1042  // If EKF is started we switch away if it reports unhealthy. This could be due to bad
1043  // sensor data. If EKF reversion is inhibited, we only switch across if the EKF encounters
1044  // an internal processing error, but not for bad sensor data.
1045  switch (ekf_type()) {
1046  case 0:
1047  return AP_AHRS_DCM::healthy();
1048 
1049  case 2: {
1050  bool ret = _ekf2_started && EKF2.healthy();
1051  if (!ret) {
1052  return false;
1053  }
1056  active_EKF_type() != EKF_TYPE2) {
1057  // on fixed wing we want to be using EKF to be considered
1058  // healthy if EKF is enabled
1059  return false;
1060  }
1061  return true;
1062  }
1063 
1064  case 3: {
1065  bool ret = _ekf3_started && EKF3.healthy();
1066  if (!ret) {
1067  return false;
1068  }
1071  active_EKF_type() != EKF_TYPE3) {
1072  // on fixed wing we want to be using EKF to be considered
1073  // healthy if EKF is enabled
1074  return false;
1075  }
1076  return true;
1077  }
1078 
1079 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1080  case EKF_TYPE_SITL:
1081  return true;
1082 #endif
1083  }
1084 
1085  return AP_AHRS_DCM::healthy();
1086 }
1087 
1089 {
1090  _ekf_type.set(setting?1:0);
1091 }
1092 
1093 // true if the AHRS has completed initialisation
1095 {
1096  switch (ekf_type()) {
1097  case 0:
1098  return true;
1099 
1100  case 2:
1101  default:
1102  // initialisation complete 10sec after ekf has started
1104 
1105  case 3:
1106  // initialisation complete 10sec after ekf has started
1108 
1109 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1110  case EKF_TYPE_SITL:
1111  return true;
1112 #endif
1113  }
1114 };
1115 
1116 // get_filter_status : returns filter status as a series of flags
1118 {
1119  switch (ekf_type()) {
1120  case EKF_TYPE_NONE:
1121  return false;
1122 
1123  case EKF_TYPE2:
1124  default:
1125  EKF2.getFilterStatus(-1,status);
1126  return true;
1127 
1128  case EKF_TYPE3:
1129  EKF3.getFilterStatus(-1,status);
1130  return true;
1131 
1132 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1133  case EKF_TYPE_SITL:
1134  memset(&status, 0, sizeof(status));
1135  status.flags.attitude = 1;
1136  status.flags.horiz_vel = 1;
1137  status.flags.vert_vel = 1;
1138  status.flags.horiz_pos_rel = 1;
1139  status.flags.horiz_pos_abs = 1;
1140  status.flags.vert_pos = 1;
1141  status.flags.pred_horiz_pos_rel = 1;
1142  status.flags.pred_horiz_pos_abs = 1;
1143  status.flags.using_gps = 1;
1144  return true;
1145 #endif
1146  }
1147 
1148 }
1149 
1150 // write optical flow data to EKF
1151 void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
1152 {
1153  EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
1154  EKF3.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset);
1155 }
1156 
1157 // write body frame odometry measurements to the EKF
1158 void AP_AHRS_NavEKF::writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)
1159 {
1160  EKF3.writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, posOffset);
1161 }
1162 
1163 // Write position and quaternion data from an external navigation system
1164 void AP_AHRS_NavEKF::writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
1165 {
1166  EKF2.writeExtNavData(sensOffset, pos, quat, posErr, angErr, timeStamp_ms, resetTime_ms);
1167 }
1168 
1169 
1170 // inhibit GPS usage
1172 {
1173  switch (ekf_type()) {
1174  case 0:
1175 
1176  case 2:
1177  default:
1178  return EKF2.setInhibitGPS();
1179 
1180  case 3:
1181  return EKF3.setInhibitGPS();
1182 
1183 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1184  case EKF_TYPE_SITL:
1185  return false;
1186 #endif
1187  }
1188 }
1189 
1190 // get speed limit
1191 void AP_AHRS_NavEKF::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
1192 {
1193  switch (ekf_type()) {
1194  case 0:
1195 
1196  case 2:
1197  EKF2.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);
1198  break;
1199 
1200  case 3:
1201  EKF3.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);
1202  break;
1203 
1204 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1205  case EKF_TYPE_SITL:
1206  // same as EKF2 for no optical flow
1207  ekfGndSpdLimit = 400.0f;
1208  ekfNavVelGainScaler = 1.0f;
1209  break;
1210 #endif
1211  }
1212 }
1213 
1214 // get compass offset estimates
1215 // true if offsets are valid
1216 bool AP_AHRS_NavEKF::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
1217 {
1218  switch (ekf_type()) {
1219  case 0:
1220 
1221  case 2:
1222  default:
1223  return EKF2.getMagOffsets(mag_idx, magOffsets);
1224 
1225  case 3:
1226  return EKF3.getMagOffsets(mag_idx, magOffsets);
1227 
1228 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1229  case EKF_TYPE_SITL:
1230  magOffsets.zero();
1231  return true;
1232 #endif
1233  }
1234 }
1235 
1236 // Retrieves the NED delta velocity corrected
1238 {
1239  const EKF_TYPE type = active_EKF_type();
1240  if (type == EKF_TYPE2 || type == EKF_TYPE3) {
1241  int8_t imu_idx = 0;
1242  Vector3f accel_bias;
1243  if (type == EKF_TYPE2) {
1244  accel_bias.zero();
1245  imu_idx = EKF2.getPrimaryCoreIMUIndex();
1246  EKF2.getAccelZBias(-1,accel_bias.z);
1247  } else if (type == EKF_TYPE3) {
1248  imu_idx = EKF3.getPrimaryCoreIMUIndex();
1249  EKF3.getAccelBias(-1,accel_bias);
1250  }
1251  if (imu_idx == -1) {
1252  // should never happen, call parent implementation in this scenario
1254  return;
1255  }
1256  ret.zero();
1257  const AP_InertialSensor &_ins = AP::ins();
1258  _ins.get_delta_velocity((uint8_t)imu_idx, ret);
1259  dt = _ins.get_delta_velocity_dt((uint8_t)imu_idx);
1260  ret -= accel_bias*dt;
1262  ret.z += GRAVITY_MSS*dt;
1263  } else {
1265  }
1266 }
1267 
1268 // report any reason for why the backend is refusing to initialise
1270 {
1271  switch (ekf_type()) {
1272  case 0:
1273  return nullptr;
1274 
1275  case 2:
1276  default:
1277  return EKF2.prearm_failure_reason();
1278 
1279  case 3:
1280  return EKF3.prearm_failure_reason();
1281 
1282  }
1283  return nullptr;
1284 }
1285 
1286 // return the amount of yaw angle change due to the last yaw angle reset in radians
1287 // returns the time of the last yaw angle reset or 0 if no reset has ever occurred
1288 uint32_t AP_AHRS_NavEKF::getLastYawResetAngle(float &yawAng) const
1289 {
1290  switch (ekf_type()) {
1291 
1292  case 2:
1293  default:
1294  return EKF2.getLastYawResetAngle(yawAng);
1295 
1296  case 3:
1297  return EKF3.getLastYawResetAngle(yawAng);
1298 
1299 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1300  case EKF_TYPE_SITL:
1301  return 0;
1302 #endif
1303  }
1304  return 0;
1305 }
1306 
1307 // return the amount of NE position change in metres due to the last reset
1308 // returns the time of the last reset or 0 if no reset has ever occurred
1310 {
1311  switch (ekf_type()) {
1312 
1313  case 2:
1314  default:
1315  return EKF2.getLastPosNorthEastReset(pos);
1316 
1317  case 3:
1318  return EKF3.getLastPosNorthEastReset(pos);
1319 
1320 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1321  case EKF_TYPE_SITL:
1322  return 0;
1323 #endif
1324  }
1325  return 0;
1326 }
1327 
1328 // return the amount of NE velocity change in metres/sec due to the last reset
1329 // returns the time of the last reset or 0 if no reset has ever occurred
1331 {
1332  switch (ekf_type()) {
1333 
1334  case 2:
1335  default:
1336  return EKF2.getLastVelNorthEastReset(vel);
1337 
1338  case 3:
1339  return EKF3.getLastVelNorthEastReset(vel);
1340 
1341 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1342  case EKF_TYPE_SITL:
1343  return 0;
1344 #endif
1345  }
1346  return 0;
1347 }
1348 
1349 
1350 // return the amount of vertical position change due to the last reset in meters
1351 // returns the time of the last reset or 0 if no reset has ever occurred
1352 uint32_t AP_AHRS_NavEKF::getLastPosDownReset(float &posDelta) const
1353 {
1354  switch (ekf_type()) {
1355  case EKF_TYPE2:
1356  return EKF2.getLastPosDownReset(posDelta);
1357 
1358  case EKF_TYPE3:
1359  return EKF3.getLastPosDownReset(posDelta);
1360 
1361 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1362  case EKF_TYPE_SITL:
1363  return 0;
1364 #endif
1365  }
1366  return 0;
1367 }
1368 
1369 // Resets the baro so that it reads zero at the current height
1370 // Resets the EKF height to zero
1371 // Adjusts the EKf origin height so that the EKF height + origin height is the same as before
1372 // Returns true if the height datum reset has been performed
1373 // If using a range finder for height no reset is performed and it returns false
1375 {
1376  switch (ekf_type()) {
1377 
1378  case 2:
1379  default: {
1381  return EKF2.resetHeightDatum();
1382  }
1383 
1384  case 3: {
1386  return EKF3.resetHeightDatum();
1387  }
1388 
1389 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1390  case EKF_TYPE_SITL:
1391  return false;
1392 #endif
1393  }
1394  return false;
1395 }
1396 
1397 // send a EKF_STATUS_REPORT for current EKF
1398 void AP_AHRS_NavEKF::send_ekf_status_report(mavlink_channel_t chan) const
1399 {
1400  switch (ekf_type()) {
1401  case EKF_TYPE_NONE:
1402  // send zero status report
1403  mavlink_msg_ekf_status_report_send(chan, 0, 0, 0, 0, 0, 0, 0);
1404  break;
1405 
1406 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1407  case EKF_TYPE_SITL:
1408  // send zero status report
1409  mavlink_msg_ekf_status_report_send(chan, 0, 0, 0, 0, 0, 0, 0);
1410  break;
1411 #endif
1412 
1413  case EKF_TYPE2:
1414  return EKF2.send_status_report(chan);
1415 
1416  case EKF_TYPE3:
1417  return EKF3.send_status_report(chan);
1418 
1419  }
1420 }
1421 
1422 // passes a reference to the location of the inertial navigation origin
1423 // in WGS-84 coordinates
1424 // returns a boolean true when the inertial navigation origin has been set
1426 {
1427  switch (ekf_type()) {
1428  case EKF_TYPE_NONE:
1429  return false;
1430 
1431  case EKF_TYPE2:
1432  default:
1433  if (!EKF2.getOriginLLH(-1,ret)) {
1434  return false;
1435  }
1436  return true;
1437 
1438  case EKF_TYPE3:
1439  if (!EKF3.getOriginLLH(-1,ret)) {
1440  return false;
1441  }
1442  return true;
1443 
1444 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1445  case EKF_TYPE_SITL:
1446  const struct SITL::sitl_fdm &fdm = _sitl->state;
1447  ret = fdm.home;
1448  return true;
1449 #endif
1450  }
1451 }
1452 
1453 // get_hgt_ctrl_limit - get maximum height to be observed by the control loops in metres and a validity flag
1454 // this is used to limit height during optical flow navigation
1455 // it will return false when no limiting is required
1456 bool AP_AHRS_NavEKF::get_hgt_ctrl_limit(float& limit) const
1457 {
1458  switch (ekf_type()) {
1459  case EKF_TYPE_NONE:
1460  // We are not using an EKF so no limiting applies
1461  return false;
1462 
1463  case EKF_TYPE2:
1464  default:
1465  return EKF2.getHeightControlLimit(limit);
1466 
1467  case EKF_TYPE3:
1468  return EKF3.getHeightControlLimit(limit);
1469 
1470 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1471  case EKF_TYPE_SITL:
1472  return false;
1473 #endif
1474  }
1475 }
1476 
1477 // get_location - updates the provided location with the latest calculated location
1478 // returns true on success (i.e. the EKF knows it's latest position), false on failure
1480 {
1481  switch (ekf_type()) {
1482  case EKF_TYPE_NONE:
1483  // We are not using an EKF so no data
1484  return false;
1485 
1486  case EKF_TYPE2:
1487  default:
1488  return EKF2.getLLH(loc);
1489 
1490  case EKF_TYPE3:
1491  return EKF3.getLLH(loc);
1492 
1493 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1494  case EKF_TYPE_SITL:
1495  return get_position(loc);
1496 #endif
1497  }
1498 }
1499 
1500 // get_variances - provides the innovations normalised using the innovation variance where a value of 0
1501 // indicates prefect consistency between the measurement and the EKF solution and a value of of 1 is the maximum
1502 // inconsistency that will be accpeted by the filter
1503 // boolean false is returned if variances are not available
1504 bool AP_AHRS_NavEKF::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
1505 {
1506  switch (ekf_type()) {
1507  case EKF_TYPE_NONE:
1508  // We are not using an EKF so no data
1509  return false;
1510 
1511  case EKF_TYPE2:
1512  default:
1513  // use EKF to get variance
1514  EKF2.getVariances(-1,velVar, posVar, hgtVar, magVar, tasVar, offset);
1515  return true;
1516 
1517  case EKF_TYPE3:
1518  // use EKF to get variance
1519  EKF3.getVariances(-1,velVar, posVar, hgtVar, magVar, tasVar, offset);
1520  return true;
1521 
1522 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1523  case EKF_TYPE_SITL:
1524  velVar = 0;
1525  posVar = 0;
1526  hgtVar = 0;
1527  magVar.zero();
1528  tasVar = 0;
1529  offset.zero();
1530  return true;
1531 #endif
1532  }
1533 }
1534 
1536 {
1537  switch (ekf_type()) {
1538  case EKF_TYPE2:
1539  default:
1540  EKF2.setTakeoffExpected(val);
1541  break;
1542 
1543  case EKF_TYPE3:
1544  EKF3.setTakeoffExpected(val);
1545  break;
1546 
1547 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1548  case EKF_TYPE_SITL:
1549  break;
1550 #endif
1551  }
1552 }
1553 
1555 {
1556  switch (ekf_type()) {
1557  case EKF_TYPE2:
1558  default:
1560  break;
1561 
1562  case EKF_TYPE3:
1564  break;
1565 
1566 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
1567  case EKF_TYPE_SITL:
1568  break;
1569 #endif
1570  }
1571 }
1572 
1574 {
1575  nav_filter_status ekf_status {};
1576  if (!get_filter_status(ekf_status)) {
1577  return false;
1578  }
1579  return ekf_status.flags.gps_glitching;
1580 }
1581 
1582 // is the EKF backend doing its own sensor logging?
1584 {
1585  switch (ekf_type()) {
1586  case 2:
1587  return EKF2.have_ekf_logging();
1588 
1589  case 3:
1590  return EKF3.have_ekf_logging();
1591 
1592  default:
1593  break;
1594  }
1595  return false;
1596 }
1597 
1598 // get the index of the current primary IMU
1600 {
1601  int8_t imu = -1;
1602  switch (ekf_type()) {
1603  case 2:
1604  // let EKF2 choose primary IMU
1605  imu = EKF2.getPrimaryCoreIMUIndex();
1606  break;
1607  case 3:
1608  // let EKF2 choose primary IMU
1609  imu = EKF3.getPrimaryCoreIMUIndex();
1610  break;
1611  default:
1612  break;
1613  }
1614  if (imu == -1) {
1615  imu = AP::ins().get_primary_accel();
1616  }
1617  return imu;
1618 }
1619 
1620 // get earth-frame accel vector for primary IMU
1622 {
1624 }
1625 
1626 
1627 // get the index of the current primary accelerometer sensor
1629 {
1630  if (ekf_type() != 0) {
1631  return get_primary_IMU_index();
1632  }
1633  return AP::ins().get_primary_accel();
1634 }
1635 
1636 // get the index of the current primary gyro sensor
1638 {
1639  if (ekf_type() != 0) {
1640  return get_primary_IMU_index();
1641  }
1642  return AP::ins().get_primary_gyro();
1643 }
1644 
1645 #endif // AP_AHRS_NAVEKF_AVAILABLE
1646 
void get_relative_position_D_home(float &posD) const override
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
bool get_soft_armed() const
Definition: Util.h:15
void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)
Vector3f _gyro_estimate
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
static AP_Param * find_object(const char *name)
Definition: AP_Param.cpp:939
Vector2< float > Vector2f
Definition: vector2.h:239
bool initialised() const override
bool get_relative_position_D_origin(float &posD) const override
bool use_compass() override
float roll
Definition: AP_AHRS.h:224
AP_Int8 _ekf_type
Definition: AP_AHRS.h:586
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
uint8_t get_primary_IMU_index(void) const
bool resetHeightDatum(void)
Definition: AP_NavEKF3.cpp:910
void send_ekf_status_report(mavlink_channel_t chan) const
Vector3< float > Vector3f
Definition: vector3.h:246
void update_SITL(void)
const Vector3f & get_accel_ef_blended() const override
float get_error_rp() const override
Definition: AP_AHRS_DCM.h:76
bool use_for_yaw(uint8_t i) const
return true if the compass should be used for yaw calculations
bool resetHeightDatum() override
float get_error_yaw() const override
bool getHAGL(float &HAGL) const
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
void getMagNED(int8_t instance, Vector3f &magNED) const
Definition: AP_NavEKF2.cpp:929
virtual void getCorrectedDeltaVelocityNED(Vector3f &ret, float &dt) const
Definition: AP_AHRS.h:537
double pitchDeg
Definition: SITL.h:20
double xAccel
Definition: SITL.h:18
bool get_secondary_attitude(Vector3f &eulers) const override
void send_status_report(mavlink_channel_t chan)
const Vector3f & get_gyro(void) const override
virtual const Vector3f & get_accel_ef_blended(void) const
Definition: AP_AHRS.h:201
virtual void boost_end(void)
Definition: Scheduler.h:35
bool use_compass() override
bool getPosNE(int8_t instance, Vector2f &posNE) const
Definition: AP_NavEKF2.cpp:781
void setTakeoffExpected(bool val)
bool have_inertial_nav() const override
void getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
uint32_t getLastYawResetAngle(float &yawAngDelta)
bool setOriginLLH(const Location &loc)
bool healthy() const override
bool get_secondary_position(struct Location &loc) const override
const Vector3f & get_gyro(uint8_t i) const
float get_error_rp() const override
bool get_filter_status(nav_filter_status &status) const
void update_EKF3(void)
Interface definition for the various Ground Control System.
bool getGpsGlitchStatus() const
const struct Location & get_home(void) const
Definition: AP_AHRS.h:435
bool getOriginLLH(int8_t instance, struct Location &loc) const
Definition: AP_NavEKF2.cpp:992
Quaternion quaternion
Definition: SITL.h:21
uint8_t ekf_type(void) const
bool use_compass(void) const
uint8_t get_primary_gyro(void) const
AP_AHRS_NavEKF(NavEKF2 &_EKF2, NavEKF3 &_EKF3, Flags flags=FLAG_NONE)
void getGyroBias(int8_t instance, Vector3f &gyroBias) const
Definition: AP_NavEKF3.cpp:869
bool get_hagl(float &hagl) const override
bool get_mag_field_correction(Vector3f &ret) const override
double longitude
Definition: SITL.h:14
bool set_origin(const Location &loc) override
bool setOriginLLH(const Location &loc)
void getFilterStatus(int8_t instance, nav_filter_status &status) const
bool InitialiseFilter(void)
Definition: AP_NavEKF2.cpp:596
const char * prearm_failure_reason(void) const
void getEulerAngles(int8_t instance, Vector3f &eulers) const
bool have_ekf_logging(void) const
Definition: AP_NavEKF3.h:352
double speedE
Definition: SITL.h:17
float pitch
Definition: AP_AHRS.h:225
bool getPosD(int8_t instance, float &posD) const
Definition: AP_NavEKF2.cpp:793
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
AP_HAL::Util * util
Definition: HAL.h:115
void getMagXYZ(int8_t instance, Vector3f &magXYZ) const
Definition: AP_NavEKF3.cpp:965
void setTakeoffExpected(bool val)
bool getHeightControlLimit(float &height) const
bool get_location(struct Location &loc) const
AHRS_VehicleClass _vehicle_class
Definition: AP_AHRS.h:572
void getGyroBias(int8_t instance, Vector3f &gyroBias) const
Definition: AP_NavEKF2.cpp:831
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
bool InitialiseFilter(void)
Definition: AP_NavEKF3.cpp:620
float yaw
Definition: AP_AHRS.h:226
void update(bool skip_ins_update=false) override
Definition: AP_AHRS_DCM.cpp:50
const Vector3f & get_gyro() const override
Definition: AP_AHRS_DCM.h:47
void getRotationBodyToNED(Matrix3f &mat) const
bool get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const
uint32_t start_time_ms
void reset_attitude(const float &roll, const float &pitch, const float &yaw) override
Vector3f _dcm_attitude
AP_Int8 odom_enable
Definition: SITL.h:142
void reset_attitude(const float &roll, const float &pitch, const float &yaw) override
void reset_gyro_drift() override
Definition: AP_AHRS_DCM.cpp:41
virtual Vector2f groundspeed_vector(void)
Definition: AP_AHRS.cpp:235
void resetGyroBias(void)
Definition: AP_NavEKF3.cpp:896
bool getHeightControlLimit(float &height) const
void from_rotation_matrix(const Matrix3f &m)
Definition: quaternion.cpp:76
void update_EKF2(void)
double rollRate
Definition: SITL.h:19
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
bool get_origin(Location &ret) const override
Vector3f _accel_ef_ekf_blended
virtual const Vector3f & get_accel_ef(void) const
Definition: AP_AHRS.h:196
void getQuaternion(int8_t instance, Quaternion &quat) const
double speedD
Definition: SITL.h:17
void getRotationBodyToNED(Matrix3f &mat) const
Location home
Definition: SITL.h:13
uint32_t getLastYawResetAngle(float &yawAng) const override
const Vector3f & get_accel(uint8_t i) const
void setTouchdownExpected(bool val)
const Vector3f & get_gyro_drift() const override
Definition: AP_AHRS_DCM.h:57
Matrix3< T > transposed(void) const
Definition: matrix3.cpp:189
T y
Definition: vector2.h:37
uint8_t get_primary_accel(void) const
void getWind(int8_t instance, Vector3f &wind) const
Definition: AP_NavEKF2.cpp:920
bool get_relative_position_NED_home(Vector3f &vec) const override
int8_t getPrimaryCoreIMUIndex(void) const
Definition: AP_NavEKF2.cpp:770
uint32_t getLastYawResetAngle(float &yawAngDelta)
bool healthy() const override
void setTakeoffExpected(bool val)
double yawRate
Definition: SITL.h:19
bool airspeed_estimate(float *airspeed_ret) const override
bool airspeed_estimate(float *airspeed_ret) const override
bool getLLH(struct Location &loc) const
double rollDeg
Definition: SITL.h:20
const char * prearm_failure_reason(void) const override
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:139
void getVelNED(int8_t instance, Vector3f &vel) const
Definition: AP_NavEKF3.cpp:841
AP_HAL::OpticalFlow * opticalflow
Definition: HAL.h:116
const Vector3f & get_accel_ef() const override
uint32_t getLastPosNorthEastReset(Vector2f &posDelta)
float ground_speed(uint8_t instance) const
Definition: AP_GPS.h:232
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
uint32_t getLastPosDownReset(float &posDelta)
virtual bool get_position(struct Location &loc) const override
void update_cd_values(void)
Definition: AP_AHRS.cpp:352
#define GRAVITY_MSS
Definition: definitions.h:47
void update(bool skip_ins_update=false)
#define f(i)
void reset(bool recover_eulers=false) override
void getCorrectedDeltaVelocityNED(Vector3f &ret, float &dt) const override
bool getPosD(int8_t instance, float &posD) const
Definition: AP_NavEKF3.cpp:831
int8_t getPrimaryCoreIMUIndex(void) const
Definition: AP_NavEKF3.cpp:808
T y
Definition: vector3.h:67
double yawDeg
Definition: SITL.h:20
uint32_t millis()
Definition: system.cpp:157
void getEulerAngles(int8_t instance, Vector3f &eulers) const
bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const override
uint8_t get_primary_accel_index(void) const override
double yAccel
Definition: SITL.h:18
double speedN
Definition: SITL.h:17
uint32_t getLastPosNorthEastReset(Vector2f &posDelta)
void update(bool skip_ins_update=false) override
T z
Definition: vector3.h:67
Vector3f _accel_ef_ekf[INS_MAX_INSTANCES]
#define AP_AHRS_NAVEKF_SETTLE_TIME_MS
void getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
void UpdateFilter(void)
Definition: AP_NavEKF3.cpp:720
void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)
uint32_t getLastPosDownReset(float &posDelta) const override
double zAccel
Definition: SITL.h:18
void rotation_matrix(Matrix3f &m) const
Definition: quaternion.cpp:24
const Matrix3f & get_rotation_body_to_ned() const override
Definition: AP_AHRS_DCM.h:52
bool get_position(struct Location &loc) const override
void send_status_report(mavlink_channel_t chan)
uint8_t setInhibitGPS(void)
bool get_relative_position_NE_origin(Vector2f &posNE) const override
float get_error_yaw() const override
Definition: AP_AHRS_DCM.h:79
void getFilterFaults(int8_t instance, uint16_t &faults) const
bool resetHeightDatum(void)
Definition: AP_NavEKF2.cpp:872
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
Definition: AP_NavEKF3.cpp:986
GPS_Status status(uint8_t instance) const
Query GPS status.
Definition: AP_GPS.h:189
bool have_ekf_logging(void) const override
uint32_t getLastPosDownReset(float &posDelta)
SITL::SITL * _sitl
struct Location _home
Definition: AP_AHRS.h:655
bool use_compass(void) const
Vector3f wind_estimate() const override
Definition: AP_AHRS_DCM.h:84
const Matrix3f & get_rotation_autopilot_body_to_vehicle_body(void) const
Definition: AP_AHRS.h:263
uint32_t _last_body_odm_update_ms
struct nav_filter_status::@138 flags
Matrix3f _dcm_matrix
void getFilterFaults(int8_t instance, uint16_t &faults) const
bool get_vert_pos_rate(float &velocity) const
bool getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
Definition: AP_NavEKF2.cpp:959
double pitchRate
Definition: SITL.h:19
void UpdateFilter(void)
Definition: AP_NavEKF2.cpp:682
T x
Definition: vector2.h:37
float get_altitude(void) const
Definition: AP_Baro.h:84
bool getHAGL(float &HAGL) const
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
void getMagNED(int8_t instance, Vector3f &magNED) const
Definition: AP_NavEKF3.cpp:956
uint8_t setInhibitGPS(void)
Definition: AP_NavEKF2.cpp:893
bool getPosNE(int8_t instance, Vector2f &posNE) const
Definition: AP_NavEKF3.cpp:819
Vector3f location_3d_diff_NED(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:149
AP_AHRS_View * _view
Definition: AP_AHRS.h:667
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
Definition: AP_NavEKF2.cpp:903
Vector3f wind_estimate() const override
static constexpr float radians(float deg)
Definition: AP_Math.h:158
float get_delta_velocity_dt(uint8_t i) const
static struct notify_flags_and_values_type flags
Definition: AP_Notify.h:117
void getVelNED(int8_t instance, Vector3f &vel) const
Definition: AP_NavEKF2.cpp:803
void zero()
Definition: vector2.h:125
uint8_t get_primary_gyro_index(void) const override
bool always_use_EKF() const
virtual void push_gyro_bias(float gyro_bias_x, float gyro_bias_y)=0
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
bool healthy(void) const
Definition: AP_NavEKF3.cpp:788
const Matrix3f & get_rotation_body_to_ned(void) const override
uint8_t fly_forward
Definition: AP_AHRS.h:596
bool getOriginLLH(int8_t instance, struct Location &loc) const
uint8_t setInhibitGPS(void)
Definition: AP_NavEKF3.cpp:929
void reset(bool recover_eulers=false) override
void reset_gyro_drift() override
EKF_TYPE active_EKF_type(void) const
Compass * _compass
Definition: AP_AHRS.h:618
bool get_mag_field_NED(Vector3f &ret) const
void resetGyroBias(void)
Definition: AP_NavEKF2.cpp:858
uint32_t getLastVelNorthEastReset(Vector2f &vel) const override
double latitude
Definition: SITL.h:14
bool get_relative_position_NED_origin(Vector3f &vec) const override
AP_InertialSensor & ins()
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
struct AP_AHRS::ahrs_flags _flags
void setTouchdownExpected(bool val)
void getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const
Definition: AP_NavEKF3.cpp:939
uint32_t getLastVelNorthEastReset(Vector2f &vel) const
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
float getPosDownDerivative(int8_t instance) const
Definition: AP_NavEKF3.cpp:850
void update_trig(void)
Definition: AP_AHRS.cpp:336
AP_Baro & baro()
Definition: AP_Baro.cpp:737
void getAccelBias(int8_t instance, Vector3f &accelBias) const
Definition: AP_NavEKF3.cpp:878
void getWind(int8_t instance, Vector3f &wind) const
Definition: AP_NavEKF3.cpp:947
#define INS_MAX_INSTANCES
float getPosDownDerivative(int8_t instance) const
Definition: AP_NavEKF2.cpp:812
uint32_t getLastVelNorthEastReset(Vector2f &vel) const
bool get_secondary_quaternion(Quaternion &quat) const override
void set_ekf_use(bool setting)
void getFilterStatus(int8_t instance, nav_filter_status &status) const
bool have_ekf_logging(void) const
Definition: AP_NavEKF2.h:321
void getAccelZBias(int8_t instance, float &zbias) const
Definition: AP_NavEKF2.cpp:911
bool get_relative_position_NE_home(Vector2f &posNE) const override
double altitude
Definition: SITL.h:15
Vector2f groundspeed_vector() override
bool get_velocity_NED(Vector3f &vec) const override
const uint16_t startup_delay_ms
void getMagXYZ(int8_t instance, Vector3f &magXYZ) const
Definition: AP_NavEKF2.cpp:938
bool get_hgt_ctrl_limit(float &limit) const override
void setTouchdownExpected(bool val)
bool healthy(void) const
Definition: AP_NavEKF2.cpp:750
bool getLLH(struct Location &loc) const
Definition: AP_NavEKF2.cpp:980
void identity(void)
Definition: matrix3.h:219
void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
struct sitl_fdm state
Definition: SITL.h:71
const char * prearm_failure_reason(void) const
void zero()
Definition: vector3.h:182
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
T x
Definition: vector3.h:67
uint8_t get_accel_count(void) const
void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms) override
Vector3f _gyro_drift
const Vector3f & get_gyro_drift(void) const override
bool get_accel_health(uint8_t instance) const
uint32_t getLastPosNorthEastReset(Vector2f &pos) const override
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
void update_DCM(bool skip_ins_update)