AHRS_Test.cpp 2.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109
  1. //
  2. // Simple test for the AP_AHRS interface
  3. //
  4. #include <AP_AHRS/AP_AHRS.h>
  5. #include <AP_HAL/AP_HAL.h>
  6. #include <AP_BoardConfig/AP_BoardConfig.h>
  7. #include <GCS_MAVLink/GCS_Dummy.h>
  8. #include <AP_RangeFinder/AP_RangeFinder.h>
  9. #include <AP_Logger/AP_Logger.h>
  10. #include <AP_GPS/AP_GPS.h>
  11. #include <AP_Baro/AP_Baro.h>
  12. void setup();
  13. void loop();
  14. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  15. static AP_BoardConfig board_config;
  16. static AP_InertialSensor ins;
  17. static Compass compass;
  18. static AP_GPS gps;
  19. static AP_Baro barometer;
  20. static AP_SerialManager serial_manager;
  21. AP_Int32 logger_bitmask;
  22. static AP_Logger logger{logger_bitmask};
  23. class DummyVehicle {
  24. public:
  25. RangeFinder sonar;
  26. NavEKF2 EKF2{&ahrs, sonar};
  27. NavEKF3 EKF3{&ahrs, sonar};
  28. AP_AHRS_NavEKF ahrs{EKF2, EKF3,
  29. AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
  30. };
  31. static DummyVehicle vehicle;
  32. // choose which AHRS system to use
  33. // AP_AHRS_DCM ahrs = AP_AHRS_DCM::create(barometer, gps);
  34. AP_AHRS_NavEKF &ahrs = vehicle.ahrs;
  35. void setup(void)
  36. {
  37. board_config.init();
  38. ins.init(100);
  39. ahrs.init();
  40. serial_manager.init();
  41. compass.init();
  42. if(compass.read()) {
  43. hal.console->printf("Enabling compass\n");
  44. ahrs.set_compass(&compass);
  45. } else {
  46. hal.console->printf("No compass detected\n");
  47. }
  48. gps.init(serial_manager);
  49. }
  50. void loop(void)
  51. {
  52. static uint16_t counter;
  53. static uint32_t last_t, last_print, last_compass;
  54. uint32_t now = AP_HAL::micros();
  55. float heading = 0;
  56. if (last_t == 0) {
  57. last_t = now;
  58. return;
  59. }
  60. last_t = now;
  61. if (now - last_compass > 100 * 1000UL &&
  62. compass.read()) {
  63. heading = compass.calculate_heading(ahrs.get_rotation_body_to_ned());
  64. // read compass at 10Hz
  65. last_compass = now;
  66. }
  67. ahrs.update();
  68. counter++;
  69. if (now - last_print >= 100000 /* 100ms : 10hz */) {
  70. Vector3f drift = ahrs.get_gyro_drift();
  71. hal.console->printf(
  72. "r:%4.1f p:%4.1f y:%4.1f "
  73. "drift=(%5.1f %5.1f %5.1f) hdg=%.1f rate=%.1f\n",
  74. (double)ToDeg(ahrs.roll),
  75. (double)ToDeg(ahrs.pitch),
  76. (double)ToDeg(ahrs.yaw),
  77. (double)ToDeg(drift.x),
  78. (double)ToDeg(drift.y),
  79. (double)ToDeg(drift.z),
  80. (double)(compass.use_for_yaw() ? ToDeg(heading) : 0.0f),
  81. (double)((1.0e6f * counter) / (now-last_print)));
  82. last_print = now;
  83. counter = 0;
  84. }
  85. }
  86. const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
  87. AP_GROUPEND
  88. };
  89. GCS_Dummy _gcs;
  90. AP_HAL_MAIN();