Airspeed.cpp 2.6 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394
  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. * Airspeed.cpp - airspeed example sketch
  15. *
  16. */
  17. #include <AP_Airspeed/AP_Airspeed.h>
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <AP_BoardConfig/AP_BoardConfig.h>
  20. #include <GCS_MAVLink/GCS_Dummy.h>
  21. void setup();
  22. void loop();
  23. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  24. float temperature;
  25. // create airspeed object
  26. AP_Airspeed airspeed;
  27. static AP_BoardConfig board_config;
  28. namespace {
  29. // try to set the object value but provide diagnostic if it failed
  30. void set_object_value(const void *object_pointer,
  31. const struct AP_Param::GroupInfo *group_info,
  32. const char *name, float value)
  33. {
  34. if (!AP_Param::set_object_value(object_pointer, group_info, name, value)) {
  35. hal.console->printf("WARNING: AP_Param::set object value \"%s::%s\" Failed.\n",
  36. group_info->name, name);
  37. }
  38. }
  39. }
  40. // to be called only once on boot for initializing objects
  41. void setup()
  42. {
  43. hal.console->printf("ArduPilot Airspeed library test\n");
  44. // set airspeed pin to 65, enable and use to true
  45. set_object_value(&airspeed, airspeed.var_info, "PIN", 65);
  46. set_object_value(&airspeed, airspeed.var_info, "ENABLE", 1);
  47. set_object_value(&airspeed, airspeed.var_info, "USE", 1);
  48. board_config.init();
  49. // initialize airspeed
  50. airspeed.init();
  51. airspeed.calibrate(false);
  52. }
  53. // loop
  54. void loop(void)
  55. {
  56. static uint32_t timer;
  57. // run read() and get_temperature() in 10Hz
  58. if ((AP_HAL::millis() - timer) > 100) {
  59. // current system time in milliseconds
  60. timer = AP_HAL::millis();
  61. airspeed.update(false);
  62. airspeed.get_temperature(temperature);
  63. // print temperature and airspeed to console
  64. hal.console->printf("airspeed %5.2f temperature %6.2f healthy = %u\n",
  65. (double)airspeed.get_airspeed(), (double)temperature, airspeed.healthy());
  66. }
  67. hal.scheduler->delay(1);
  68. }
  69. const struct AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
  70. AP_GROUPEND
  71. };
  72. GCS_Dummy _gcs;
  73. AP_HAL_MAIN();