PX4 Firmware
PX4 Autopilot Software http://px4.io
ekf.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2015 Estimation and Control Library (ECL). All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name ECL nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file ekf.cpp
36  * Core functions for ekf attitude and position estimator.
37  *
38  * @author Roman Bast <bapstroman@gmail.com>
39  * @author Paul Riseborough <p_riseborough@live.com.au>
40  */
41 
42 #include "ekf.h"
43 
44 #include <ecl.h>
45 #include <mathlib/mathlib.h>
46 
47 bool Ekf::init(uint64_t timestamp)
48 {
49  bool ret = initialise_interface(timestamp);
50  reset(timestamp);
51 
52  return ret;
53 }
54 
55 void Ekf::reset(uint64_t timestamp)
56 {
58 
59  _delta_angle_corr.setZero();
60  _imu_down_sampled.delta_ang.setZero();
61  _imu_down_sampled.delta_vel.setZero();
64  _imu_down_sampled.time_us = timestamp;
65 
66  _q_down_sampled(0) = 1.0f;
67  _q_down_sampled(1) = 0.0f;
68  _q_down_sampled(2) = 0.0f;
69  _q_down_sampled(3) = 0.0f;
70 
71  _imu_updated = false;
73  _gps_speed_valid = false;
74 
75  _filter_initialised = false;
76  _terrain_initialised = false;
79 
82 
84 
85  _fault_status.value = 0;
87 
88  _accel_mag_filt = 0.0f;
89  _ang_rate_mag_filt = 0.0f;
90  _prev_dvel_bias_var.zero();
91 }
92 
94 {
95  resetStates();
97 }
98 
100 {
101  _state.vel.setZero();
102  _state.pos.setZero();
103  _state.gyro_bias.setZero();
104  _state.accel_bias.setZero();
105  _state.mag_I.setZero();
106  _state.mag_B.setZero();
107  _state.wind_vel.setZero();
108  _state.quat_nominal.setZero();
109  _state.quat_nominal(0) = 1.0f;
110 
111  _output_new.vel.setZero();
112  _output_new.pos.setZero();
113  _output_new.quat_nominal.setZero();
114  _output_new.quat_nominal(0) = 1.0f;
115 }
116 
118 {
119  bool updated = false;
120 
121  if (!_filter_initialised) {
123 
124  if (!_filter_initialised) {
125  return false;
126  }
127  }
128 
129  // Only run the filter if IMU data in the buffer has been updated
130  if (_imu_updated) {
131 
132  // perform state and covariance prediction for the main filter
133  predictState();
135 
136  // control fusion of observation data
138 
139  // run a separate filter for terrain estimation
141 
142  updated = true;
143  }
144 
145  // the output observer always runs
146  // Use full rate IMU data at the current time horizon
148 
149  return updated;
150 }
151 
153 {
154  // Keep accumulating measurements until we have a minimum of 10 samples for the required sensors
155 
156  // Sum the IMU delta angle measurements
157  const imuSample &imu_init = _imu_buffer.get_newest();
158  _delVel_sum += imu_init.delta_vel;
159 
160  // Sum the magnetometer measurements
162  if ((_mag_counter == 0) && (_mag_sample_delayed.time_us != 0)) {
163  // initialise the counter when we start getting data from the buffer
164  _mag_counter = 1;
165 
166  } else if ((_mag_counter != 0) && (_mag_sample_delayed.time_us != 0)) {
167  // increment the sample count and apply a LPF to the measurement
168  _mag_counter ++;
169 
170  // don't start using data until we can be certain all bad initial data has been flushed
171  if (_mag_counter == (uint8_t)(_obs_buffer_length + 1)) {
173 
174  } else if (_mag_counter > (uint8_t)(_obs_buffer_length + 1)) {
176  }
177  }
178  }
179 
180  // Count the number of external vision measurements received
182  if ((_ev_counter == 0) && (_ev_sample_delayed.time_us != 0)) {
183  // initialise the counter
184  _ev_counter = 1;
185 
186  // set the height fusion mode to use external vision data when we start getting valid data from the buffer
189  _control_status.flags.gps_hgt = false;
190  _control_status.flags.rng_hgt = false;
192  }
193 
194  } else if ((_ev_counter != 0) && (_ev_sample_delayed.time_us != 0)) {
195  // increment the sample count
196  _ev_counter ++;
197  }
198  }
199 
200  // set the default height source from the adjustable parameter
201  if (_hgt_counter == 0) {
203  }
204 
205  // accumulate enough height measurements to be confident in the quality of the data
206  // we use baro height initially and switch to GPS/range/EV finder later when it passes checks.
208  if ((_hgt_counter == 0) && (_baro_sample_delayed.time_us != 0)) {
209  // initialise the counter and height fusion method when we start getting data from the buffer
211  _hgt_counter = 1;
212 
213  } else if ((_hgt_counter != 0) && (_baro_sample_delayed.time_us != 0)) {
214  // increment the sample count and apply a LPF to the measurement
215  _hgt_counter ++;
216 
217  // don't start using data until we can be certain all bad initial data has been flushed
218  if (_hgt_counter == (uint8_t)(_obs_buffer_length + 1)) {
219  // initialise filter states
221 
222  } else if (_hgt_counter > (uint8_t)(_obs_buffer_length + 1)) {
223  // noise filter the data
225  }
226  }
227  }
228 
229  // check to see if we have enough measurements and return false if not
230  bool hgt_count_fail = _hgt_counter <= 2u * _obs_buffer_length;
231  bool mag_count_fail = _mag_counter <= 2u * _obs_buffer_length;
232 
233  if (hgt_count_fail || mag_count_fail) {
234  return false;
235 
236  } else {
237  // reset variables that are shared with post alignment GPS checks
238  _gps_drift_velD = 0.0f;
239  _gps_alt_ref = 0.0f;
240 
241  // Zero all of the states
242  _state.vel.setZero();
243  _state.pos.setZero();
244  _state.gyro_bias.setZero();
245  _state.accel_bias.setZero();
246  _state.mag_I.setZero();
247  _state.mag_B.setZero();
248  _state.wind_vel.setZero();
249 
250  // get initial roll and pitch estimate from delta velocity vector, assuming vehicle is static
251  float pitch = 0.0f;
252  float roll = 0.0f;
253 
254  if (_delVel_sum.norm() > 0.001f) {
255  _delVel_sum.normalize();
256  pitch = asinf(_delVel_sum(0));
257  roll = atan2f(-_delVel_sum(1), -_delVel_sum(2));
258 
259  } else {
260  return false;
261  }
262 
263  // calculate initial tilt alignment
264  Eulerf euler_init(roll, pitch, 0.0f);
265  _state.quat_nominal = Quatf(euler_init);
266 
267  // update transformation matrix from body to world frame
269 
270  // calculate the initial magnetic field and yaw alignment
272 
273  // initialise the state covariance matrix
275 
276  // update the yaw angle variance using the variance of the measurement
278  // using error estimate from external vision data TODO: this is never true
280  } else if (_params.mag_fusion_type <= MAG_FUSE_TYPE_3D) {
281  // using magnetic heading tuning parameter
283  }
284 
286  // if we are using the range finder as the primary source, then calculate the baro height at origin so we can use baro as a backup
287  // so it can be used as a backup ad set the initial height using the range finder
288  const baroSample &baro_newest = _baro_buffer.get_newest();
289  _baro_hgt_offset = baro_newest.hgt;
291  ECL_INFO_TIMESTAMPED("EKF using range finder height - commencing alignment");
292 
293  } else if (_control_status.flags.ev_hgt) {
294  // if we are using external vision data for height, then the vertical position state needs to be reset
295  // because the initialisation position is not the zero datum
296  resetHeight();
297 
298  }
299 
300  // try to initialise the terrain estimator
302 
303  // reset the essential fusion timeout counters
310 
311  // reset the output predictor state history to match the EKF initial values
313 
314  return true;
315  }
316 }
317 
319 {
322  calcEarthRateNED(_earth_rate_NED, (float)_pos_ref.lat_rad);
324  }
325  }
326 
327  // apply imu bias corrections
328  Vector3f corrected_delta_ang = _imu_sample_delayed.delta_ang - _state.gyro_bias;
329  Vector3f corrected_delta_vel = _imu_sample_delayed.delta_vel - _state.accel_bias;
330 
331  // correct delta angles for earth rotation rate
332  corrected_delta_ang -= -_R_to_earth.transpose() * _earth_rate_NED * _imu_sample_delayed.delta_ang_dt;
333 
334  // convert the delta angle to a delta quaternion
335  Quatf dq;
336  dq.from_axis_angle(corrected_delta_ang);
337 
338  // rotate the previous quaternion by the delta quaternion using a quaternion multiplication
340 
341  // quaternions must be normalised whenever they are modified
342  _state.quat_nominal.normalize();
343 
344  // save the previous value of velocity so we can use trapzoidal integration
345  Vector3f vel_last = _state.vel;
346 
347  // update transformation matrix from body to world frame
349 
350  // Calculate an earth frame delta velocity
351  Vector3f corrected_delta_vel_ef = _R_to_earth * corrected_delta_vel;
352 
353  // calculate a filtered horizontal acceleration with a 1 sec time constant
354  // this are used for manoeuvre detection elsewhere
355  float alpha = 1.0f - _imu_sample_delayed.delta_vel_dt;
356  _accel_lpf_NE(0) = _accel_lpf_NE(0) * alpha + corrected_delta_vel_ef(0);
357  _accel_lpf_NE(1) = _accel_lpf_NE(1) * alpha + corrected_delta_vel_ef(1);
358 
359  // calculate the increment in velocity using the current orientation
360  _state.vel += corrected_delta_vel_ef;
361 
362  // compensate for acceleration due to gravity
364 
365  // predict position states via trapezoidal integration of velocity
366  _state.pos += (vel_last + _state.vel) * _imu_sample_delayed.delta_vel_dt * 0.5f;
367 
368  constrainStates();
369 
370  // calculate an average filter update time
372 
373  // filter and limit input between -50% and +100% of nominal value
374  input = math::constrain(input, 0.5f * FILTER_UPDATE_PERIOD_S, 2.0f * FILTER_UPDATE_PERIOD_S);
375  _dt_ekf_avg = 0.99f * _dt_ekf_avg + 0.01f * input;
376 }
377 
378 bool Ekf::collect_imu(const imuSample &imu)
379 {
380  // accumulate and downsample IMU data across a period FILTER_UPDATE_PERIOD_MS long
381 
382  // copy imu data to local variables
383  _imu_sample_new = imu;
384 
385  // accumulate the time deltas
388 
389  // use a quaternion to accumulate delta angle data
390  // this quaternion represents the rotation from the start to end of the accumulation period
391  Quatf delta_q;
392  delta_q.rotate(imu.delta_ang);
393  _q_down_sampled = _q_down_sampled * delta_q;
394  _q_down_sampled.normalize();
395 
396  // rotate the accumulated delta velocity data forward each time so it is always in the updated rotation frame
397  Dcmf delta_R(delta_q.inversed());
399 
400  // accumulate the most recent delta velocity data at the updated rotation frame
401  // assume effective sample time is halfway between the previous and current rotation frame
402  _imu_down_sampled.delta_vel += (imu.delta_vel + delta_R * imu.delta_vel) * 0.5f;
403 
404  // if the target time delta between filter prediction steps has been exceeded
405  // write the accumulated IMU data to the ring buffer
406  const float target_dt = FILTER_UPDATE_PERIOD_S;
407 
409 
410  // accumulate the amount of time to advance the IMU collection time so that we meet the
411  // average EKF update rate requirement
413  _imu_collection_time_adj = math::constrain(_imu_collection_time_adj, -0.5f * target_dt, 0.5f * target_dt);
414 
415  imuSample imu_sample_new;
416  imu_sample_new.delta_ang = _q_down_sampled.to_axis_angle();
417  imu_sample_new.delta_vel = _imu_down_sampled.delta_vel;
420  imu_sample_new.time_us = imu.time_us;
421 
422  _imu_buffer.push(imu_sample_new);
423 
424  // get the oldest data from the buffer
426 
427  // calculate the minimum interval between observations required to guarantee no loss of data
428  // this will occur if data is overwritten before its time stamp falls behind the fusion time horizon
430 
431  // reset
432  _imu_down_sampled.delta_ang.setZero();
433  _imu_down_sampled.delta_vel.setZero();
436  _q_down_sampled(0) = 1.0f;
437  _q_down_sampled(1) = _q_down_sampled(2) = _q_down_sampled(3) = 0.0f;
438 
439  _imu_updated = true;
440 
441  } else {
442  _imu_updated = false;
443  }
444 
445  return _imu_updated;
446 }
447 
448 /*
449  * Implement a strapdown INS algorithm using the latest IMU data at the current time horizon.
450  * Buffer the INS states and calculate the difference with the EKF states at the delayed fusion time horizon.
451  * Calculate delta angle, delta velocity and velocity corrections from the differences and apply them at the
452  * current time horizon so that the INS states track the EKF states at the delayed fusion time horizon.
453  * The inspiration for using a complementary filter to correct for time delays in the EKF
454  * is based on the work by A Khosravian:
455  * “Recursive Attitude Estimation in the Presence of Multi-rate and Multi-delay Vector Measurements”
456  * A Khosravian, J Trumpf, R Mahony, T Hamel, Australian National University
457 */
459 {
460  // Use full rate IMU data at the current time horizon
461  const imuSample &imu = _imu_sample_new;
462 
463  // correct delta angles for bias offsets
464  const float dt_scale_correction = _dt_imu_avg / _dt_ekf_avg;
465 
466  // Apply corrections to the delta angle required to track the quaternion states at the EKF fusion time horizon
467  const Vector3f delta_angle{imu.delta_ang - _state.gyro_bias * dt_scale_correction + _delta_angle_corr};
468 
469  // calculate a yaw change about the earth frame vertical
470  const float spin_del_ang_D = _R_to_earth_now(2, 0) * delta_angle(0) +
471  _R_to_earth_now(2, 1) * delta_angle(1) +
472  _R_to_earth_now(2, 2) * delta_angle(2);
473  _yaw_delta_ef += spin_del_ang_D;
474 
475  // Calculate filtered yaw rate to be used by the magnetometer fusion type selection logic
476  // Note fixed coefficients are used to save operations. The exact time constant is not important.
477  _yaw_rate_lpf_ef = 0.95f * _yaw_rate_lpf_ef + 0.05f * spin_del_ang_D / imu.delta_ang_dt;
478 
479  // convert the delta angle to an equivalent delta quaternions
480  Quatf dq;
481  dq.from_axis_angle(delta_angle);
482 
483  // rotate the previous INS quaternion by the delta quaternions
486 
487  // the quaternions must always be normalised after modification
488  _output_new.quat_nominal.normalize();
489 
490  // calculate the rotation matrix from body to earth frame
492 
493  // correct delta velocity for bias offsets
494  const Vector3f delta_vel{imu.delta_vel - _state.accel_bias * dt_scale_correction};
495 
496  // rotate the delta velocity to earth frame
497  Vector3f delta_vel_NED{_R_to_earth_now * delta_vel};
498 
499  // correct for measured acceleration due to gravity
500  delta_vel_NED(2) += CONSTANTS_ONE_G * imu.delta_vel_dt;
501 
502  // calculate the earth frame velocity derivatives
503  if (imu.delta_vel_dt > 1e-4f) {
504  _vel_deriv_ned = delta_vel_NED * (1.0f / imu.delta_vel_dt);
505  }
506 
507  // save the previous velocity so we can use trapezoidal integration
508  const Vector3f vel_last{_output_new.vel};
509 
510  // increment the INS velocity states by the measurement plus corrections
511  // do the same for vertical state used by alternative correction algorithm
512  _output_new.vel += delta_vel_NED;
513  _output_vert_new.vel_d += delta_vel_NED(2);
514 
515  // use trapezoidal integration to calculate the INS position states
516  // do the same for vertical state used by alternative correction algorithm
517  const Vector3f delta_pos_NED = (_output_new.vel + vel_last) * (imu.delta_vel_dt * 0.5f);
518  _output_new.pos += delta_pos_NED;
519  _output_vert_new.vel_d_integ += delta_pos_NED(2);
520 
521  // accumulate the time for each update
523 
524  // correct velocity for IMU offset
525  if (imu.delta_ang_dt > 1e-4f) {
526  // calculate the average angular rate across the last IMU update
527  const Vector3f ang_rate = imu.delta_ang * (1.0f / imu.delta_ang_dt);
528 
529  // calculate the velocity of the IMU relative to the body origin
530  const Vector3f vel_imu_rel_body = cross_product(ang_rate, _params.imu_pos_body);
531 
532  // rotate the relative velocity into earth frame
533  _vel_imu_rel_body_ned = _R_to_earth_now * vel_imu_rel_body;
534  }
535 
536  // store the INS states in a ring buffer with the same length and time coordinates as the IMU data buffer
537  if (_imu_updated) {
540 
541  // get the oldest INS state data from the ring buffer
542  // this data will be at the EKF fusion time horizon
545 
546  // calculate the quaternion delta between the INS and EKF quaternions at the EKF fusion time horizon
547  Quatf quat_inv = _state.quat_nominal.inversed();
548  Quatf q_error = quat_inv * _output_sample_delayed.quat_nominal;
549  q_error.normalize();
550 
551  // convert the quaternion delta to a delta angle
552  float scalar;
553 
554  if (q_error(0) >= 0.0f) {
555  scalar = -2.0f;
556 
557  } else {
558  scalar = 2.0f;
559  }
560 
561  const Vector3f delta_ang_error{scalar * q_error(1), scalar * q_error(2), scalar * q_error(3)};
562 
563  // calculate a gain that provides tight tracking of the estimator attitude states and
564  // adjust for changes in time delay to maintain consistent damping ratio of ~0.7
565  const float time_delay = fmaxf((imu.time_us - _imu_sample_delayed.time_us) * 1e-6f, _dt_imu_avg);
566  const float att_gain = 0.5f * _dt_imu_avg / time_delay;
567 
568  // calculate a corrrection to the delta angle
569  // that will cause the INS to track the EKF quaternions
570  _delta_angle_corr = delta_ang_error * att_gain;
571 
572  // calculate velocity and position tracking errors
573  const Vector3f vel_err{_state.vel - _output_sample_delayed.vel};
574  const Vector3f pos_err{_state.pos - _output_sample_delayed.pos};
575 
576  // collect magnitude tracking error for diagnostics
577  _output_tracking_error[0] = delta_ang_error.norm();
578  _output_tracking_error[1] = vel_err.norm();
579  _output_tracking_error[2] = pos_err.norm();
580 
581  /*
582  * Loop through the output filter state history and apply the corrections to the velocity and position states.
583  * This method is too expensive to use for the attitude states due to the quaternion operations required
584  * but because it eliminates the time delay in the 'correction loop' it allows higher tracking gains
585  * to be used and reduces tracking error relative to EKF states.
586  */
587 
588  // Complementary filter gains
589  const float vel_gain = _dt_ekf_avg / math::constrain(_params.vel_Tau, _dt_ekf_avg, 10.0f);
590  const float pos_gain = _dt_ekf_avg / math::constrain(_params.pos_Tau, _dt_ekf_avg, 10.0f);
591  {
592  /*
593  * Calculate a correction to be applied to vel_d that casues vel_d_integ to track the EKF
594  * down position state at the fusion time horizon using an alternative algorithm to what
595  * is used for the vel and pos state tracking. The algorithm applies a correction to the vel_d
596  * state history and propagates vel_d_integ forward in time using the corrected vel_d history.
597  * This provides an alternative vertical velocity output that is closer to the first derivative
598  * of the position but does degrade tracking relative to the EKF state.
599  */
600 
601  // calculate down velocity and position tracking errors
602  const float vel_d_err = (_state.vel(2) - _output_vert_delayed.vel_d);
603  const float pos_d_err = (_state.pos(2) - _output_vert_delayed.vel_d_integ);
604 
605  // calculate a velocity correction that will be applied to the output state history
606  // using a PD feedback tuned to a 5% overshoot
607  const float vel_d_correction = pos_d_err * pos_gain + vel_d_err * pos_gain * 1.1f;
608 
609  /*
610  * Calculate corrections to be applied to vel and pos output state history.
611  * The vel and pos state history are corrected individually so they track the EKF states at
612  * the fusion time horizon. This option provides the most accurate tracking of EKF states.
613  */
614 
615  // loop through the vertical output filter state history starting at the oldest and apply the corrections to the
616  // vel_d states and propagate vel_d_integ forward using the corrected vel_d
617  uint8_t index = _output_vert_buffer.get_oldest_index();
618 
619  const uint8_t size = _output_vert_buffer.get_length();
620 
621  for (uint8_t counter = 0; counter < (size - 1); counter++) {
622  const uint8_t index_next = (index + 1) % size;
623  outputVert &current_state = _output_vert_buffer[index];
624  outputVert &next_state = _output_vert_buffer[index_next];
625 
626  // correct the velocity
627  if (counter == 0) {
628  current_state.vel_d += vel_d_correction;
629  }
630 
631  next_state.vel_d += vel_d_correction;
632 
633  // position is propagated forward using the corrected velocity and a trapezoidal integrator
634  next_state.vel_d_integ = current_state.vel_d_integ + (current_state.vel_d + next_state.vel_d) * 0.5f * next_state.dt;
635 
636  // advance the index
637  index = (index + 1) % size;
638  }
639 
640  // update output state to corrected values
642 
643  // reset time delta to zero for the next accumulation of full rate IMU data
644  _output_vert_new.dt = 0.0f;
645  }
646 
647  {
648  /*
649  * Calculate corrections to be applied to vel and pos output state history.
650  * The vel and pos state history are corrected individually so they track the EKF states at
651  * the fusion time horizon. This option provides the most accurate tracking of EKF states.
652  */
653 
654  // calculate a velocity correction that will be applied to the output state history
655  _vel_err_integ += vel_err;
656  const Vector3f vel_correction = vel_err * vel_gain + _vel_err_integ * sq(vel_gain) * 0.1f;
657 
658  // calculate a position correction that will be applied to the output state history
659  _pos_err_integ += pos_err;
660  const Vector3f pos_correction = pos_err * pos_gain + _pos_err_integ * sq(pos_gain) * 0.1f;
661 
662  // loop through the output filter state history and apply the corrections to the velocity and position states
663  for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
664  // a constant velocity correction is applied
665  _output_buffer[index].vel += vel_correction;
666 
667  // a constant position correction is applied
668  _output_buffer[index].pos += pos_correction;
669  }
670 
671  // update output state to corrected values
673  }
674  }
675 }
676 
677 /*
678  * Predict the previous quaternion output state forward using the latest IMU delta angle data.
679 */
681 {
682  // Correct delta angle data for bias errors using bias state estimates from the EKF and also apply
683  // corrections required to track the EKF quaternion states
685 
686  // increment the quaternions using the corrected delta angle vector
687  // the quaternions must always be normalised after modification
688  return Quatf{_output_new.quat_nominal * AxisAnglef{delta_angle}}.unit();
689 }
constexpr _Tp constrain(_Tp val, _Tp min_val, _Tp max_val)
Definition: Limits.hpp:66
Vector3f _vel_err_integ
integral of velocity tracking error (m)
Definition: ekf.h:406
float _cos_tilt_rng
cosine of the range finder tilt rotation about the Y body axis
Definition: ekf.h:464
struct estimator::filter_control_status_u::@60 flags
void setControlBaroHeight()
bool pop_first_older_than(const uint64_t &timestamp, data_type *sample)
Definition: RingBuffer.h:126
Vector3f delta_ang
delta angle in body frame (integrated gyro measurements) (rad)
Definition: common.h:107
void calculateOutputStates()
Definition: ekf.cpp:458
Adapter / shim layer for system calls needed by ECL.
stateSample _state
state struct of the ekf running at the delayed time horizon
Definition: ekf.h:288
uint32_t yaw_align
1 - true if the filter yaw alignment is complete
Definition: common.h:442
float mag_heading_noise
measurement noise used for simple heading fusion (rad)
Definition: common.h:269
bool initialiseFilter(void)
Definition: ekf.cpp:152
RingBuffer< outputSample > _output_buffer
float dt
delta time (sec)
Definition: common.h:102
Quatf calculate_quaternion() const
Definition: ekf.cpp:680
float _yaw_rate_lpf_ef
Filtered angular rate about earth frame D axis (rad/sec)
Definition: ekf.h:353
bool resetMagHeading(const Vector3f &mag_init, bool increase_yaw_var=true, bool update_buffer=true)
Definition: ekf_helper.cpp:554
#define MAG_FUSE_TYPE_3D
Magnetometer 3-axis fusion will always be used. This is more accurate, but more affected by localised...
Definition: common.h:202
RingBuffer< extVisionSample > _ext_vision_buffer
Dcm< float > Dcmf
Definition: Dcm.hpp:185
const data_type & get_newest()
Definition: RingBuffer.h:121
Vector3f accel_bias
delta velocity bias estimate in m/s
Definition: common.h:372
float _gps_alt_ref
WGS-84 height (m)
Definition: ekf.h:425
float _yaw_delta_ef
Recent change in yaw angle measured about the earth frame D axis (rad)
Definition: ekf.h:352
uint64_t time_us
timestamp of the measurement (uSec)
Definition: common.h:96
Vector2f _accel_lpf_NE
Low pass filtered horizontal earth frame acceleration (m/sec**2)
Definition: ekf.h:351
float vel_Tau
velocity state correction time constant (1/sec)
Definition: common.h:332
uint32_t rng_hgt
10 - true when range finder height is being fused as a primary height reference
Definition: common.h:451
void initialiseCovariance()
Definition: covariance.cpp:49
Vector3f cross_product(const Vector3f &vecIn1, const Vector3f &vecIn2)
Vector3f mag_I
NED earth magnetic field in gauss.
Definition: common.h:373
uint32_t baro_hgt
9 - true when baro height is being fused as a primary height reference
Definition: common.h:450
RingBuffer< outputVert > _output_vert_buffer
float pos_Tau
position state correction time constant (1/sec)
Definition: common.h:333
int32_t vdist_sensor_type
selects the primary source for height data
Definition: common.h:223
imuSample _imu_down_sampled
down sampled imu data (sensor rate -> filter update rate)
Definition: ekf.h:404
static constexpr float CONSTANTS_ONE_G
Definition: geo.h:51
float vel_d
D velocity calculated using alternative algorithm (m/sec)
Definition: common.h:100
const T & getState() const
Definition: AlphaFilter.hpp:67
bool collect_imu(const imuSample &imu) override
Definition: ekf.cpp:378
uint64_t _time_last_of_fuse
time the last fusion of optical flow measurements were performed (uSec)
Definition: ekf.h:334
uint64_t _time_last_hgt_fuse
time the last fusion of height measurements was performed (uSec)
Definition: ekf.h:333
float _imu_collection_time_adj
the amount of time the IMU collection needs to be advanced to meet the target set by FILTER_UPDATE_PE...
Definition: ekf.h:339
void predictState()
Definition: ekf.cpp:318
void controlFusionModes()
Definition: control.cpp:46
AlphaFilterVector3f _mag_lpf
filtered magnetometer measurement (Gauss)
Definition: ekf.h:433
Vector3f _prev_dvel_bias_var
saved delta velocity XYZ bias variances (m/sec)**2
Definition: ekf.h:454
Dcmf _R_to_earth
transformation matrix from body frame to earth frame from last EKF prediction
Definition: ekf.h:348
void calcEarthRateNED(Vector3f &omega, float lat_rad) const
Definition: ekf_helper.cpp:820
uint64_t time_us
timestamp of the measurement (uSec)
Definition: common.h:163
uint64_t _time_last_pos_fuse
time the last fusion of horizontal position measurements was performed (uSec)
Definition: ekf.h:330
int _primary_hgt_source
specifies primary source of height data
Definition: ekf.h:473
const data_type & get_oldest()
Definition: RingBuffer.h:122
bool _terrain_initialised
true when the terrain estimator has been initialized
Definition: ekf.h:462
uint64_t time_us
timestamp of the measurement (uSec)
Definition: common.h:111
Vector3f pos
NED position estimate in earth frame (m/sec)
Definition: common.h:95
float _output_tracking_error[3]
contains the magnitude of the angle, velocity and position track errors (rad, m/s, m)
Definition: ekf.h:408
#define VDIST_SENSOR_EV
Use external vision.
Definition: common.h:181
void reset(uint64_t timestamp) override
Definition: ekf.cpp:55
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
uint32_t _mag_counter
number of magnetometer samples read during initialisation
Definition: ekf.h:430
float rng_gnd_clearance
minimum valid value for range when on ground (m)
Definition: common.h:291
void update(const T &input, float tau, float dt)
Definition: AlphaFilter.hpp:50
uint32_t _ev_counter
number of external vision samples read during initialisation
Definition: ekf.h:431
filter_control_status_u _control_status
Euler< float > Eulerf
Definition: Euler.hpp:156
RingBuffer< baroSample > _baro_buffer
Vector3f _earth_rate_NED
earth rotation vector (NED) in rad/s
Definition: ekf.h:346
Vector3f vel
NED velocity in earth frame in m/s.
Definition: common.h:369
static unsigned counter
Definition: safety.c:56
uint32_t ev_hgt
14 - true when height data from external vision measurements is being fused
Definition: common.h:455
float _gps_drift_velD
GPS down position derivative (m/sec)
Definition: ekf.h:413
int32_t mag_fusion_type
integer used to specify the type of magnetometer fusion used
Definition: common.h:275
static constexpr float sq(float var)
Definition: ekf.h:695
RingBuffer< magSample > _mag_buffer
uint32_t ev_yaw
13 - true when yaw data from external vision measurements is being fused
Definition: common.h:454
fault_status_u _fault_status
float hgt
pressure altitude above sea level (m)
Definition: common.h:131
void increaseQuatYawErrVariance(float yaw_variance)
Quatf quat_nominal
quaternion defining the rotation from body to earth frame
Definition: common.h:368
filter_control_status_u _control_status_prev
void resetHeight()
Definition: ekf_helper.cpp:214
void alignOutputFilter()
Definition: ekf_helper.cpp:378
Vector3f pos
NED position in earth frame in m.
Definition: common.h:370
void runTerrainEstimator()
innovation_fault_status_u _innov_check_fail_status
float rng_sens_pitch
Pitch offset of the range sensor (rad). Sensor points out along Z axis when offset is zero...
Definition: common.h:292
Vector3< float > Vector3f
Definition: Vector3.hpp:136
extVisionSample _ev_sample_delayed
float _accel_mag_filt
acceleration magnitude after application of a decaying envelope filter (rad/sec)
Definition: ekf.h:452
float _R_rng_to_earth_2_2
2,2 element of the rotation matrix from sensor frame to earth frame
Definition: ekf.h:465
void constrainStates()
Definition: ekf_helper.cpp:784
bool _filter_initialised
true when the EKF sttes and covariances been initialised
Definition: ekf.h:290
Vector3f mag_B
magnetometer bias estimate in body frame in gauss
Definition: common.h:374
constexpr _Tp max(_Tp a, _Tp b)
Definition: Limits.hpp:60
float _sin_tilt_rng
sine of the range finder tilt rotation about the Y body axis
Definition: ekf.h:463
uint64_t time_us
timestamp of the measurement (uSec)
Definition: common.h:132
Quaternion< float > Quatf
Definition: Quaternion.hpp:544
uint64_t time_us
timestamp of the measurement (uSec)
Definition: common.h:127
Vector3f vel
NED velocity estimate in earth frame (m/sec)
Definition: common.h:94
float vel_d_integ
Integral of vel_d (m)
Definition: common.h:101
RingBuffer< imuSample > _imu_buffer
void reset(const T &val)
Definition: AlphaFilter.hpp:48
uint64_t _time_last_delpos_fuse
time the last fusion of incremental horizontal position measurements was performed (uSec) ...
Definition: ekf.h:331
Vector3f _delVel_sum
summed delta velocity (m/sec)
Definition: ekf.h:434
bool initHagl()
Vector3f imu_pos_body
xyz position of IMU in body frame (m)
Definition: common.h:325
AxisAngle< float > AxisAnglef
Definition: AxisAngle.hpp:160
uint8_t get_oldest_index() const
Definition: RingBuffer.h:124
uint32_t gps_hgt
11 - true when GPS height is being fused as a primary height reference
Definition: common.h:452
float angErr
1-Sigma angular error (rad)
Definition: common.h:162
void predictCovariance()
Definition: covariance.cpp:135
uint64_t _time_last_vel_fuse
time the last fusion of velocity measurements was performed (uSec)
Definition: ekf.h:332
float _ang_rate_mag_filt
angular rate magnitude after application of a decaying envelope filter (rad/sec)
Definition: ekf.h:453
float _baro_hgt_offset
baro height reading at the local NED origin (m)
Definition: ekf.h:436
uint32_t _hgt_counter
number of height samples read during initialisation
Definition: ekf.h:428
bool init(uint64_t timestamp) override
Definition: ekf.cpp:47
static constexpr float FILTER_UPDATE_PERIOD_S
Quatf _q_down_sampled
down sampled quaternion (tracking delta angles between ekf update steps)
Definition: ekf.h:405
Vector2f wind_vel
wind velocity in m/s
Definition: common.h:375
bool _earth_rate_initialised
true when we know the earth rotatin rate (requires GPS)
Definition: ekf.h:291
Vector3f mag
NED magnetometer body frame measurements (Gauss)
Definition: common.h:126
Vector3f _delta_angle_corr
delta angle correction vector (rad)
Definition: ekf.h:403
Vector3f delta_vel
delta velocity in body frame (integrated accelerometer measurements) (m/sec)
Definition: common.h:108
bool initialise_interface(uint64_t timestamp)
uint64_t _time_last_hagl_fuse
last system time that the hagl measurement failed it&#39;s checks (uSec)
Definition: ekf.h:461
Vector3f gyro_bias
delta angle bias estimate in rad
Definition: common.h:371
Quatf quat_nominal
nominal quaternion describing vehicle attitude
Definition: common.h:93
float _dt_ekf_avg
average update rate of the ekf
Definition: ekf.h:285
float delta_ang_dt
delta angle integration period (sec)
Definition: common.h:109
Class for core functions for ekf attitude and position estimator.
bool update() override
Definition: ekf.cpp:117
Vector3f _pos_err_integ
integral of position tracking error (m.s)
Definition: ekf.h:407
#define ECL_INFO_TIMESTAMPED
Definition: ecl.h:93
outputSample _output_sample_delayed
float delta_vel_dt
delta velocity integration period (sec)
Definition: common.h:110
uint8_t get_length() const
Definition: RingBuffer.h:117
float _rng_filt_state
filtered height measurement (m)
Definition: ekf.h:429
void resetStates() override
Definition: ekf.cpp:99
void resetStatesAndCovariances() override
Definition: ekf.cpp:93
void push(const data_type &sample)
Definition: RingBuffer.h:97