Compass_learn.h 1.1 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758
  1. #pragma once
  2. #include <AP_AHRS/AP_AHRS.h>
  3. /*
  4. compass learning using magnetic field tables from AP_Declination
  5. */
  6. class CompassLearn {
  7. public:
  8. CompassLearn(Compass &compass);
  9. // called on each compass read
  10. void update(void);
  11. private:
  12. Compass &compass;
  13. bool have_earth_field;
  14. // 5 degree resolution
  15. static const uint16_t num_sectors = 72;
  16. Vector3f predicted_offsets[num_sectors];
  17. float errors[num_sectors];
  18. uint32_t num_samples;
  19. // earth field
  20. Vector3f mag_ef;
  21. // semaphore for access to shared data with IO thread
  22. HAL_Semaphore sem;
  23. struct sample {
  24. // milliGauss body field and offsets
  25. Vector3f field;
  26. Vector3f offsets;
  27. // euler radians attitude
  28. Vector3f attitude;
  29. };
  30. Matrix3f mat;
  31. struct sample new_sample;
  32. bool sample_available;
  33. Vector3f last_field;
  34. static const uint32_t min_field_change = 60;
  35. Vector3f best_offsets;
  36. float best_error;
  37. float best_yaw_deg;
  38. float worst_error;
  39. bool converged;
  40. uint8_t primary_mag;
  41. void io_timer(void);
  42. void process_sample(const struct sample &s);
  43. };