BARO_generic.cpp 2.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104
  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. generic Baro driver test
  15. */
  16. #include <AP_Baro/AP_Baro.h>
  17. #include <AP_BoardConfig/AP_BoardConfig.h>
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <GCS_MAVLink/GCS_Dummy.h>
  20. const AP_HAL::HAL &hal = AP_HAL::get_HAL();
  21. // create barometer object
  22. static AP_Baro barometer;
  23. static uint32_t timer;
  24. static uint8_t counter;
  25. static AP_BoardConfig board_config;
  26. void setup();
  27. void loop();
  28. // to be called only once on boot for initializing objects
  29. void setup()
  30. {
  31. hal.console->printf("Barometer library test\n");
  32. board_config.init();
  33. hal.scheduler->delay(1000);
  34. // initialize the barometer
  35. barometer.init();
  36. barometer.calibrate();
  37. // set up timer to count time in microseconds
  38. timer = AP_HAL::micros();
  39. }
  40. // loop
  41. void loop()
  42. {
  43. // terminate program if console fails to initialize
  44. if (!hal.console->is_initialized()) {
  45. return;
  46. }
  47. // run accumulate() at 50Hz and update() at 10Hz
  48. if ((AP_HAL::micros() - timer) > 20 * 1000UL) {
  49. timer = AP_HAL::micros();
  50. barometer.accumulate();
  51. if (counter++ < 5) {
  52. return;
  53. }
  54. counter = 0;
  55. barometer.update();
  56. //calculate time taken for barometer readings to update
  57. uint32_t read_time = AP_HAL::micros() - timer;
  58. if (!barometer.healthy()) {
  59. hal.console->printf("not healthy\n");
  60. return;
  61. }
  62. //output barometer readings to console
  63. hal.console->printf(" Pressure: %.2f Pa\n"
  64. " Temperature: %.2f degC\n"
  65. " Relative Altitude: %.2f m\n"
  66. " climb=%.2f m/s\n"
  67. " Read + update time: %u usec\n"
  68. "\n",
  69. (double)barometer.get_pressure(),
  70. (double)barometer.get_temperature(),
  71. (double)barometer.get_altitude(),
  72. (double)barometer.get_climb_rate(),
  73. (unsigned)read_time);
  74. } else {
  75. // if stipulated time has not passed between two distinct readings, delay the program for a millisecond
  76. hal.scheduler->delay(1);
  77. }
  78. }
  79. const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
  80. AP_GROUPEND
  81. };
  82. GCS_Dummy _gcs;
  83. AP_HAL_MAIN();