AP_Compass_SITL.cpp 4.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130
  1. #include "AP_Compass_SITL.h"
  2. #include <AP_HAL/AP_HAL.h>
  3. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  4. extern const AP_HAL::HAL& hal;
  5. AP_Compass_SITL::AP_Compass_SITL()
  6. : _sitl(AP::sitl())
  7. {
  8. if (_sitl != nullptr) {
  9. _compass._setup_earth_field();
  10. for (uint8_t i=0; i<SITL_NUM_COMPASSES; i++) {
  11. // default offsets to correct value
  12. if (_compass.get_offsets(i).is_zero()) {
  13. _compass.set_offsets(i, _sitl->mag_ofs);
  14. }
  15. _compass_instance[i] = register_compass();
  16. set_dev_id(_compass_instance[i], AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_SITL, i, 0, DEVTYPE_SITL));
  17. // save so the compass always comes up configured in SITL
  18. save_dev_id(_compass_instance[i]);
  19. }
  20. // make first compass external
  21. set_external(_compass_instance[0], true);
  22. hal.scheduler->register_timer_process(FUNCTOR_BIND(this, &AP_Compass_SITL::_timer, void));
  23. }
  24. }
  25. /*
  26. create correction matrix for diagnonals and off-diagonals
  27. */
  28. void AP_Compass_SITL::_setup_eliptical_correcion(void)
  29. {
  30. Vector3f diag = _sitl->mag_diag.get();
  31. if (diag.is_zero()) {
  32. diag(1,1,1);
  33. }
  34. const Vector3f &diagonals = diag;
  35. const Vector3f &offdiagonals = _sitl->mag_offdiag;
  36. if (diagonals == _last_dia && offdiagonals == _last_odi) {
  37. return;
  38. }
  39. _eliptical_corr = Matrix3f(diagonals.x, offdiagonals.x, offdiagonals.y,
  40. offdiagonals.x, diagonals.y, offdiagonals.z,
  41. offdiagonals.y, offdiagonals.z, diagonals.z);
  42. if (!_eliptical_corr.invert()) {
  43. _eliptical_corr.identity();
  44. }
  45. _last_dia = diag;
  46. _last_odi = offdiagonals;
  47. }
  48. void AP_Compass_SITL::_timer()
  49. {
  50. // TODO: Refactor delay buffer with AP_Baro_SITL.
  51. // Sampled at 100Hz
  52. uint32_t now = AP_HAL::millis();
  53. if ((now - _last_sample_time) < 10) {
  54. return;
  55. }
  56. _last_sample_time = now;
  57. // calculate sensor noise and add to 'truth' field in body frame
  58. // units are milli-Gauss
  59. Vector3f noise = rand_vec3f() * _sitl->mag_noise;
  60. Vector3f new_mag_data = _sitl->state.bodyMagField + noise;
  61. // add delay
  62. uint32_t best_time_delta = 1000; // initialise large time representing buffer entry closest to current time - delay.
  63. uint8_t best_index = 0; // initialise number representing the index of the entry in buffer closest to delay.
  64. // storing data from sensor to buffer
  65. if (now - last_store_time >= 10) { // store data every 10 ms.
  66. last_store_time = now;
  67. if (store_index > buffer_length-1) { // reset buffer index if index greater than size of buffer
  68. store_index = 0;
  69. }
  70. buffer[store_index].data = new_mag_data; // add data to current index
  71. buffer[store_index].time = last_store_time; // add time to current index
  72. store_index = store_index + 1; // increment index
  73. }
  74. // return delayed measurement
  75. uint32_t delayed_time = now - _sitl->mag_delay; // get time corresponding to delay
  76. // find data corresponding to delayed time in buffer
  77. for (uint8_t i=0; i<=buffer_length-1; i++) {
  78. // find difference between delayed time and time stamp in buffer
  79. uint32_t time_delta = abs((int32_t)(delayed_time - buffer[i].time));
  80. // if this difference is smaller than last delta, store this time
  81. if (time_delta < best_time_delta) {
  82. best_index= i;
  83. best_time_delta = time_delta;
  84. }
  85. }
  86. if (best_time_delta < 1000) { // only output stored state if < 1 sec retrieval error
  87. new_mag_data = buffer[best_index].data;
  88. }
  89. _setup_eliptical_correcion();
  90. new_mag_data = _eliptical_corr * new_mag_data;
  91. new_mag_data -= _sitl->mag_ofs.get();
  92. for (uint8_t i=0; i<SITL_NUM_COMPASSES; i++) {
  93. Vector3f f = new_mag_data;
  94. if (i == 0) {
  95. // rotate the first compass, allowing for testing of external compass rotation
  96. f.rotate_inverse((enum Rotation)_sitl->mag_orient.get());
  97. f.rotate(get_board_orientation());
  98. }
  99. accumulate_sample(f, _compass_instance[i], 10);
  100. }
  101. }
  102. void AP_Compass_SITL::read()
  103. {
  104. for (uint8_t i=0; i<SITL_NUM_COMPASSES; i++) {
  105. drain_accumulated_samples(_compass_instance[i], nullptr);
  106. }
  107. }
  108. #endif