Compass_learn.cpp 7.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236
  1. #include <AP_Math/AP_Math.h>
  2. #include <AP_AHRS/AP_AHRS.h>
  3. #include <AP_Compass/AP_Compass.h>
  4. #include <AP_Declination/AP_Declination.h>
  5. #include <AP_Logger/AP_Logger.h>
  6. #include "Compass_learn.h"
  7. #include <GCS_MAVLink/GCS.h>
  8. #include <stdio.h>
  9. #if COMPASS_LEARN_ENABLED
  10. extern const AP_HAL::HAL &hal;
  11. // constructor
  12. CompassLearn::CompassLearn(Compass &_compass) :
  13. compass(_compass)
  14. {
  15. gcs().send_text(MAV_SEVERITY_INFO, "CompassLearn: Initialised");
  16. }
  17. /*
  18. update when new compass sample available
  19. */
  20. void CompassLearn::update(void)
  21. {
  22. const AP_AHRS &ahrs = AP::ahrs();
  23. if (converged || compass.get_learn_type() != Compass::LEARN_INFLIGHT ||
  24. !hal.util->get_soft_armed() || ahrs.get_time_flying_ms() < 3000) {
  25. // only learn when flying and with enough time to be clear of
  26. // the ground
  27. return;
  28. }
  29. if (!have_earth_field) {
  30. Location loc;
  31. if (!ahrs.get_position(loc)) {
  32. // need to wait till we have a global position
  33. return;
  34. }
  35. // remember primary mag
  36. primary_mag = compass.get_primary();
  37. // setup the expected earth field in mGauss at this location
  38. mag_ef = AP_Declination::get_earth_field_ga(loc) * 1000;
  39. have_earth_field = true;
  40. // form eliptical correction matrix and invert it. This is
  41. // needed to remove the effects of the eliptical correction
  42. // when calculating new offsets
  43. const Vector3f &diagonals = compass.get_diagonals(primary_mag);
  44. const Vector3f &offdiagonals = compass.get_offdiagonals(primary_mag);
  45. mat = Matrix3f(
  46. diagonals.x, offdiagonals.x, offdiagonals.y,
  47. offdiagonals.x, diagonals.y, offdiagonals.z,
  48. offdiagonals.y, offdiagonals.z, diagonals.z
  49. );
  50. if (!mat.invert()) {
  51. // if we can't invert, use the identity matrix
  52. mat.identity();
  53. }
  54. // set initial error to field intensity
  55. float intensity = mag_ef.length();
  56. for (uint16_t i=0; i<num_sectors; i++) {
  57. errors[i] = intensity;
  58. }
  59. gcs().send_text(MAV_SEVERITY_INFO, "CompassLearn: have earth field");
  60. hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&CompassLearn::io_timer, void));
  61. }
  62. AP_Notify::flags.compass_cal_running = true;
  63. if (sample_available) {
  64. // last sample still being processed by IO thread
  65. return;
  66. }
  67. Vector3f field = compass.get_field(primary_mag);
  68. Vector3f field_change = field - last_field;
  69. if (field_change.length() < min_field_change) {
  70. return;
  71. }
  72. {
  73. WITH_SEMAPHORE(sem);
  74. // give a sample to the backend to process
  75. new_sample.field = field;
  76. new_sample.offsets = compass.get_offsets(primary_mag);
  77. new_sample.attitude = Vector3f(ahrs.roll, ahrs.pitch, ahrs.yaw);
  78. sample_available = true;
  79. last_field = field;
  80. num_samples++;
  81. }
  82. if (sample_available) {
  83. AP::logger().Write("COFS", "TimeUS,OfsX,OfsY,OfsZ,Var,Yaw,WVar,N", "QffffffI",
  84. AP_HAL::micros64(),
  85. (double)best_offsets.x,
  86. (double)best_offsets.y,
  87. (double)best_offsets.z,
  88. (double)best_error,
  89. (double)best_yaw_deg,
  90. (double)worst_error,
  91. num_samples);
  92. }
  93. if (!converged) {
  94. WITH_SEMAPHORE(sem);
  95. // set offsets to current best guess
  96. compass.set_offsets(primary_mag, best_offsets);
  97. // set non-primary offsets to match primary
  98. Vector3f field_primary = compass.get_field(primary_mag);
  99. for (uint8_t i=0; i<compass.get_count(); i++) {
  100. if (i == primary_mag || !compass._state[i].use_for_yaw) {
  101. continue;
  102. }
  103. Vector3f field2 = compass.get_field(i);
  104. Vector3f new_offsets = compass.get_offsets(i) + (field_primary - field2);
  105. compass.set_offsets(i, new_offsets);
  106. }
  107. // stop updating the offsets once converged
  108. if (num_samples > 30 && best_error < 50 && worst_error > 65) {
  109. // set the offsets and enable compass for EKF use. Let the
  110. // EKF learn the remaining compass offset error
  111. for (uint8_t i=0; i<compass.get_count(); i++) {
  112. if (compass._state[i].use_for_yaw) {
  113. compass.save_offsets(i);
  114. compass.set_use_for_yaw(i, true);
  115. }
  116. }
  117. compass.set_learn_type(Compass::LEARN_NONE, true);
  118. // setup so use can trigger it again
  119. converged = false;
  120. sample_available = false;
  121. num_samples = 0;
  122. have_earth_field = false;
  123. memset(predicted_offsets, 0, sizeof(predicted_offsets));
  124. worst_error = 0;
  125. best_error = 0;
  126. best_yaw_deg = 0;
  127. best_offsets.zero();
  128. gcs().send_text(MAV_SEVERITY_INFO, "CompassLearn: finished");
  129. AP_Notify::flags.compass_cal_running = false;
  130. AP_Notify::events.compass_cal_saved = true;
  131. }
  132. }
  133. }
  134. /*
  135. we run the math intensive calculations in the IO thread
  136. */
  137. void CompassLearn::io_timer(void)
  138. {
  139. if (!sample_available) {
  140. return;
  141. }
  142. struct sample s;
  143. {
  144. WITH_SEMAPHORE(sem);
  145. s = new_sample;
  146. sample_available = false;
  147. }
  148. process_sample(s);
  149. }
  150. /*
  151. process a new compass sample
  152. */
  153. void CompassLearn::process_sample(const struct sample &s)
  154. {
  155. uint16_t besti = 0;
  156. float bestv = 0, worstv=0;
  157. /*
  158. we run through the 72 possible yaw error values, and for each
  159. one we calculate a value for the compass offsets if that yaw
  160. error is correct.
  161. */
  162. for (uint16_t i=0; i<num_sectors; i++) {
  163. float yaw_err_deg = i*(360/num_sectors);
  164. // form rotation matrix for the euler attitude
  165. Matrix3f dcm;
  166. dcm.from_euler(s.attitude.x, s.attitude.y, wrap_2PI(s.attitude.z + radians(yaw_err_deg)));
  167. // calculate the field we would expect to get if this yaw error is correct
  168. Vector3f expected_field = dcm.transposed() * mag_ef;
  169. // calculate a value for the compass offsets for this yaw error
  170. Vector3f v1 = mat * s.field;
  171. Vector3f v2 = mat * expected_field;
  172. Vector3f offsets = (v2 - v1) + s.offsets;
  173. float delta = (offsets - predicted_offsets[i]).length();
  174. if (num_samples == 1) {
  175. predicted_offsets[i] = offsets;
  176. } else {
  177. // lowpass the predicted offsets and the error
  178. const float learn_rate = 0.92f;
  179. predicted_offsets[i] = predicted_offsets[i] * learn_rate + offsets * (1-learn_rate);
  180. errors[i] = errors[i] * learn_rate + delta * (1-learn_rate);
  181. }
  182. // keep track of the current best prediction
  183. if (i == 0 || errors[i] < bestv) {
  184. besti = i;
  185. bestv = errors[i];
  186. }
  187. // also keep the worst error. This is used as part of the convergence test
  188. if (i == 0 || errors[i] > worstv) {
  189. worstv = errors[i];
  190. }
  191. }
  192. WITH_SEMAPHORE(sem);
  193. // pass the current estimate to the front-end
  194. best_offsets = predicted_offsets[besti];
  195. best_error = bestv;
  196. worst_error = worstv;
  197. best_yaw_deg = wrap_360(degrees(s.attitude.z) + besti * (360/num_sectors));
  198. }
  199. #endif // COMPASS_LEARN_ENABLED