GPS_Backend.cpp 8.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291
  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. #include "AP_GPS.h"
  14. #include "GPS_Backend.h"
  15. #include <AP_Logger/AP_Logger.h>
  16. #define GPS_BACKEND_DEBUGGING 0
  17. #if GPS_BACKEND_DEBUGGING
  18. # define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
  19. #else
  20. # define Debug(fmt, args ...)
  21. #endif
  22. #include <GCS_MAVLink/GCS.h>
  23. extern const AP_HAL::HAL& hal;
  24. AP_GPS_Backend::AP_GPS_Backend(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
  25. port(_port),
  26. gps(_gps),
  27. state(_state)
  28. {
  29. state.have_speed_accuracy = false;
  30. state.have_horizontal_accuracy = false;
  31. state.have_vertical_accuracy = false;
  32. }
  33. int32_t AP_GPS_Backend::swap_int32(int32_t v) const
  34. {
  35. const uint8_t *b = (const uint8_t *)&v;
  36. union {
  37. int32_t v;
  38. uint8_t b[4];
  39. } u;
  40. u.b[0] = b[3];
  41. u.b[1] = b[2];
  42. u.b[2] = b[1];
  43. u.b[3] = b[0];
  44. return u.v;
  45. }
  46. int16_t AP_GPS_Backend::swap_int16(int16_t v) const
  47. {
  48. const uint8_t *b = (const uint8_t *)&v;
  49. union {
  50. int16_t v;
  51. uint8_t b[2];
  52. } u;
  53. u.b[0] = b[1];
  54. u.b[1] = b[0];
  55. return u.v;
  56. }
  57. /**
  58. fill in time_week_ms and time_week from BCD date and time components
  59. assumes MTK19 millisecond form of bcd_time
  60. */
  61. void AP_GPS_Backend::make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
  62. {
  63. uint8_t year, mon, day, hour, min, sec;
  64. uint16_t msec;
  65. year = bcd_date % 100;
  66. mon = (bcd_date / 100) % 100;
  67. day = bcd_date / 10000;
  68. uint32_t v = bcd_milliseconds;
  69. msec = v % 1000; v /= 1000;
  70. sec = v % 100; v /= 100;
  71. min = v % 100; v /= 100;
  72. hour = v % 100;
  73. int8_t rmon = mon - 2;
  74. if (0 >= rmon) {
  75. rmon += 12;
  76. year -= 1;
  77. }
  78. // get time in seconds since unix epoch
  79. uint32_t ret = (year/4) - (GPS_LEAPSECONDS_MILLIS / 1000UL) + 367*rmon/12 + day;
  80. ret += year*365 + 10501;
  81. ret = ret*24 + hour;
  82. ret = ret*60 + min;
  83. ret = ret*60 + sec;
  84. // convert to time since GPS epoch
  85. ret -= 272764785UL;
  86. // get GPS week and time
  87. state.time_week = ret / AP_SEC_PER_WEEK;
  88. state.time_week_ms = (ret % AP_SEC_PER_WEEK) * AP_MSEC_PER_SEC;
  89. state.time_week_ms += msec;
  90. }
  91. /*
  92. fill in 3D velocity for a GPS that doesn't give vertical velocity numbers
  93. */
  94. void AP_GPS_Backend::fill_3d_velocity(void)
  95. {
  96. float gps_heading = radians(state.ground_course);
  97. state.velocity.x = state.ground_speed * cosf(gps_heading);
  98. state.velocity.y = state.ground_speed * sinf(gps_heading);
  99. state.velocity.z = 0;
  100. state.have_vertical_velocity = false;
  101. }
  102. void
  103. AP_GPS_Backend::inject_data(const uint8_t *data, uint16_t len)
  104. {
  105. // not all backends have valid ports
  106. if (port != nullptr) {
  107. if (port->txspace() > len) {
  108. port->write(data, len);
  109. } else {
  110. Debug("GPS %d: Not enough TXSPACE", state.instance + 1);
  111. }
  112. }
  113. }
  114. void AP_GPS_Backend::_detection_message(char *buffer, const uint8_t buflen) const
  115. {
  116. const uint8_t instance = state.instance;
  117. const struct AP_GPS::detect_state dstate = gps.detect_state[instance];
  118. if (dstate.auto_detected_baud) {
  119. hal.util->snprintf(buffer, buflen,
  120. "GPS %d: detected as %s at %d baud",
  121. instance + 1,
  122. name(),
  123. gps._baudrates[dstate.current_baud]);
  124. } else {
  125. hal.util->snprintf(buffer, buflen,
  126. "GPS %d: specified as %s",
  127. instance + 1,
  128. name());
  129. }
  130. }
  131. void AP_GPS_Backend::broadcast_gps_type() const
  132. {
  133. #ifndef HAL_NO_GCS
  134. char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
  135. _detection_message(buffer, sizeof(buffer));
  136. gcs().send_text(MAV_SEVERITY_INFO, "%s", buffer);
  137. #endif
  138. }
  139. void AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages() const
  140. {
  141. #ifndef HAL_NO_LOGGING
  142. char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
  143. _detection_message(buffer, sizeof(buffer));
  144. AP::logger().Write_Message(buffer);
  145. #endif
  146. }
  147. bool AP_GPS_Backend::should_log() const
  148. {
  149. return gps.should_log();
  150. }
  151. void AP_GPS_Backend::send_mavlink_gps_rtk(mavlink_channel_t chan)
  152. {
  153. #ifndef HAL_NO_GCS
  154. const uint8_t instance = state.instance;
  155. // send status
  156. switch (instance) {
  157. case 0:
  158. mavlink_msg_gps_rtk_send(chan,
  159. 0, // Not implemented yet
  160. 0, // Not implemented yet
  161. state.rtk_week_number,
  162. state.rtk_time_week_ms,
  163. 0, // Not implemented yet
  164. 0, // Not implemented yet
  165. state.rtk_num_sats,
  166. state.rtk_baseline_coords_type,
  167. state.rtk_baseline_x_mm,
  168. state.rtk_baseline_y_mm,
  169. state.rtk_baseline_z_mm,
  170. state.rtk_accuracy,
  171. state.rtk_iar_num_hypotheses);
  172. break;
  173. case 1:
  174. mavlink_msg_gps2_rtk_send(chan,
  175. 0, // Not implemented yet
  176. 0, // Not implemented yet
  177. state.rtk_week_number,
  178. state.rtk_time_week_ms,
  179. 0, // Not implemented yet
  180. 0, // Not implemented yet
  181. state.rtk_num_sats,
  182. state.rtk_baseline_coords_type,
  183. state.rtk_baseline_x_mm,
  184. state.rtk_baseline_y_mm,
  185. state.rtk_baseline_z_mm,
  186. state.rtk_accuracy,
  187. state.rtk_iar_num_hypotheses);
  188. break;
  189. }
  190. #endif
  191. }
  192. /*
  193. set a timestamp based on arrival time on uart at current byte,
  194. assuming the message started nbytes ago
  195. */
  196. void AP_GPS_Backend::set_uart_timestamp(uint16_t nbytes)
  197. {
  198. if (port) {
  199. state.uart_timestamp_ms = port->receive_time_constraint_us(nbytes) / 1000U;
  200. }
  201. }
  202. void AP_GPS_Backend::check_new_itow(uint32_t itow, uint32_t msg_length)
  203. {
  204. if (itow != _last_itow) {
  205. _last_itow = itow;
  206. /*
  207. we need to calculate a pseudo-itow, which copes with the
  208. iTow from the GPS changing in unexpected ways. We assume
  209. that timestamps from the GPS are always in multiples of
  210. 50ms. That means we can't handle a GPS with an update rate
  211. of more than 20Hz. We could do more, but we'd need the GPS
  212. poll time to be higher
  213. */
  214. const uint32_t gps_min_period_ms = 50;
  215. // get the time the packet arrived on the UART
  216. uint64_t uart_us = port->receive_time_constraint_us(msg_length);
  217. uint32_t now = AP_HAL::millis();
  218. uint32_t dt_ms = now - _last_ms;
  219. _last_ms = now;
  220. // round to nearest 50ms period
  221. dt_ms = ((dt_ms + (gps_min_period_ms/2)) / gps_min_period_ms) * gps_min_period_ms;
  222. // work out an actual message rate. If we get 5 messages in a
  223. // row with a new rate we switch rate
  224. if (_last_rate_ms == dt_ms) {
  225. if (_rate_counter < 5) {
  226. _rate_counter++;
  227. } else if (_rate_ms != dt_ms) {
  228. _rate_ms = dt_ms;
  229. }
  230. } else {
  231. _rate_counter = 0;
  232. _last_rate_ms = dt_ms;
  233. }
  234. if (_rate_ms == 0) {
  235. // only allow 5Hz to 20Hz in user config
  236. _rate_ms = constrain_int16(gps.get_rate_ms(state.instance), 50, 200);
  237. }
  238. // round to calculated message rate
  239. dt_ms = ((dt_ms + (_rate_ms/2)) / _rate_ms) * _rate_ms;
  240. // calculate pseudo-itow
  241. _pseudo_itow += dt_ms * 1000U;
  242. // use msg arrival time, and correct for jitter
  243. uint64_t local_us = jitter_correction.correct_offboard_timestamp_usec(_pseudo_itow, uart_us);
  244. state.uart_timestamp_ms = local_us / 1000U;
  245. }
  246. }