AP_NMEA_Output.cpp 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181
  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. Author: Francisco Ferreira (some code is copied from sitl_gps.cpp)
  13. */
  14. #include "AP_NMEA_Output.h"
  15. #if !HAL_MINIMIZE_FEATURES && AP_AHRS_NAVEKF_AVAILABLE
  16. #include <AP_Math/definitions.h>
  17. #include <AP_RTC/AP_RTC.h>
  18. #include <AP_SerialManager/AP_SerialManager.h>
  19. #include <stdio.h>
  20. #include <time.h>
  21. AP_NMEA_Output* AP_NMEA_Output::_singleton;
  22. AP_NMEA_Output::AP_NMEA_Output()
  23. {
  24. AP_SerialManager& sm = AP::serialmanager();
  25. for (uint8_t i = 0; i < ARRAY_SIZE(_uart); i++) {
  26. _uart[i] = sm.find_serial(AP_SerialManager::SerialProtocol_NMEAOutput, i);
  27. if (_uart[i] == nullptr) {
  28. break;
  29. }
  30. _num_outputs++;
  31. }
  32. }
  33. AP_NMEA_Output* AP_NMEA_Output::probe()
  34. {
  35. if (!_singleton && AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_NMEAOutput, 0) != nullptr) {
  36. _singleton = new AP_NMEA_Output();
  37. }
  38. return _singleton;
  39. }
  40. uint8_t AP_NMEA_Output::_nmea_checksum(const char *str)
  41. {
  42. uint8_t checksum = 0;
  43. const uint8_t* bytes = (const uint8_t*) str;
  44. for (uint16_t i = 1; str[i]; i++) {
  45. checksum ^= bytes[i];
  46. }
  47. return checksum;
  48. }
  49. void AP_NMEA_Output::update()
  50. {
  51. uint16_t now = AP_HAL::millis16();
  52. uint16_t time_diff = now - _last_sent;
  53. // only send at 10Hz
  54. if (time_diff < 100) {
  55. return;
  56. }
  57. // get time and date
  58. uint64_t time_usec;
  59. bool time_valid = AP::rtc().get_utc_usec(time_usec);
  60. if (!time_valid) {
  61. return;
  62. }
  63. // not completely accurate, our time includes leap seconds and time_t should be without
  64. time_t time_sec = time_usec / 1000000;
  65. struct tm* tm = gmtime(&time_sec);
  66. // format time string
  67. char tstring[11];
  68. snprintf(tstring, sizeof(tstring), "%02u%02u%06.3f", tm->tm_hour, tm->tm_min, tm->tm_sec + (time_usec % 1000000) * 1.0e-6);
  69. // format date string
  70. char dstring[7];
  71. snprintf(dstring, sizeof(dstring), "%02u%02u%02u", tm->tm_mday, tm->tm_mon+1, tm->tm_year % 100);
  72. AP_AHRS_NavEKF& ahrs = AP::ahrs_navekf();
  73. // get location (note: get_position from AHRS always returns true after having GPS position once)
  74. Location loc;
  75. bool pos_valid = ahrs.get_location(loc);
  76. // format latitude
  77. char lat_string[13];
  78. float deg = fabsf(loc.lat * 1.0e-7f);
  79. snprintf(lat_string,
  80. sizeof(lat_string),
  81. "%02u%08.5f,%c",
  82. (unsigned) deg,
  83. double((deg - int(deg)) * 60),
  84. loc.lat < 0 ? 'S' : 'N');
  85. // format longitude
  86. char lng_string[14];
  87. deg = fabsf(loc.lng * 1.0e-7f);
  88. snprintf(lng_string,
  89. sizeof(lng_string),
  90. "%03u%08.5f,%c",
  91. (unsigned) deg,
  92. double((deg - int(deg)) * 60),
  93. loc.lng < 0 ? 'W' : 'E');
  94. // format GGA message
  95. char* gga = nullptr;
  96. int16_t gga_res = asprintf(&gga,
  97. "$GPGGA,%s,%s,%s,%01d,%02d,%04.1f,%07.2f,M,0.0,M,,",
  98. tstring,
  99. lat_string,
  100. lng_string,
  101. pos_valid ? 1 : 0,
  102. pos_valid ? 6 : 3,
  103. 2.0,
  104. loc.alt * 0.01f);
  105. char gga_end[6];
  106. snprintf(gga_end, sizeof(gga_end), "*%02X\r\n", (unsigned) _nmea_checksum(gga));
  107. // get speed
  108. Vector2f speed = ahrs.groundspeed_vector();
  109. float speed_knots = norm(speed.x, speed.y) * M_PER_SEC_TO_KNOTS;
  110. float heading = wrap_360(degrees(atan2f(speed.x, speed.y)));
  111. // format RMC message
  112. char* rmc = nullptr;
  113. int16_t rmc_res = asprintf(&rmc,
  114. "$GPRMC,%s,%c,%s,%s,%.2f,%.2f,%s,,",
  115. tstring,
  116. pos_valid ? 'A' : 'V',
  117. lat_string,
  118. lng_string,
  119. speed_knots,
  120. heading,
  121. dstring);
  122. char rmc_end[6];
  123. snprintf(rmc_end, sizeof(rmc_end), "*%02X\r\n", (unsigned) _nmea_checksum(rmc));
  124. // send to all NMEA output ports
  125. for (uint8_t i = 0; i < _num_outputs; i++) {
  126. if (gga_res != -1) {
  127. _uart[i]->write(gga);
  128. _uart[i]->write(gga_end);
  129. }
  130. if (rmc_res != -1) {
  131. _uart[i]->write(rmc);
  132. _uart[i]->write(rmc_end);
  133. }
  134. }
  135. if (gga_res != -1) {
  136. free(gga);
  137. }
  138. if (rmc_res != -1) {
  139. free(rmc);
  140. }
  141. _last_sent = now;
  142. }
  143. #endif // !HAL_MINIMIZE_FEATURES && AP_AHRS_NAVEKF_AVAILABLE