APM:Libraries
AP_AHRS_DCM.cpp
Go to the documentation of this file.
1 /*
2  * APM_AHRS_DCM.cpp
3  *
4  * AHRS system using DCM matrices
5  *
6  * Based on DCM code by Doug Weibel, Jordi Muñoz and Jose Julio. DIYDrones.com
7  *
8  * Adapted for the general ArduPilot AHRS interface by Andrew Tridgell
9 
10  This program is free software: you can redistribute it and/or modify
11  it under the terms of the GNU General Public License as published by
12  the Free Software Foundation, either version 3 of the License, or
13  (at your option) any later version.
14 
15  This program is distributed in the hope that it will be useful,
16  but WITHOUT ANY WARRANTY; without even the implied warranty of
17  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
18  GNU General Public License for more details.
19 
20  You should have received a copy of the GNU General Public License
21  along with this program. If not, see <http://www.gnu.org/licenses/>.
22  */
23 #include "AP_AHRS.h"
24 #include <AP_HAL/AP_HAL.h>
25 
26 extern const AP_HAL::HAL& hal;
27 
28 // this is the speed in m/s above which we first get a yaw lock with
29 // the GPS
30 #define GPS_SPEED_MIN 3
31 
32 // the limit (in degrees/second) beyond which we stop integrating
33 // omega_I. At larger spin rates the DCM PI controller can get 'dizzy'
34 // which results in false gyro drift. See
35 // http://gentlenav.googlecode.com/files/fastRotations.pdf
36 #define SPIN_RATE_LIMIT 20
37 
38 // reset the current gyro drift estimate
39 // should be called if gyro offsets are recalculated
40 void
42 {
43  _omega_I.zero();
46 }
47 
48 // run a full DCM update round
49 void
50 AP_AHRS_DCM::update(bool skip_ins_update)
51 {
52  float delta_t;
53 
54  if (_last_startup_ms == 0) {
56  }
57 
58  if (!skip_ins_update) {
59  // tell the IMU to grab some data
60  AP::ins().update();
61  }
62 
63  const AP_InertialSensor &_ins = AP::ins();
64 
65  // ask the IMU how much time this sensor reading represents
66  delta_t = _ins.get_delta_time();
67 
68  // if the update call took more than 0.2 seconds then discard it,
69  // otherwise we may move too far. This happens when arming motors
70  // in ArduCopter
71  if (delta_t > 0.2f) {
72  memset(&_ra_sum[0], 0, sizeof(_ra_sum));
73  _ra_deltat = 0;
74  return;
75  }
76 
77  // Integrate the DCM matrix using gyro inputs
78  matrix_update(delta_t);
79 
80  // Normalize the DCM matrix
81  normalize();
82 
83  // Perform drift correction
84  drift_correction(delta_t);
85 
86  // paranoid check for bad values in the DCM matrix
87  check_matrix();
88 
89  // Calculate pitch, roll, yaw for stabilization and navigation
90  euler_angles();
91 
92  // update trig values including _cos_roll, cos_pitch
93  update_trig();
94 
95  // update AOA and SSA
97 }
98 
99 // update the DCM matrix using only the gyros
100 void
102 {
103  // note that we do not include the P terms in _omega. This is
104  // because the spin_rate is calculated from _omega.length(),
105  // and including the P terms would give positive feedback into
106  // the _P_gain() calculation, which can lead to a very large P
107  // value
108  _omega.zero();
109 
110  // average across first two healthy gyros. This reduces noise on
111  // systems with more than one gyro. We don't use the 3rd gyro
112  // unless another is unhealthy as 3rd gyro on PH2 has a lot more
113  // noise
114  uint8_t healthy_count = 0;
115  Vector3f delta_angle;
116  const AP_InertialSensor &_ins = AP::ins();
117  for (uint8_t i=0; i<_ins.get_gyro_count(); i++) {
118  if (_ins.get_gyro_health(i) && healthy_count < 2) {
119  Vector3f dangle;
120  if (_ins.get_delta_angle(i, dangle)) {
121  healthy_count++;
122  delta_angle += dangle;
123  }
124  }
125  }
126  if (healthy_count > 1) {
127  delta_angle /= healthy_count;
128  }
129  if (_G_Dt > 0) {
130  _omega = delta_angle / _G_Dt;
131  _omega += _omega_I;
133  }
134 }
135 
136 
137 /*
138  * reset the DCM matrix and omega. Used on ground start, and on
139  * extreme errors in the matrix
140  */
141 void
142 AP_AHRS_DCM::reset(bool recover_eulers)
143 {
144  // reset the integration terms
145  _omega_I.zero();
146  _omega_P.zero();
147  _omega_yaw_P.zero();
148  _omega.zero();
149 
150  // if the caller wants us to try to recover to the current
151  // attitude then calculate the dcm matrix from the current
152  // roll/pitch/yaw values
153  if (recover_eulers && !isnan(roll) && !isnan(pitch) && !isnan(yaw)) {
155  } else {
156 
157  // Use the measured accel due to gravity to calculate an initial
158  // roll and pitch estimate
159 
160  AP_InertialSensor &_ins = AP::ins();
161 
162  // Get body frame accel vector
163  Vector3f initAccVec = _ins.get_accel();
164  uint8_t counter = 0;
165 
166  // the first vector may be invalid as the filter starts up
167  while ((initAccVec.length() < 9.0f || initAccVec.length() > 11) && counter++ < 20) {
168  _ins.wait_for_sample();
169  _ins.update();
170  initAccVec = _ins.get_accel();
171  }
172 
173  // normalise the acceleration vector
174  if (initAccVec.length() > 5.0f) {
175  // calculate initial pitch angle
176  pitch = atan2f(initAccVec.x, norm(initAccVec.y, initAccVec.z));
177  // calculate initial roll angle
178  roll = atan2f(-initAccVec.y, -initAccVec.z);
179  } else {
180  // If we can't use the accel vector, then align flat
181  roll = 0.0f;
182  pitch = 0.0f;
183  }
185 
186  }
187 
189 }
190 
191 // reset the current attitude, used by HIL
192 void AP_AHRS_DCM::reset_attitude(const float &_roll, const float &_pitch, const float &_yaw)
193 {
194  _dcm_matrix.from_euler(_roll, _pitch, _yaw);
195 }
196 
197 /*
198  * check the DCM matrix for pathological values
199  */
200 void
202 {
203  if (_dcm_matrix.is_nan()) {
204  //Serial.printf("ERROR: DCM matrix NAN\n");
205  AP_AHRS_DCM::reset(true);
206  return;
207  }
208  // some DCM matrix values can lead to an out of range error in
209  // the pitch calculation via asin(). These NaN values can
210  // feed back into the rest of the DCM matrix via the
211  // error_course value.
212  if (!(_dcm_matrix.c.x < 1.0f &&
213  _dcm_matrix.c.x > -1.0f)) {
214  // We have an invalid matrix. Force a normalisation.
215  normalize();
216 
217  if (_dcm_matrix.is_nan() ||
218  fabsf(_dcm_matrix.c.x) > 10) {
219  // normalisation didn't fix the problem! We're
220  // in real trouble. All we can do is reset
221  //Serial.printf("ERROR: DCM matrix error. _dcm_matrix.c.x=%f\n",
222  // _dcm_matrix.c.x);
223  AP_AHRS_DCM::reset(true);
224  }
225  }
226 }
227 
228 // renormalise one vector component of the DCM matrix
229 // this will return false if renormalization fails
230 bool
232 {
233  // numerical errors will slowly build up over time in DCM,
234  // causing inaccuracies. We can keep ahead of those errors
235  // using the renormalization technique from the DCM IMU paper
236  // (see equations 18 to 21).
237 
238  // For APM we don't bother with the taylor expansion
239  // optimisation from the paper as on our 2560 CPU the cost of
240  // the sqrt() is 44 microseconds, and the small time saving of
241  // the taylor expansion is not worth the potential of
242  // additional error buildup.
243 
244  // Note that we can get significant renormalisation values
245  // when we have a larger delta_t due to a glitch eleswhere in
246  // APM, such as a I2c timeout or a set of EEPROM writes. While
247  // we would like to avoid these if possible, if it does happen
248  // we don't want to compound the error by making DCM less
249  // accurate.
250 
251  const float renorm_val = 1.0f / a.length();
252 
253  // keep the average for reporting
254  _renorm_val_sum += renorm_val;
256 
257  if (!(renorm_val < 2.0f && renorm_val > 0.5f)) {
258  // this is larger than it should get - log it as a warning
259  if (!(renorm_val < 1.0e6f && renorm_val > 1.0e-6f)) {
260  // we are getting values which are way out of
261  // range, we will reset the matrix and hope we
262  // can recover our attitude using drift
263  // correction before we hit the ground!
264  //Serial.printf("ERROR: DCM renormalisation error. renorm_val=%f\n",
265  // renorm_val);
266  return false;
267  }
268  }
269 
270  result = a * renorm_val;
271  return true;
272 }
273 
274 /*************************************************
275  * Direction Cosine Matrix IMU: Theory
276  * William Premerlani and Paul Bizard
277  *
278  * Numerical errors will gradually reduce the orthogonality conditions expressed by equation 5
279  * to approximations rather than identities. In effect, the axes in the two frames of reference no
280  * longer describe a rigid body. Fortunately, numerical error accumulates very slowly, so it is a
281  * simple matter to stay ahead of it.
282  * We call the process of enforcing the orthogonality conditions ÒrenormalizationÓ.
283  */
284 void
286 {
287  const float error = _dcm_matrix.a * _dcm_matrix.b; // eq.18
288 
289  const Vector3f t0 = _dcm_matrix.a - (_dcm_matrix.b * (0.5f * error)); // eq.19
290  const Vector3f t1 = _dcm_matrix.b - (_dcm_matrix.a * (0.5f * error)); // eq.19
291  const Vector3f t2 = t0 % t1; // c= a x b // eq.20
292 
293  if (!renorm(t0, _dcm_matrix.a) ||
294  !renorm(t1, _dcm_matrix.b) ||
295  !renorm(t2, _dcm_matrix.c)) {
296  // Our solution is blowing up and we will force back
297  // to last euler angles
299  AP_AHRS_DCM::reset(true);
300  }
301 }
302 
303 
304 // produce a yaw error value. The returned value is proportional
305 // to sin() of the current heading error in earth frame
306 float
308 {
309  const Vector3f &mag = _compass->get_field();
310  // get the mag vector in the earth frame
311  Vector2f rb = _dcm_matrix.mulXY(mag);
312 
313  if (rb.length() < FLT_EPSILON) {
314  return 0.0f;
315  }
316 
317  rb.normalize();
318  if (rb.is_inf()) {
319  // not a valid vector
320  return 0.0f;
321  }
322 
323  // update vector holding earths magnetic field (if required)
328  }
329 
330  // calculate the error term in earth frame
331  // calculate the Z component of the cross product of rb and _mag_earth
332  return rb % _mag_earth;
333 }
334 
335 // the _P_gain raises the gain of the PI controller
336 // when we are spinning fast. See the fastRotations
337 // paper from Bill.
338 float
339 AP_AHRS_DCM::_P_gain(float spin_rate)
340 {
341  if (spin_rate < ToRad(50)) {
342  return 1.0f;
343  }
344  if (spin_rate > ToRad(500)) {
345  return 10.0f;
346  }
347  return spin_rate/ToRad(50);
348 }
349 
350 // _yaw_gain reduces the gain of the PI controller applied to heading errors
351 // when observability from change of velocity is good (eg changing speed or turning)
352 // This reduces unwanted roll and pitch coupling due to compass errors for planes.
353 // High levels of noise on _accel_ef will cause the gain to drop and could lead to
354 // increased heading drift during straight and level flight, however some gain is
355 // always available. TODO check the necessity of adding adjustable acc threshold
356 // and/or filtering accelerations before getting magnitude
357 float
359 {
360  const float VdotEFmag = norm(_accel_ef[_active_accel_instance].x,
362  if (VdotEFmag <= 4.0f) {
363  return 0.2f*(4.5f - VdotEFmag);
364  }
365  return 0.1f;
366 }
367 
368 
369 // return true if we have and should use GPS
370 bool AP_AHRS_DCM::have_gps(void) const
371 {
372  if (AP::gps().status() <= AP_GPS::NO_FIX || !_gps_use) {
373  return false;
374  }
375  return true;
376 }
377 
378 /*
379  when we are getting the initial attitude we want faster gains so
380  that if the board starts upside down we quickly approach the right
381  attitude.
382  We don't want to keep those high gains for too long though as high P
383  gains cause slow gyro offset learning. So we keep the high gains for
384  a maximum of 20 seconds
385  */
387 {
388  return !hal.util->get_soft_armed() && (AP_HAL::millis() - _last_startup_ms) < 20000U;
389 }
390 
391 
392 // return true if we should use the compass for yaw correction
394 {
395  if (!_compass || !_compass->use_for_yaw()) {
396  // no compass available
397  return false;
398  }
399  if (!_flags.fly_forward || !have_gps()) {
400  // we don't have any alterative to the compass
401  return true;
402  }
403  if (AP::gps().ground_speed() < GPS_SPEED_MIN) {
404  // we are not going fast enough to use the GPS
405  return true;
406  }
407 
408  // if the current yaw differs from the GPS yaw by more than 45
409  // degrees and the estimated wind speed is less than 80% of the
410  // ground speed, then switch to GPS navigation. This will help
411  // prevent flyaways with very bad compass offsets
412  const int32_t error = abs(wrap_180_cd(yaw_sensor - AP::gps().ground_course_cd()));
413  if (error > 4500 && _wind.length() < AP::gps().ground_speed()*0.8f) {
414  if (AP_HAL::millis() - _last_consistent_heading > 2000) {
415  // start using the GPS for heading if the compass has been
416  // inconsistent with the GPS for 2 seconds
417  return false;
418  }
419  } else {
421  }
422 
423  // use the compass
424  return true;
425 }
426 
427 // yaw drift correction using the compass or GPS
428 // this function prodoces the _omega_yaw_P vector, and also
429 // contributes to the _omega_I.z long term yaw drift estimate
430 void
432 {
433  bool new_value = false;
434  float yaw_error;
435  float yaw_deltat;
436 
437  const AP_GPS &_gps = AP::gps();
438 
439  if (AP_AHRS_DCM::use_compass()) {
440  /*
441  we are using compass for yaw
442  */
444  yaw_deltat = (_compass->last_update_usec() - _compass_last_update) * 1.0e-6f;
446  // we force an additional compass read()
447  // here. This has the effect of throwing away
448  // the first compass value, which can be bad
449  if (!_flags.have_initial_yaw && _compass->read()) {
450  const float heading = _compass->calculate_heading(_dcm_matrix);
451  _dcm_matrix.from_euler(roll, pitch, heading);
452  _omega_yaw_P.zero();
453  _flags.have_initial_yaw = true;
454  }
455  new_value = true;
456  yaw_error = yaw_error_compass();
457 
458  // also update the _gps_last_update, so if we later
459  // disable the compass due to significant yaw error we
460  // don't suddenly change yaw with a reset
462  }
463  } else if (_flags.fly_forward && have_gps()) {
464  /*
465  we are using GPS for yaw
466  */
467  if (_gps.last_fix_time_ms() != _gps_last_update &&
468  _gps.ground_speed() >= GPS_SPEED_MIN) {
469  yaw_deltat = (_gps.last_fix_time_ms() - _gps_last_update) * 1.0e-3f;
471  new_value = true;
472  const float gps_course_rad = ToRad(_gps.ground_course_cd() * 0.01f);
473  const float yaw_error_rad = wrap_PI(gps_course_rad - yaw);
474  yaw_error = sinf(yaw_error_rad);
475 
476  /* reset yaw to match GPS heading under any of the
477  following 3 conditions:
478 
479  1) if we have reached GPS_SPEED_MIN and have never had
480  yaw information before
481 
482  2) if the last time we got yaw information from the GPS
483  is more than 20 seconds ago, which means we may have
484  suffered from considerable gyro drift
485 
486  3) if we are over 3*GPS_SPEED_MIN (which means 9m/s)
487  and our yaw error is over 60 degrees, which means very
488  poor yaw. This can happen on bungee launch when the
489  operator pulls back the plane rapidly enough then on
490  release the GPS heading changes very rapidly
491  */
492  if (!_flags.have_initial_yaw ||
493  yaw_deltat > 20 ||
494  (_gps.ground_speed() >= 3*GPS_SPEED_MIN && fabsf(yaw_error_rad) >= 1.047f)) {
495  // reset DCM matrix based on current yaw
496  _dcm_matrix.from_euler(roll, pitch, gps_course_rad);
497  _omega_yaw_P.zero();
498  _flags.have_initial_yaw = true;
499  yaw_error = 0;
500  }
501  }
502  }
503 
504  if (!new_value) {
505  // we don't have any new yaw information
506  // slowly decay _omega_yaw_P to cope with loss
507  // of our yaw source
508  _omega_yaw_P *= 0.97f;
509  return;
510  }
511 
512  // convert the error vector to body frame
513  const float error_z = _dcm_matrix.c.z * yaw_error;
514 
515  // the spin rate changes the P gain, and disables the
516  // integration at higher rates
517  const float spin_rate = _omega.length();
518 
519  // sanity check _kp_yaw
520  if (_kp_yaw < AP_AHRS_YAW_P_MIN) {
522  }
523 
524  // update the proportional control to drag the
525  // yaw back to the right value. We use a gain
526  // that depends on the spin rate. See the fastRotations.pdf
527  // paper from Bill Premerlani
528  // We also adjust the gain depending on the rate of change of horizontal velocity which
529  // is proportional to how observable the heading is from the acceerations and GPS velocity
530  // The accelration derived heading will be more reliable in turns than compass or GPS
531 
532  _omega_yaw_P.z = error_z * _P_gain(spin_rate) * _kp_yaw * _yaw_gain();
533  if (use_fast_gains()) {
534  _omega_yaw_P.z *= 8;
535  }
536 
537  // don't update the drift term if we lost the yaw reference
538  // for more than 2 seconds
539  if (yaw_deltat < 2.0f && spin_rate < ToRad(SPIN_RATE_LIMIT)) {
540  // also add to the I term
541  _omega_I_sum.z += error_z * _ki_yaw * yaw_deltat;
542  }
543 
544  _error_yaw = 0.8f * _error_yaw + 0.2f * fabsf(yaw_error);
545 }
546 
547 
552 Vector3f AP_AHRS_DCM::ra_delayed(uint8_t instance, const Vector3f &ra)
553 {
554  // get the old element, and then fill it with the new element
555  const Vector3f ret = _ra_delay_buffer[instance];
556  _ra_delay_buffer[instance] = ra;
557  if (ret.is_zero()) {
558  // use the current vector if the previous vector is exactly
559  // zero. This prevents an error on initialisation
560  return ra;
561  }
562  return ret;
563 }
564 
565 // perform drift correction. This function aims to update _omega_P and
566 // _omega_I with our best estimate of the short term and long term
567 // gyro error. The _omega_P value is what pulls our attitude solution
568 // back towards the reference vector quickly. The _omega_I term is an
569 // attempt to learn the long term drift rate of the gyros.
570 //
571 // This drift correction implementation is based on a paper
572 // by Bill Premerlani from here:
573 // http://gentlenav.googlecode.com/files/RollPitchDriftCompensation.pdf
574 void
576 {
577  Vector3f velocity;
578  uint32_t last_correction_time;
579 
580  // perform yaw drift correction if we have a new yaw reference
581  // vector
583 
584  const AP_InertialSensor &_ins = AP::ins();
585 
586  // rotate accelerometer values into the earth frame
587  for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
588  if (_ins.get_accel_health(i)) {
589  /*
590  by using get_delta_velocity() instead of get_accel() the
591  accel value is sampled over the right time delta for
592  each sensor, which prevents an aliasing effect
593  */
594  Vector3f delta_velocity;
595  _ins.get_delta_velocity(i, delta_velocity);
596  const float delta_velocity_dt = _ins.get_delta_velocity_dt(i);
597  if (delta_velocity_dt > 0) {
598  _accel_ef[i] = _dcm_matrix * (delta_velocity / delta_velocity_dt);
599  // integrate the accel vector in the earth frame between GPS readings
600  _ra_sum[i] += _accel_ef[i] * deltat;
601  }
602  }
603  }
604 
605  //update _accel_ef_blended
606  if (_ins.get_accel_count() == 2 && _ins.use_accel(0) && _ins.use_accel(1)) {
607  const float imu1_weight_target = _active_accel_instance == 0 ? 1.0f : 0.0f;
608  // slew _imu1_weight over one second
609  _imu1_weight += constrain_float(imu1_weight_target-_imu1_weight, -deltat, deltat);
611  } else {
613  }
614 
615  // keep a sum of the deltat values, so we know how much time
616  // we have integrated over
617  _ra_deltat += deltat;
618 
619  const AP_GPS &_gps = AP::gps();
620 
621  if (!have_gps() ||
622  _gps.status() < AP_GPS::GPS_OK_FIX_3D ||
623  _gps.num_sats() < _gps_minsats) {
624  // no GPS, or not a good lock. From experience we need at
625  // least 6 satellites to get a really reliable velocity number
626  // from the GPS.
627  //
628  // As a fallback we use the fixed wing acceleration correction
629  // if we have an airspeed estimate (which we only have if
630  // _fly_forward is set), otherwise no correction
631  if (_ra_deltat < 0.2f) {
632  // not enough time has accumulated
633  return;
634  }
635  float airspeed;
636  if (airspeed_sensor_enabled()) {
637  airspeed = _airspeed->get_airspeed();
638  } else {
639  airspeed = _last_airspeed;
640  }
641  // use airspeed to estimate our ground velocity in
642  // earth frame by subtracting the wind
643  velocity = _dcm_matrix.colx() * airspeed;
644 
645  // add in wind estimate
646  velocity += _wind;
647 
648  last_correction_time = AP_HAL::millis();
649  _have_gps_lock = false;
650  } else {
651  if (_gps.last_fix_time_ms() == _ra_sum_start) {
652  // we don't have a new GPS fix - nothing more to do
653  return;
654  }
655  velocity = _gps.velocity();
656  last_correction_time = _gps.last_fix_time_ms();
657  if (_have_gps_lock == false) {
658  // if we didn't have GPS lock in the last drift
659  // correction interval then set the velocities equal
660  _last_velocity = velocity;
661  }
662  _have_gps_lock = true;
663 
664  // keep last airspeed estimate for dead-reckoning purposes
665  Vector3f airspeed = velocity - _wind;
666  airspeed.z = 0;
667  _last_airspeed = airspeed.length();
668  }
669 
670  if (have_gps()) {
671  // use GPS for positioning with any fix, even a 2D fix
672  _last_lat = _gps.location().lat;
673  _last_lng = _gps.location().lng;
676 
677  // once we have a single GPS lock, we can update using
678  // dead-reckoning from then on
679  _have_position = true;
680  } else {
681  // update dead-reckoning position estimate
682  _position_offset_north += velocity.x * _ra_deltat;
683  _position_offset_east += velocity.y * _ra_deltat;
684  }
685 
686  // see if this is our first time through - in which case we
687  // just setup the start times and return
688  if (_ra_sum_start == 0) {
689  _ra_sum_start = last_correction_time;
690  _last_velocity = velocity;
691  return;
692  }
693 
694  // equation 9: get the corrected acceleration vector in earth frame. Units
695  // are m/s/s
696  Vector3f GA_e(0.0f, 0.0f, -1.0f);
697 
698  if (_ra_deltat <= 0) {
699  // waiting for more data
700  return;
701  }
702 
703  bool using_gps_corrections = false;
704  float ra_scale = 1.0f/(_ra_deltat*GRAVITY_MSS);
705 
707  const float v_scale = gps_gain.get() * ra_scale;
708  const Vector3f vdelta = (velocity - _last_velocity) * v_scale;
709  GA_e += vdelta;
710  GA_e.normalize();
711  if (GA_e.is_inf()) {
712  // wait for some non-zero acceleration information
714  return;
715  }
716  using_gps_corrections = true;
717  }
718 
719  // calculate the error term in earth frame.
720  // we do this for each available accelerometer then pick the
721  // accelerometer that leads to the smallest error term. This takes
722  // advantage of the different sample rates on different
723  // accelerometers to dramatically reduce the impact of aliasing
724  // due to harmonics of vibrations that match closely the sampling
725  // rate of our accelerometers. On the Pixhawk we have the LSM303D
726  // running at 800Hz and the MPU6000 running at 1kHz, by combining
727  // the two the effects of aliasing are greatly reduced.
729  float error_dirn[INS_MAX_INSTANCES];
731  int8_t besti = -1;
732  float best_error = 0;
733  for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
734  if (!_ins.get_accel_health(i)) {
735  // only use healthy sensors
736  continue;
737  }
738  _ra_sum[i] *= ra_scale;
739 
740  // get the delayed ra_sum to match the GPS lag
741  if (using_gps_corrections) {
742  GA_b[i] = ra_delayed(i, _ra_sum[i]);
743  } else {
744  GA_b[i] = _ra_sum[i];
745  }
746  if (GA_b[i].is_zero()) {
747  // wait for some non-zero acceleration information
748  continue;
749  }
750  GA_b[i].normalize();
751  if (GA_b[i].is_inf()) {
752  // wait for some non-zero acceleration information
753  continue;
754  }
755  error[i] = GA_b[i] % GA_e;
756  // Take dot product to catch case vectors are opposite sign and parallel
757  error_dirn[i] = GA_b[i] * GA_e;
758  const float error_length = error[i].length();
759  if (besti == -1 || error_length < best_error) {
760  besti = i;
761  best_error = error_length;
762  }
763  // Catch case where orientation is 180 degrees out
764  if (error_dirn[besti] < 0.0f) {
765  best_error = 1.0f;
766  }
767 
768  }
769 
770  if (besti == -1) {
771  // no healthy accelerometers!
773  return;
774  }
775 
776  _active_accel_instance = besti;
777 
778 #define YAW_INDEPENDENT_DRIFT_CORRECTION 0
779 #if YAW_INDEPENDENT_DRIFT_CORRECTION
780  // step 2 calculate earth_error_Z
781  const float earth_error_Z = error.z;
782 
783  // equation 10
784  const float tilt = norm(GA_e.x, GA_e.y);
785 
786  // equation 11
787  const float theta = atan2f(GA_b[besti].y, GA_b[besti].x);
788 
789  // equation 12
790  const Vector3f GA_e2 = Vector3f(cosf(theta)*tilt, sinf(theta)*tilt, GA_e.z);
791 
792  // step 6
793  error = GA_b[besti] % GA_e2;
794  error.z = earth_error_Z;
795 #endif // YAW_INDEPENDENT_DRIFT_CORRECTION
796 
797  // to reduce the impact of two competing yaw controllers, we
798  // reduce the impact of the gps/accelerometers on yaw when we are
799  // flat, but still allow for yaw correction using the
800  // accelerometers at high roll angles as long as we have a GPS
801  if (AP_AHRS_DCM::use_compass()) {
802  if (have_gps() && is_equal(gps_gain.get(), 1.0f)) {
803  error[besti].z *= sinf(fabsf(roll));
804  } else {
805  error[besti].z = 0;
806  }
807  }
808 
809  // if ins is unhealthy then stop attitude drift correction and
810  // hope the gyros are OK for a while. Just slowly reduce _omega_P
811  // to prevent previous bad accels from throwing us off
812  if (!_ins.healthy()) {
813  error[besti].zero();
814  } else {
815  // convert the error term to body frame
816  error[besti] = _dcm_matrix.mul_transpose(error[besti]);
817  }
818 
819  if (error[besti].is_nan() || error[besti].is_inf()) {
820  // don't allow bad values
821  check_matrix();
823  return;
824  }
825 
826  _error_rp = 0.8f * _error_rp + 0.2f * best_error;
827 
828  // base the P gain on the spin rate
829  const float spin_rate = _omega.length();
830 
831  // sanity check _kp value
832  if (_kp < AP_AHRS_RP_P_MIN) {
834  }
835 
836  // we now want to calculate _omega_P and _omega_I. The
837  // _omega_P value is what drags us quickly to the
838  // accelerometer reading.
839  _omega_P = error[besti] * _P_gain(spin_rate) * _kp;
840  if (use_fast_gains()) {
841  _omega_P *= 8;
842  }
843 
844  if (_flags.fly_forward && _gps.status() >= AP_GPS::GPS_OK_FIX_2D &&
845  _gps.ground_speed() < GPS_SPEED_MIN &&
846  _ins.get_accel().x >= 7 &&
847  pitch_sensor > -3000 && pitch_sensor < 3000) {
848  // assume we are in a launch acceleration, and reduce the
849  // rp gain by 50% to reduce the impact of GPS lag on
850  // takeoff attitude when using a catapult
851  _omega_P *= 0.5f;
852  }
853 
854  // accumulate some integrator error
855  if (spin_rate < ToRad(SPIN_RATE_LIMIT)) {
856  _omega_I_sum += error[besti] * _ki * _ra_deltat;
858  }
859 
860  if (_omega_I_sum_time >= 5) {
861  // limit the rate of change of omega_I to the hardware
862  // reported maximum gyro drift rate. This ensures that
863  // short term errors don't cause a buildup of omega_I
864  // beyond the physical limits of the device
865  const float change_limit = _gyro_drift_limit * _omega_I_sum_time;
866  _omega_I_sum.x = constrain_float(_omega_I_sum.x, -change_limit, change_limit);
867  _omega_I_sum.y = constrain_float(_omega_I_sum.y, -change_limit, change_limit);
868  _omega_I_sum.z = constrain_float(_omega_I_sum.z, -change_limit, change_limit);
870  _omega_I_sum.zero();
871  _omega_I_sum_time = 0;
872  }
873 
874  // zero our accumulator ready for the next GPS step
875  memset(&_ra_sum[0], 0, sizeof(_ra_sum));
876  _ra_deltat = 0;
877  _ra_sum_start = last_correction_time;
878 
879  // remember the velocity for next time
880  _last_velocity = velocity;
881 }
882 
883 
884 // update our wind speed estimate
886 {
887  if (!_flags.wind_estimation) {
888  return;
889  }
890  const Vector3f &velocity = _last_velocity;
891 
892  // this is based on the wind speed estimation code from MatrixPilot by
893  // Bill Premerlani. Adaption for ArduPilot by Jon Challinger
894  // See http://gentlenav.googlecode.com/files/WindEstimation.pdf
895  const Vector3f fuselageDirection = _dcm_matrix.colx();
896  const Vector3f fuselageDirectionDiff = fuselageDirection - _last_fuse;
897  const uint32_t now = AP_HAL::millis();
898 
899  // scrap our data and start over if we're taking too long to get a direction change
900  if (now - _last_wind_time > 10000) {
901  _last_wind_time = now;
902  _last_fuse = fuselageDirection;
903  _last_vel = velocity;
904  return;
905  }
906 
907  float diff_length = fuselageDirectionDiff.length();
908  if (diff_length > 0.2f) {
909  // when turning, use the attitude response to estimate
910  // wind speed
911  float V;
912  const Vector3f velocityDiff = velocity - _last_vel;
913 
914  // estimate airspeed it using equation 6
915  V = velocityDiff.length() / diff_length;
916 
917  const Vector3f fuselageDirectionSum = fuselageDirection + _last_fuse;
918  const Vector3f velocitySum = velocity + _last_vel;
919 
920  _last_fuse = fuselageDirection;
921  _last_vel = velocity;
922 
923  const float theta = atan2f(velocityDiff.y, velocityDiff.x) - atan2f(fuselageDirectionDiff.y, fuselageDirectionDiff.x);
924  const float sintheta = sinf(theta);
925  const float costheta = cosf(theta);
926 
927  Vector3f wind = Vector3f();
928  wind.x = velocitySum.x - V * (costheta * fuselageDirectionSum.x - sintheta * fuselageDirectionSum.y);
929  wind.y = velocitySum.y - V * (sintheta * fuselageDirectionSum.x + costheta * fuselageDirectionSum.y);
930  wind.z = velocitySum.z - V * fuselageDirectionSum.z;
931  wind *= 0.5f;
932 
933  if (wind.length() < _wind.length() + 20) {
934  _wind = _wind * 0.95f + wind * 0.05f;
935  }
936 
937  _last_wind_time = now;
938  } else if (now - _last_wind_time > 2000 && airspeed_sensor_enabled()) {
939  // when flying straight use airspeed to get wind estimate if available
941  const Vector3f wind = velocity - (airspeed * get_EAS2TAS());
942  _wind = _wind * 0.92f + wind * 0.08f;
943  }
944 }
945 
946 
947 
948 // calculate the euler angles and DCM matrix which will be used for high level
949 // navigation control. Apply trim such that a positive trim value results in a
950 // positive vehicle rotation about that axis (ie a negative offset)
951 void
953 {
956 
958 }
959 
960 // return our current position estimate using
961 // dead-reckoning or GPS
962 bool AP_AHRS_DCM::get_position(struct Location &loc) const
963 {
964  loc.lat = _last_lat;
965  loc.lng = _last_lng;
966  loc.alt = AP::baro().get_altitude() * 100 + _home.alt;
967  loc.flags.relative_alt = 0;
968  loc.flags.terrain_alt = 0;
970  const AP_GPS &_gps = AP::gps();
972  float gps_delay_sec = 0;
973  _gps.get_lag(gps_delay_sec);
974  location_update(loc, _gps.ground_course_cd() * 0.01f, _gps.ground_speed() * gps_delay_sec);
975  }
976  return _have_position;
977 }
978 
979 // return an airspeed estimate if available
980 bool AP_AHRS_DCM::airspeed_estimate(float *airspeed_ret) const
981 {
982  bool ret = false;
983  if (airspeed_sensor_enabled()) {
984  *airspeed_ret = _airspeed->get_airspeed();
985  return true;
986  }
987 
988  if (!_flags.wind_estimation) {
989  return false;
990  }
991 
992  // estimate it via GPS speed and wind
993  if (have_gps()) {
994  *airspeed_ret = _last_airspeed;
995  ret = true;
996  }
997 
998  if (ret && _wind_max > 0 && AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
999  // constrain the airspeed by the ground speed
1000  // and AHRS_WIND_MAX
1001  const float gnd_speed = AP::gps().ground_speed();
1002  float true_airspeed = *airspeed_ret * get_EAS2TAS();
1003  true_airspeed = constrain_float(true_airspeed,
1004  gnd_speed - _wind_max,
1005  gnd_speed + _wind_max);
1006  *airspeed_ret = true_airspeed / get_EAS2TAS();
1007  }
1008  return ret;
1009 }
1010 
1012 {
1013  _home = loc;
1014  _home.options = 0;
1015  _home_is_set = true;
1016 }
1017 
1018 // a relative ground position to home in meters, Down
1020 {
1021  posD = -AP::baro().get_altitude();
1022 }
1023 
1024 /*
1025  check if the AHRS subsystem is healthy
1026 */
1027 bool AP_AHRS_DCM::healthy(void) const
1028 {
1029  // consider ourselves healthy if there have been no failures for 5 seconds
1030  return (_last_failure_ms == 0 || AP_HAL::millis() - _last_failure_ms > 5000);
1031 }
1032 
1033 /*
1034  return amount of time that AHRS has been up
1035  */
1036 uint32_t AP_AHRS_DCM::uptime_ms(void) const
1037 {
1038  if (_last_startup_ms == 0) {
1039  return 0;
1040  }
1041  return AP_HAL::millis() - _last_startup_ms;
1042 }
t2
Definition: calcH_MAG.c:1
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
void to_euler(float *roll, float *pitch, float *yaw) const
Definition: matrix3.cpp:49
void estimate_wind(void)
bool get_soft_armed() const
Definition: Util.h:15
Definition: AP_GPS.h:48
void location_update(struct Location &loc, float bearing, float distance)
Definition: location.cpp:115
float _ki_yaw
Definition: AP_AHRS_DCM.h:107
float roll
Definition: AP_AHRS.h:224
static uint8_t counter
bool use_fast_gains(void) const
float _P_gain(float spin_rate)
uint8_t have_initial_yaw
Definition: AP_AHRS.h:595
AP_Int8 _wind_max
Definition: AP_AHRS.h:582
void set_home(const Location &loc) override
Vector3< float > Vector3f
Definition: vector3.h:246
bool use_for_yaw(uint8_t i) const
return true if the compass should be used for yaw calculations
bool _home_is_set
Definition: AP_AHRS.h:656
float get_declination() const
Vector3f _omega
Definition: AP_AHRS_DCM.h:132
Vector3f _omega_yaw_P
Definition: AP_AHRS_DCM.h:128
bool is_inf(void) const
Definition: vector3.cpp:321
AP_Airspeed * _airspeed
Definition: AP_AHRS.h:624
bool use_compass() override
Matrix3f _dcm_matrix
Definition: AP_AHRS_DCM.h:122
void get_relative_position_D_home(float &posD) const override
Vector3f _last_vel
Definition: AP_AHRS_DCM.h:179
float _position_offset_east
Definition: AP_AHRS_DCM.h:172
AP_Float _kp
Definition: AP_AHRS.h:577
Vector2< T > mulXY(const Vector3< T > &v) const
Definition: matrix3.cpp:157
#define GPS_SPEED_MIN
Definition: AP_AHRS_DCM.cpp:30
#define ToRad(x)
Definition: AP_Common.h:53
Vector2f _mag_earth
Definition: AP_AHRS_DCM.h:161
Vector3f _last_fuse
Definition: AP_AHRS_DCM.h:178
int32_t _last_lng
Definition: AP_AHRS_DCM.h:168
bool healthy(void) const
AP_Int8 _gps_minsats
Definition: AP_AHRS.h:584
bool is_inf(void) const
Definition: vector2.cpp:72
float get_airspeed(uint8_t i) const
Definition: AP_Airspeed.h:53
Vector3f _last_velocity
Definition: AP_AHRS_DCM.h:155
AP_Float _kp_yaw
Definition: AP_AHRS.h:576
float pitch
Definition: AP_AHRS.h:225
float _last_declination
Definition: AP_AHRS_DCM.h:160
AP_HAL::Util * util
Definition: HAL.h:115
Matrix3f _body_dcm_matrix
Definition: AP_AHRS_DCM.h:125
void from_euler(float roll, float pitch, float yaw)
Definition: matrix3.cpp:26
uint32_t last_fix_time_ms(uint8_t instance) const
Definition: AP_GPS.h:301
bool read()
Definition: AP_Compass.cpp:979
float yaw
Definition: AP_AHRS.h:226
void update(bool skip_ins_update=false) override
Definition: AP_AHRS_DCM.cpp:50
Vector3f _ra_sum[INS_MAX_INSTANCES]
Definition: AP_AHRS_DCM.h:154
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
Definition: AP_Math.cpp:111
bool get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
Definition: location.cpp:125
Vector3f _accel_ef_blended
Definition: AP_AHRS.h:646
bool use_accel(uint8_t instance) const
void euler_angles(void)
bool have_gps(void) const
const char * result
Definition: Printf.cpp:16
AP_Float gps_gain
Definition: AP_AHRS.h:578
void reset_attitude(const float &roll, const float &pitch, const float &yaw) override
const Location & location(uint8_t instance) const
Definition: AP_GPS.h:200
void reset_gyro_drift() override
Definition: AP_AHRS_DCM.cpp:41
virtual void update_AOA_SSA(void)
Definition: AP_AHRS.cpp:387
uint8_t correct_centrifugal
Definition: AP_AHRS.h:597
#define AP_AHRS_RP_P_MIN
Definition: AP_AHRS.h:35
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
int32_t ground_course_cd(uint8_t instance) const
Definition: AP_GPS.h:252
t0
Definition: calcTms.c:1
uint32_t _last_consistent_heading
Definition: AP_AHRS_DCM.h:182
float calculate_heading(const Matrix3f &dcm_matrix) const
Definition: AP_Compass.h:87
const Vector3f & get_accel(uint8_t i) const
const Vector3f & get_field(uint8_t i) const
Return the current field as a Vector3f in milligauss.
Definition: AP_Compass.h:122
bool renorm(Vector3f const &a, Vector3f &result)
T y
Definition: vector2.h:37
uint8_t get_primary_accel(void) const
bool get_delta_angle(uint8_t i, Vector3f &delta_angle) const
bool healthy() const override
#define x(i)
bool airspeed_estimate(float *airspeed_ret) const override
uint32_t _last_wind_time
Definition: AP_AHRS_DCM.h:180
uint32_t _ra_sum_start
Definition: AP_AHRS_DCM.h:157
uint32_t _last_failure_ms
Definition: AP_AHRS_DCM.h:190
const Vector3f & velocity(uint8_t instance) const
Definition: AP_GPS.h:224
float wrap_PI(const T radian)
Definition: AP_Math.cpp:152
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
float _gyro_drift_limit
Definition: AP_AHRS.h:642
int32_t pitch_sensor
Definition: AP_AHRS.h:230
virtual bool get_position(struct Location &loc) const override
float yaw_error_compass()
void update_cd_values(void)
Definition: AP_AHRS.cpp:352
#define SPIN_RATE_LIMIT
Definition: AP_AHRS_DCM.cpp:36
#define GRAVITY_MSS
Definition: definitions.h:47
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
void drift_correction(float deltat)
T y
Definition: vector3.h:67
void matrix_update(float _G_Dt)
Vector3< T > c
Definition: matrix3.h:48
uint32_t millis()
Definition: system.cpp:157
const Matrix3f & get_rotation_vehicle_body_to_autopilot_body(void) const
Definition: AP_AHRS.h:264
T z
Definition: vector3.h:67
Vector3f _omega_P
Definition: AP_AHRS_DCM.h:127
bool is_nan(void)
Definition: matrix3.h:227
Receiving valid messages and 2D lock.
Definition: AP_GPS.h:99
float _yaw_gain(void) const
GPS_Status status(uint8_t instance) const
Query GPS status.
Definition: AP_GPS.h:189
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
void normalize()
Definition: vector3.h:176
float _imu1_weight
Definition: AP_AHRS_DCM.h:187
float _error_rp
Definition: AP_AHRS_DCM.h:147
Vector3f _omega_I
Definition: AP_AHRS_DCM.h:129
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
Definition: AP_Common.h:135
uint8_t _active_accel_instance
Definition: AP_AHRS.h:664
Vector3f _wind
Definition: AP_AHRS_DCM.h:185
void check_matrix(void)
float get_delta_time() const
struct Location _home
Definition: AP_AHRS.h:655
float length(void) const
Definition: vector3.cpp:288
Vector3f ra_delayed(uint8_t instance, const Vector3f &ra)
Vector3< T > mul_transpose(const Vector3< T > &v) const
Definition: matrix3.cpp:165
Vector3f _accel_ef[INS_MAX_INSTANCES]
Definition: AP_AHRS.h:645
AP_Int8 _gps_use
Definition: AP_AHRS.h:581
bool _have_gps_lock
Definition: AP_AHRS_DCM.h:164
float length(void) const
Definition: vector2.cpp:24
#define AP_AHRS_YAW_P_MIN
Definition: AP_AHRS.h:36
float _position_offset_north
Definition: AP_AHRS_DCM.h:171
AP_Airspeed airspeed
Definition: Airspeed.cpp:34
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
float get_altitude(void) const
Definition: AP_Baro.h:84
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
uint8_t wind_estimation
Definition: AP_AHRS.h:598
uint8_t num_sats(uint8_t instance) const
Definition: AP_GPS.h:260
uint32_t last_update_usec(void) const
Definition: AP_Compass.h:289
uint16_t _renorm_val_count
Definition: AP_AHRS_DCM.h:146
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
float get_delta_velocity_dt(uint8_t i) const
Receiving valid GPS messages but no lock.
Definition: AP_GPS.h:98
void normalize()
Definition: vector2.h:140
void normalize(void)
void drift_correction_yaw(void)
uint8_t fly_forward
Definition: AP_AHRS.h:596
uint32_t uptime_ms() const override
float _last_airspeed
Definition: AP_AHRS_DCM.h:181
float _ra_deltat
Definition: AP_AHRS_DCM.h:156
#define error(fmt, args ...)
void reset(bool recover_eulers=false) override
float _error_yaw
Definition: AP_AHRS_DCM.h:148
bool is_zero(void) const
Definition: vector3.h:159
uint32_t _compass_last_update
Definition: AP_AHRS.h:630
Compass * _compass
Definition: AP_AHRS.h:618
bool _have_position
Definition: AP_AHRS_DCM.h:175
uint8_t get_gyro_count(void) const
float _omega_I_sum_time
Definition: AP_AHRS_DCM.h:131
float _renorm_val_sum
Definition: AP_AHRS_DCM.h:145
AP_InertialSensor & ins()
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
Vector3< T > b
Definition: matrix3.h:48
bool get_gyro_health(uint8_t instance) const
struct AP_AHRS::ahrs_flags _flags
bool airspeed_sensor_enabled(void) const
Definition: AP_AHRS.h:299
float get_EAS2TAS(void) const
Definition: AP_AHRS.h:290
void rotate(const Vector3< T > &g)
Definition: matrix3.cpp:115
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
void update_trig(void)
Definition: AP_AHRS.cpp:336
AP_Baro & baro()
Definition: AP_Baro.cpp:737
Vector3f _ra_delay_buffer[INS_MAX_INSTANCES]
Definition: AP_AHRS_DCM.h:136
#define INS_MAX_INSTANCES
int32_t yaw_sensor
Definition: AP_AHRS.h:231
Vector3< T > a
Definition: matrix3.h:48
int32_t _last_lat
Definition: AP_AHRS_DCM.h:167
Vector3f _omega_I_sum
Definition: AP_AHRS_DCM.h:130
Vector3< T > colx(void) const
Definition: matrix3.h:157
void zero()
Definition: vector3.h:182
uint32_t _last_startup_ms
Definition: AP_AHRS_DCM.h:193
T x
Definition: vector3.h:67
uint8_t options
Definition: AP_Common.h:136
uint32_t _gps_last_update
Definition: AP_AHRS_DCM.h:151
uint8_t get_accel_count(void) const
bool get_lag(uint8_t instance, float &lag_sec) const
Definition: AP_GPS.cpp:1107
bool get_accel_health(uint8_t instance) const