GPS_AUTO_test.cpp 3.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126
  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. Test for AP_GPS_AUTO
  15. */
  16. #include <AP_HAL/AP_HAL.h>
  17. #include <AP_GPS/AP_GPS.h>
  18. #include <GCS_MAVLink/GCS_Dummy.h>
  19. #include <AP_Notify/AP_Notify.h>
  20. #include <AP_Notify/AP_BoardLED.h>
  21. #include <AP_SerialManager/AP_SerialManager.h>
  22. #include <AP_BoardConfig/AP_BoardConfig.h>
  23. void setup();
  24. void loop();
  25. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  26. static AP_BoardConfig board_config;
  27. // create board led object
  28. AP_BoardLED board_led;
  29. // create fake gcs object
  30. GCS_Dummy _gcs;
  31. const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
  32. AP_GROUPEND
  33. };
  34. // This example uses GPS system. Create it.
  35. static AP_GPS gps;
  36. // Serial manager is needed for UART communications
  37. static AP_SerialManager serial_manager;
  38. //to be called only once on boot for initializing objects
  39. void setup()
  40. {
  41. hal.console->printf("GPS AUTO library test\n");
  42. board_config.init();
  43. // Initialise the leds
  44. board_led.init();
  45. // Initialize the UART for GPS system
  46. serial_manager.init();
  47. gps.init(serial_manager);
  48. }
  49. /*
  50. print a int32_t lat/long in decimal degrees
  51. */
  52. void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon);
  53. void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon)
  54. {
  55. int32_t dec_portion, frac_portion;
  56. int32_t abs_lat_or_lon = labs(lat_or_lon);
  57. // extract decimal portion (special handling of negative numbers to ensure we round towards zero)
  58. dec_portion = abs_lat_or_lon / 10000000UL;
  59. // extract fractional portion
  60. frac_portion = abs_lat_or_lon - dec_portion*10000000UL;
  61. // print output including the minus sign
  62. if( lat_or_lon < 0 ) {
  63. s->printf("-");
  64. }
  65. s->printf("%ld.%07ld",(long)dec_portion,(long)frac_portion);
  66. }
  67. // loop
  68. void loop()
  69. {
  70. static uint32_t last_msg_ms;
  71. // Update GPS state based on possible bytes received from the module.
  72. gps.update();
  73. // If new GPS data is received, output it's contents to the console
  74. // Here we rely on the time of the message in GPS class and the time of last message
  75. // saved in static variable last_msg_ms. When new message is received, the time
  76. // in GPS class will be updated.
  77. if (last_msg_ms != gps.last_message_time_ms()) {
  78. // Reset the time of message
  79. last_msg_ms = gps.last_message_time_ms();
  80. // Acquire location
  81. const Location &loc = gps.location();
  82. // Print the contents of message
  83. hal.console->printf("Lat: ");
  84. print_latlon(hal.console, loc.lat);
  85. hal.console->printf(" Lon: ");
  86. print_latlon(hal.console, loc.lng);
  87. hal.console->printf(" Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %u/%lu STATUS: %u\n",
  88. (double)(loc.alt * 0.01f),
  89. (double)gps.ground_speed(),
  90. (int)gps.ground_course_cd() / 100,
  91. gps.num_sats(),
  92. gps.time_week(),
  93. (long unsigned int)gps.time_week_ms(),
  94. gps.status());
  95. }
  96. // Delay for 10 mS will give us 100 Hz invocation rate
  97. hal.scheduler->delay(10);
  98. }
  99. // Register above functions in HAL board level
  100. AP_HAL_MAIN();