CompassCalibrator.h 4.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174
  1. #pragma once
  2. #include <AP_Math/AP_Math.h>
  3. #define COMPASS_CAL_NUM_SPHERE_PARAMS 4
  4. #define COMPASS_CAL_NUM_ELLIPSOID_PARAMS 9
  5. #define COMPASS_CAL_NUM_SAMPLES 300
  6. //RMS tolerance
  7. #define COMPASS_CAL_DEFAULT_TOLERANCE 5.0f
  8. enum compass_cal_status_t {
  9. COMPASS_CAL_NOT_STARTED=0,
  10. COMPASS_CAL_WAITING_TO_START=1,
  11. COMPASS_CAL_RUNNING_STEP_ONE=2,
  12. COMPASS_CAL_RUNNING_STEP_TWO=3,
  13. COMPASS_CAL_SUCCESS=4,
  14. COMPASS_CAL_FAILED=5,
  15. COMPASS_CAL_BAD_ORIENTATION=6,
  16. };
  17. class CompassCalibrator {
  18. public:
  19. typedef uint8_t completion_mask_t[10];
  20. CompassCalibrator();
  21. void start(bool retry, float delay, uint16_t offset_max, uint8_t compass_idx);
  22. void clear();
  23. void update(bool &failure);
  24. void new_sample(const Vector3f &sample);
  25. bool check_for_timeout();
  26. bool running() const;
  27. void set_orientation(enum Rotation orientation, bool is_external, bool fix_orientation) {
  28. _check_orientation = true;
  29. _orientation = orientation;
  30. _orig_orientation = orientation;
  31. _is_external = is_external;
  32. _fix_orientation = fix_orientation;
  33. }
  34. void set_tolerance(float tolerance) { _tolerance = tolerance; }
  35. void get_calibration(Vector3f &offsets, Vector3f &diagonals, Vector3f &offdiagonals);
  36. enum Rotation get_orientation(void) { return _orientation; }
  37. enum Rotation get_original_orientation(void) { return _orig_orientation; }
  38. float get_completion_percent() const;
  39. completion_mask_t& get_completion_mask();
  40. enum compass_cal_status_t get_status() const { return _status; }
  41. float get_fitness() const { return sqrtf(_fitness); }
  42. float get_orientation_confidence() const { return _orientation_confidence; }
  43. uint8_t get_attempt() const { return _attempt; }
  44. private:
  45. class param_t {
  46. public:
  47. float* get_sphere_params() {
  48. return &radius;
  49. }
  50. float* get_ellipsoid_params() {
  51. return &offset.x;
  52. }
  53. float radius;
  54. Vector3f offset;
  55. Vector3f diag;
  56. Vector3f offdiag;
  57. };
  58. // compact class for approximate attitude, to save memory
  59. class AttitudeSample {
  60. public:
  61. Matrix3f get_rotmat();
  62. void set_from_ahrs();
  63. private:
  64. int8_t roll;
  65. int8_t pitch;
  66. int8_t yaw;
  67. };
  68. class CompassSample {
  69. public:
  70. Vector3f get() const;
  71. void set(const Vector3f &in);
  72. AttitudeSample att;
  73. private:
  74. int16_t x;
  75. int16_t y;
  76. int16_t z;
  77. };
  78. enum Rotation _orientation;
  79. enum Rotation _orig_orientation;
  80. bool _is_external;
  81. bool _check_orientation;
  82. bool _fix_orientation;
  83. uint8_t _compass_idx;
  84. enum compass_cal_status_t _status;
  85. // timeout watchdog state
  86. uint32_t _last_sample_ms;
  87. // behavioral state
  88. float _delay_start_sec;
  89. uint32_t _start_time_ms;
  90. bool _retry;
  91. float _tolerance;
  92. uint8_t _attempt;
  93. uint16_t _offset_max;
  94. completion_mask_t _completion_mask;
  95. //fit state
  96. class param_t _params;
  97. uint16_t _fit_step;
  98. CompassSample *_sample_buffer;
  99. float _fitness; // mean squared residuals
  100. float _initial_fitness;
  101. float _sphere_lambda;
  102. float _ellipsoid_lambda;
  103. uint16_t _samples_collected;
  104. uint16_t _samples_thinned;
  105. float _orientation_confidence;
  106. bool set_status(compass_cal_status_t status);
  107. // returns true if sample should be added to buffer
  108. bool accept_sample(const Vector3f &sample);
  109. bool accept_sample(const CompassSample &sample);
  110. // returns true if fit is acceptable
  111. bool fit_acceptable();
  112. void reset_state();
  113. void initialize_fit();
  114. bool fitting() const;
  115. // thins out samples between step one and step two
  116. void thin_samples();
  117. float calc_residual(const Vector3f& sample, const param_t& params) const;
  118. float calc_mean_squared_residuals(const param_t& params) const;
  119. float calc_mean_squared_residuals() const;
  120. void calc_initial_offset();
  121. void calc_sphere_jacob(const Vector3f& sample, const param_t& params, float* ret) const;
  122. void run_sphere_fit();
  123. void calc_ellipsoid_jacob(const Vector3f& sample, const param_t& params, float* ret) const;
  124. void run_ellipsoid_fit();
  125. /**
  126. * Update #_completion_mask for the geodesic section of \p v. Corrections
  127. * are applied to \p v with #_params.
  128. *
  129. * @param v[in] A vector representing one calibration sample.
  130. */
  131. void update_completion_mask(const Vector3f& v);
  132. /**
  133. * Reset and update #_completion_mask with the current samples.
  134. */
  135. void update_completion_mask();
  136. Vector3f calculate_earth_field(CompassSample &sample, enum Rotation r);
  137. bool calculate_orientation();
  138. };