AP_Compass_HIL.cpp 2.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. * AP_Compass_HIL.cpp - HIL backend for AP_Compass
  15. *
  16. */
  17. #include <AP_HAL/AP_HAL.h>
  18. #include "AP_Compass_HIL.h"
  19. extern const AP_HAL::HAL& hal;
  20. // constructor
  21. AP_Compass_HIL::AP_Compass_HIL()
  22. {
  23. memset(_compass_instance, 0, sizeof(_compass_instance));
  24. _compass._setup_earth_field();
  25. }
  26. // detect the sensor
  27. AP_Compass_Backend *AP_Compass_HIL::detect()
  28. {
  29. AP_Compass_HIL *sensor = new AP_Compass_HIL();
  30. if (sensor == nullptr) {
  31. return nullptr;
  32. }
  33. if (!sensor->init()) {
  34. delete sensor;
  35. return nullptr;
  36. }
  37. return sensor;
  38. }
  39. bool
  40. AP_Compass_HIL::init(void)
  41. {
  42. // register two compass instances
  43. for (uint8_t i=0; i<HIL_NUM_COMPASSES; i++) {
  44. _compass_instance[i] = register_compass();
  45. }
  46. return true;
  47. }
  48. void AP_Compass_HIL::read()
  49. {
  50. for (uint8_t i=0; i < ARRAY_SIZE(_compass_instance); i++) {
  51. if (_compass._hil.healthy[i]) {
  52. uint8_t compass_instance = _compass_instance[i];
  53. Vector3f field = _compass._hil.field[compass_instance];
  54. rotate_field(field, compass_instance);
  55. publish_raw_field(field, compass_instance);
  56. correct_field(field, compass_instance);
  57. uint32_t saved_last_update = _compass.last_update_usec(compass_instance);
  58. publish_filtered_field(field, compass_instance);
  59. set_last_update_usec(saved_last_update, compass_instance);
  60. }
  61. }
  62. }