AP_Compass_test.cpp 4.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133
  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. * Example of APM_Compass library (HMC5843 sensor).
  15. * Code by Jordi MuÒoz and Jose Julio. DIYDrones.com
  16. */
  17. #include <AP_HAL/AP_HAL.h>
  18. #include <AP_BoardConfig/AP_BoardConfig.h>
  19. #include <AP_AHRS/AP_AHRS.h>
  20. #include <AP_Baro/AP_Baro.h>
  21. #include <AP_Compass/AP_Compass.h>
  22. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  23. static AP_BoardConfig board_config;
  24. class DummyVehicle {
  25. public:
  26. AP_AHRS_DCM ahrs; // Need since https://github.com/ArduPilot/ardupilot/pull/10890
  27. AP_Baro baro; // Compass tries to set magnetic model based on location.
  28. };
  29. static DummyVehicle vehicle;
  30. // create compass object
  31. static Compass compass;
  32. static AP_SerialManager serial_manager;
  33. uint32_t timer;
  34. // to be called only once on boot for initializing objects
  35. static void setup()
  36. {
  37. hal.console->printf("Compass library test\n");
  38. board_config.init();
  39. vehicle.ahrs.init();
  40. compass.init();
  41. hal.console->printf("init done - %u compasses detected\n", compass.get_count());
  42. // set offsets to account for surrounding interference
  43. compass.set_and_save_offsets(0, Vector3f(0, 0, 0));
  44. // set local difference between magnetic north and true north
  45. compass.set_declination(ToRad(0.0f));
  46. hal.scheduler->delay(1000);
  47. timer = AP_HAL::micros();
  48. }
  49. // loop
  50. static void loop()
  51. {
  52. static const uint8_t compass_count = compass.get_count();
  53. static float min[COMPASS_MAX_INSTANCES][3];
  54. static float max[COMPASS_MAX_INSTANCES][3];
  55. static float offset[COMPASS_MAX_INSTANCES][3];
  56. // run read() at 10Hz
  57. if ((AP_HAL::micros() - timer) > 100000L) {
  58. timer = AP_HAL::micros();
  59. compass.read();
  60. const uint32_t read_time = AP_HAL::micros() - timer;
  61. for (uint8_t i = 0; i < compass_count; i++) {
  62. float heading;
  63. hal.console->printf("Compass #%u: ", i);
  64. if (!compass.healthy()) {
  65. hal.console->printf("not healthy\n");
  66. continue;
  67. }
  68. Matrix3f dcm_matrix;
  69. // use roll = 0, pitch = 0 for this example
  70. dcm_matrix.from_euler(0, 0, 0);
  71. heading = compass.calculate_heading(dcm_matrix, i);
  72. const Vector3f &mag = compass.get_field(i);
  73. // capture min
  74. min[i][0] = MIN(mag.x, min[i][0]);
  75. min[i][1] = MIN(mag.y, min[i][1]);
  76. min[i][2] = MIN(mag.z, min[i][2]);
  77. // capture max
  78. max[i][0] = MAX(mag.x, max[i][0]);
  79. max[i][1] = MAX(mag.y, max[i][1]);
  80. max[i][2] = MAX(mag.z, max[i][2]);
  81. // calculate offsets
  82. offset[i][0] = -(max[i][0] + min[i][0]) / 2;
  83. offset[i][1] = -(max[i][1] + min[i][1]) / 2;
  84. offset[i][2] = -(max[i][2] + min[i][2]) / 2;
  85. // display all to user
  86. hal.console->printf("Heading: %.2f (%3d, %3d, %3d)",
  87. (double)ToDeg(heading),
  88. (int)mag.x,
  89. (int)mag.y,
  90. (int)mag.z);
  91. // display offsets
  92. hal.console->printf(" offsets(%.2f, %.2f, %.2f)",
  93. (double)offset[i][0],
  94. (double)offset[i][1],
  95. (double)offset[i][2]);
  96. hal.console->printf(" t=%u", (unsigned)read_time);
  97. hal.console->printf("\n");
  98. }
  99. } else {
  100. // if stipulated time has not passed between two distinct readings, delay the program for a millisecond
  101. hal.scheduler->delay(1);
  102. }
  103. }
  104. AP_HAL_MAIN();