INS_generic.cpp 4.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175
  1. //
  2. // Simple test for the AP_InertialSensor driver.
  3. //
  4. #include <AP_HAL/AP_HAL.h>
  5. #include <AP_BoardConfig/AP_BoardConfig.h>
  6. #include <AP_InertialSensor/AP_InertialSensor.h>
  7. const AP_HAL::HAL &hal = AP_HAL::get_HAL();
  8. static AP_InertialSensor ins;
  9. static void display_offsets_and_scaling();
  10. static void run_test();
  11. // board specific config
  12. static AP_BoardConfig BoardConfig;
  13. void setup(void);
  14. void loop(void);
  15. void setup(void)
  16. {
  17. // setup any board specific drivers
  18. BoardConfig.init();
  19. hal.console->printf("AP_InertialSensor startup...\n");
  20. ins.init(100);
  21. // display initial values
  22. display_offsets_and_scaling();
  23. // display number of detected accels/gyros
  24. hal.console->printf("\n");
  25. hal.console->printf("Number of detected accels : %u\n", ins.get_accel_count());
  26. hal.console->printf("Number of detected gyros : %u\n\n", ins.get_gyro_count());
  27. hal.console->printf("Complete. Reading:\n");
  28. }
  29. void loop(void)
  30. {
  31. int16_t user_input;
  32. hal.console->printf("\n");
  33. hal.console->printf("%s\n",
  34. "Menu:\n"
  35. " d) display offsets and scaling\n"
  36. " l) level (capture offsets from level)\n"
  37. " t) test\n"
  38. " r) reboot");
  39. // wait for user input
  40. while (!hal.console->available()) {
  41. hal.scheduler->delay(20);
  42. }
  43. // read in user input
  44. while (hal.console->available()) {
  45. user_input = hal.console->read();
  46. if (user_input == 'd' || user_input == 'D') {
  47. display_offsets_and_scaling();
  48. }
  49. if (user_input == 't' || user_input == 'T') {
  50. run_test();
  51. }
  52. if (user_input == 'r' || user_input == 'R') {
  53. hal.scheduler->reboot(false);
  54. }
  55. }
  56. }
  57. static void display_offsets_and_scaling()
  58. {
  59. const Vector3f &accel_offsets = ins.get_accel_offsets();
  60. const Vector3f &accel_scale = ins.get_accel_scale();
  61. const Vector3f &gyro_offsets = ins.get_gyro_offsets();
  62. // display results
  63. hal.console->printf("\nAccel Offsets X:%10.8f \t Y:%10.8f \t Z:%10.8f\n",
  64. (double)accel_offsets.x,
  65. (double)accel_offsets.y,
  66. (double)accel_offsets.z);
  67. hal.console->printf("Accel Scale X:%10.8f \t Y:%10.8f \t Z:%10.8f\n",
  68. (double)accel_scale.x,
  69. (double)accel_scale.y,
  70. (double)accel_scale.z);
  71. hal.console->printf("Gyro Offsets X:%10.8f \t Y:%10.8f \t Z:%10.8f\n",
  72. (double)gyro_offsets.x,
  73. (double)gyro_offsets.y,
  74. (double)gyro_offsets.z);
  75. }
  76. static void run_test()
  77. {
  78. Vector3f accel;
  79. Vector3f gyro;
  80. uint8_t counter = 0;
  81. static uint8_t accel_count = ins.get_accel_count();
  82. static uint8_t gyro_count = ins.get_gyro_count();
  83. static uint8_t ins_count = MAX(accel_count, gyro_count);
  84. // flush any user input
  85. while (hal.console->available()) {
  86. hal.console->read();
  87. }
  88. // clear out any existing samples from ins
  89. ins.update();
  90. // loop as long as user does not press a key
  91. while (!hal.console->available()) {
  92. // wait until we have a sample
  93. ins.wait_for_sample();
  94. // read samples from ins
  95. ins.update();
  96. // print each accel/gyro result every 50 cycles
  97. if (counter++ % 50 != 0) {
  98. continue;
  99. }
  100. // loop and print each sensor
  101. for (uint8_t ii = 0; ii < ins_count; ii++) {
  102. char state;
  103. if (ii > accel_count - 1) {
  104. // No accel present
  105. state = '-';
  106. } else if (ins.get_accel_health(ii)) {
  107. // Healthy accel
  108. state = 'h';
  109. } else {
  110. // Accel present but not healthy
  111. state = 'u';
  112. }
  113. accel = ins.get_accel(ii);
  114. hal.console->printf("%u - Accel (%c) : X:%6.2f Y:%6.2f Z:%6.2f norm:%5.2f",
  115. ii, state, (double)accel.x, (double)accel.y, (double)accel.z,
  116. (double)accel.length());
  117. gyro = ins.get_gyro(ii);
  118. if (ii > gyro_count - 1) {
  119. // No gyro present
  120. state = '-';
  121. } else if (ins.get_gyro_health(ii)) {
  122. // Healthy gyro
  123. state = 'h';
  124. } else {
  125. // Gyro present but not healthy
  126. state = 'u';
  127. }
  128. hal.console->printf(" Gyro (%c) : X:%6.2f Y:%6.2f Z:%6.2f\n",
  129. state, (double)gyro.x, (double)gyro.y, (double)gyro.z);
  130. auto temp = ins.get_temperature(ii);
  131. hal.console->printf(" t:%6.2f\n", (double)temp);
  132. }
  133. }
  134. // clear user input
  135. while (hal.console->available()) {
  136. hal.console->read();
  137. }
  138. }
  139. AP_HAL_MAIN();