AP_Compass_Backend.cpp 7.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AP_Compass.h"
  3. #include "AP_Compass_Backend.h"
  4. #include <AP_BattMonitor/AP_BattMonitor.h>
  5. extern const AP_HAL::HAL& hal;
  6. AP_Compass_Backend::AP_Compass_Backend()
  7. : _compass(AP::compass())
  8. {
  9. }
  10. void AP_Compass_Backend::rotate_field(Vector3f &mag, uint8_t instance)
  11. {
  12. Compass::mag_state &state = _compass._state[instance];
  13. mag.rotate(MAG_BOARD_ORIENTATION);
  14. mag.rotate(state.rotation);
  15. if (!state.external) {
  16. // and add in AHRS_ORIENTATION setting if not an external compass
  17. if (_compass._board_orientation == ROTATION_CUSTOM && _compass._custom_rotation) {
  18. mag = *_compass._custom_rotation * mag;
  19. } else {
  20. mag.rotate(_compass._board_orientation);
  21. }
  22. } else {
  23. // add user selectable orientation
  24. mag.rotate((enum Rotation)state.orientation.get());
  25. }
  26. }
  27. void AP_Compass_Backend::publish_raw_field(const Vector3f &mag, uint8_t instance)
  28. {
  29. Compass::mag_state &state = _compass._state[instance];
  30. // note that we do not set last_update_usec here as otherwise the
  31. // EKF and DCM would end up consuming compass data at the full
  32. // sensor rate. We want them to consume only the filtered fields
  33. state.last_update_ms = AP_HAL::millis();
  34. #if COMPASS_CAL_ENABLED
  35. _compass._calibrator[instance].new_sample(mag);
  36. #endif
  37. }
  38. void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i)
  39. {
  40. Compass::mag_state &state = _compass._state[i];
  41. if (state.diagonals.get().is_zero()) {
  42. state.diagonals.set(Vector3f(1.0f,1.0f,1.0f));
  43. }
  44. const Vector3f &offsets = state.offset.get();
  45. const Vector3f &diagonals = state.diagonals.get();
  46. const Vector3f &offdiagonals = state.offdiagonals.get();
  47. // add in the basic offsets
  48. mag += offsets;
  49. // apply eliptical correction
  50. Matrix3f mat(
  51. diagonals.x, offdiagonals.x, offdiagonals.y,
  52. offdiagonals.x, diagonals.y, offdiagonals.z,
  53. offdiagonals.y, offdiagonals.z, diagonals.z
  54. );
  55. mag = mat * mag;
  56. #if COMPASS_MOT_ENABLED
  57. const Vector3f &mot = state.motor_compensation.get();
  58. /*
  59. calculate motor-power based compensation
  60. note that _motor_offset[] is kept even if compensation is not
  61. being applied so it can be logged correctly
  62. */
  63. state.motor_offset.zero();
  64. if (_compass._per_motor.enabled() && i == 0) {
  65. // per-motor correction is only valid for first compass
  66. _compass._per_motor.compensate(state.motor_offset);
  67. } else if (_compass._motor_comp_type == AP_COMPASS_MOT_COMP_THROTTLE) {
  68. state.motor_offset = mot * _compass._thr;
  69. } else if (_compass._motor_comp_type == AP_COMPASS_MOT_COMP_CURRENT) {
  70. AP_BattMonitor &battery = AP::battery();
  71. float current;
  72. if (battery.current_amps(current)) {
  73. state.motor_offset = mot * current;
  74. }
  75. }
  76. /*
  77. we apply the motor offsets after we apply the eliptical
  78. correction. This is needed to match the way that the motor
  79. compensation values are calculated, as they are calculated based
  80. on final field outputs, not on the raw outputs
  81. */
  82. mag += state.motor_offset;
  83. #endif // COMPASS_MOT_ENABLED
  84. }
  85. void AP_Compass_Backend::accumulate_sample(Vector3f &field, uint8_t instance,
  86. uint32_t max_samples)
  87. {
  88. /* rotate raw_field from sensor frame to body frame */
  89. rotate_field(field, instance);
  90. /* publish raw_field (uncorrected point sample) for calibration use */
  91. publish_raw_field(field, instance);
  92. /* correct raw_field for known errors */
  93. correct_field(field, instance);
  94. if (!field_ok(field)) {
  95. return;
  96. }
  97. WITH_SEMAPHORE(_sem);
  98. Compass::mag_state &state = _compass._state[instance];
  99. state.accum += field;
  100. state.accum_count++;
  101. if (max_samples && state.accum_count >= max_samples) {
  102. state.accum_count /= 2;
  103. state.accum /= 2;
  104. }
  105. }
  106. void AP_Compass_Backend::drain_accumulated_samples(uint8_t instance,
  107. const Vector3f *scaling)
  108. {
  109. WITH_SEMAPHORE(_sem);
  110. Compass::mag_state &state = _compass._state[instance];
  111. if (state.accum_count == 0) {
  112. return;
  113. }
  114. if (scaling) {
  115. state.accum *= *scaling;
  116. }
  117. state.accum /= state.accum_count;
  118. publish_filtered_field(state.accum, instance);
  119. state.accum.zero();
  120. state.accum_count = 0;
  121. }
  122. /*
  123. copy latest data to the frontend from a backend
  124. */
  125. void AP_Compass_Backend::publish_filtered_field(const Vector3f &mag, uint8_t instance)
  126. {
  127. Compass::mag_state &state = _compass._state[instance];
  128. state.field = mag;
  129. state.last_update_ms = AP_HAL::millis();
  130. state.last_update_usec = AP_HAL::micros();
  131. }
  132. void AP_Compass_Backend::set_last_update_usec(uint32_t last_update, uint8_t instance)
  133. {
  134. Compass::mag_state &state = _compass._state[instance];
  135. state.last_update_usec = last_update;
  136. }
  137. /*
  138. register a new backend with frontend, returning instance which
  139. should be used in publish_field()
  140. */
  141. uint8_t AP_Compass_Backend::register_compass(void) const
  142. {
  143. return _compass.register_compass();
  144. }
  145. /*
  146. set dev_id for an instance
  147. */
  148. void AP_Compass_Backend::set_dev_id(uint8_t instance, uint32_t dev_id)
  149. {
  150. _compass._state[instance].dev_id.set_and_notify(dev_id);
  151. _compass._state[instance].detected_dev_id = dev_id;
  152. }
  153. /*
  154. save dev_id, used by SITL
  155. */
  156. void AP_Compass_Backend::save_dev_id(uint8_t instance)
  157. {
  158. _compass._state[instance].dev_id.save();
  159. }
  160. /*
  161. set external for an instance
  162. */
  163. void AP_Compass_Backend::set_external(uint8_t instance, bool external)
  164. {
  165. if (_compass._state[instance].external != 2) {
  166. _compass._state[instance].external.set_and_notify(external);
  167. }
  168. }
  169. bool AP_Compass_Backend::is_external(uint8_t instance)
  170. {
  171. return _compass._state[instance].external;
  172. }
  173. // set rotation of an instance
  174. void AP_Compass_Backend::set_rotation(uint8_t instance, enum Rotation rotation)
  175. {
  176. _compass._state[instance].rotation = rotation;
  177. }
  178. static constexpr float FILTER_KOEF = 0.1f;
  179. /* Check that the compass value is valid by using a mean filter. If
  180. * the value is further than filtrer_range from mean value, it is
  181. * rejected.
  182. */
  183. bool AP_Compass_Backend::field_ok(const Vector3f &field)
  184. {
  185. if (field.is_inf() || field.is_nan()) {
  186. return false;
  187. }
  188. const float range = (float)_compass.get_filter_range();
  189. if (range <= 0) {
  190. return true;
  191. }
  192. const float length = field.length();
  193. if (is_zero(_mean_field_length)) {
  194. _mean_field_length = length;
  195. return true;
  196. }
  197. bool ret = true;
  198. const float d = fabsf(_mean_field_length - length) / (_mean_field_length + length); // diff divide by mean value in percent ( with the *200.0f on later line)
  199. float koeff = FILTER_KOEF;
  200. if (d * 200.0f > range) { // check the difference from mean value outside allowed range
  201. // printf("\nCompass field length error: mean %f got %f\n", (double)_mean_field_length, (double)length );
  202. ret = false;
  203. koeff /= (d * 10.0f); // 2.5 and more, so one bad sample never change mean more than 4%
  204. _error_count++;
  205. }
  206. _mean_field_length = _mean_field_length * (1 - koeff) + length * koeff; // complimentary filter 1/k
  207. return ret;
  208. }
  209. enum Rotation AP_Compass_Backend::get_board_orientation(void) const
  210. {
  211. return _compass._board_orientation;
  212. }