AP_AHRS_DCM.cpp 38 KB

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