AP_GPS_SBP.cpp 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458
  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. // Swift Navigation SBP GPS driver for ArduPilot.
  15. // Code by Niels Joubert
  16. //
  17. // Swift Binary Protocol format: http://docs.swift-nav.com/
  18. //
  19. #include "AP_GPS.h"
  20. #include "AP_GPS_SBP.h"
  21. #include <AP_Logger/AP_Logger.h>
  22. extern const AP_HAL::HAL& hal;
  23. #define SBP_DEBUGGING 1
  24. #define SBP_HW_LOGGING 1
  25. #define SBP_TIMEOUT_HEATBEAT 4000
  26. #define SBP_TIMEOUT_PVT 500
  27. #if SBP_DEBUGGING
  28. # define Debug(fmt, args ...) \
  29. do { \
  30. hal.console->printf("%s:%d: " fmt "\n", \
  31. __FUNCTION__, __LINE__, \
  32. ## args); \
  33. hal.scheduler->delay(1); \
  34. } while(0)
  35. #else
  36. # define Debug(fmt, args ...)
  37. #endif
  38. AP_GPS_SBP::AP_GPS_SBP(AP_GPS &_gps, AP_GPS::GPS_State &_state,
  39. AP_HAL::UARTDriver *_port) :
  40. AP_GPS_Backend(_gps, _state, _port)
  41. {
  42. Debug("SBP Driver Initialized");
  43. parser_state.state = sbp_parser_state_t::WAITING;
  44. //Externally visible state
  45. state.status = AP_GPS::NO_FIX;
  46. state.last_gps_time_ms = last_heatbeat_received_ms = AP_HAL::millis();
  47. }
  48. // Process all bytes available from the stream
  49. //
  50. bool
  51. AP_GPS_SBP::read(void)
  52. {
  53. //Invariant: Calling this function processes *all* data current in the UART buffer.
  54. //
  55. //IMPORTANT NOTICE: This function is NOT CALLED for several seconds
  56. // during arming. That should not cause the driver to die. Process *all* waiting messages
  57. _sbp_process();
  58. return _attempt_state_update();
  59. }
  60. void
  61. AP_GPS_SBP::inject_data(const uint8_t *data, uint16_t len)
  62. {
  63. if (port->txspace() > len) {
  64. last_injected_data_ms = AP_HAL::millis();
  65. port->write(data, len);
  66. } else {
  67. Debug("PIKSI: Not enough TXSPACE");
  68. }
  69. }
  70. //This attempts to reads all SBP messages from the incoming port.
  71. //Returns true if a new message was read, false if we failed to read a message.
  72. void
  73. AP_GPS_SBP::_sbp_process()
  74. {
  75. while (port->available() > 0) {
  76. uint8_t temp = port->read();
  77. uint16_t crc;
  78. //This switch reads one character at a time,
  79. //parsing it into buffers until a full message is dispatched
  80. switch (parser_state.state) {
  81. case sbp_parser_state_t::WAITING:
  82. if (temp == SBP_PREAMBLE) {
  83. parser_state.n_read = 0;
  84. parser_state.state = sbp_parser_state_t::GET_TYPE;
  85. }
  86. break;
  87. case sbp_parser_state_t::GET_TYPE:
  88. *((uint8_t*)&(parser_state.msg_type) + parser_state.n_read) = temp;
  89. parser_state.n_read += 1;
  90. if (parser_state.n_read >= 2) {
  91. parser_state.n_read = 0;
  92. parser_state.state = sbp_parser_state_t::GET_SENDER;
  93. }
  94. break;
  95. case sbp_parser_state_t::GET_SENDER:
  96. *((uint8_t*)&(parser_state.sender_id) + parser_state.n_read) = temp;
  97. parser_state.n_read += 1;
  98. if (parser_state.n_read >= 2) {
  99. parser_state.n_read = 0;
  100. parser_state.state = sbp_parser_state_t::GET_LEN;
  101. }
  102. break;
  103. case sbp_parser_state_t::GET_LEN:
  104. parser_state.msg_len = temp;
  105. parser_state.n_read = 0;
  106. parser_state.state = sbp_parser_state_t::GET_MSG;
  107. break;
  108. case sbp_parser_state_t::GET_MSG:
  109. *((uint8_t*)&(parser_state.msg_buff) + parser_state.n_read) = temp;
  110. parser_state.n_read += 1;
  111. if (parser_state.n_read >= parser_state.msg_len) {
  112. parser_state.n_read = 0;
  113. parser_state.state = sbp_parser_state_t::GET_CRC;
  114. }
  115. break;
  116. case sbp_parser_state_t::GET_CRC:
  117. *((uint8_t*)&(parser_state.crc) + parser_state.n_read) = temp;
  118. parser_state.n_read += 1;
  119. if (parser_state.n_read >= 2) {
  120. parser_state.state = sbp_parser_state_t::WAITING;
  121. crc = crc16_ccitt((uint8_t*)&(parser_state.msg_type), 2, 0);
  122. crc = crc16_ccitt((uint8_t*)&(parser_state.sender_id), 2, crc);
  123. crc = crc16_ccitt(&(parser_state.msg_len), 1, crc);
  124. crc = crc16_ccitt(parser_state.msg_buff, parser_state.msg_len, crc);
  125. if (parser_state.crc == crc) {
  126. _sbp_process_message();
  127. } else {
  128. Debug("CRC Error Occurred!");
  129. crc_error_counter += 1;
  130. }
  131. parser_state.state = sbp_parser_state_t::WAITING;
  132. }
  133. break;
  134. default:
  135. parser_state.state = sbp_parser_state_t::WAITING;
  136. break;
  137. }
  138. }
  139. }
  140. //INVARIANT: A fully received message with correct CRC is currently in parser_state
  141. void
  142. AP_GPS_SBP::_sbp_process_message() {
  143. switch (parser_state.msg_type) {
  144. case SBP_HEARTBEAT_MSGTYPE:
  145. last_heatbeat_received_ms = AP_HAL::millis();
  146. break;
  147. case SBP_GPS_TIME_MSGTYPE:
  148. memcpy(&last_gps_time, parser_state.msg_buff, sizeof(last_gps_time));
  149. check_new_itow(last_gps_time.tow, parser_state.msg_len);
  150. break;
  151. case SBP_VEL_NED_MSGTYPE:
  152. memcpy(&last_vel_ned, parser_state.msg_buff, sizeof(last_vel_ned));
  153. check_new_itow(last_vel_ned.tow, parser_state.msg_len);
  154. break;
  155. case SBP_POS_LLH_MSGTYPE: {
  156. struct sbp_pos_llh_t *pos_llh = (struct sbp_pos_llh_t*)parser_state.msg_buff;
  157. check_new_itow(pos_llh->tow, parser_state.msg_len);
  158. // Check if this is a single point or RTK solution
  159. // flags = 0 -> single point
  160. if (pos_llh->flags == 0) {
  161. last_pos_llh_spp = *pos_llh;
  162. } else if (pos_llh->flags == 1 || pos_llh->flags == 2) {
  163. last_pos_llh_rtk = *pos_llh;
  164. }
  165. break;
  166. }
  167. case SBP_DOPS_MSGTYPE:
  168. memcpy(&last_dops, parser_state.msg_buff, sizeof(last_dops));
  169. check_new_itow(last_dops.tow, parser_state.msg_len);
  170. break;
  171. case SBP_TRACKING_STATE_MSGTYPE:
  172. //INTENTIONALLY BLANK
  173. //Currently unhandled, but logged after switch statement.
  174. break;
  175. case SBP_IAR_STATE_MSGTYPE: {
  176. sbp_iar_state_t *iar = (struct sbp_iar_state_t*)parser_state.msg_buff;
  177. last_iar_num_hypotheses = iar->num_hypotheses;
  178. break;
  179. }
  180. default:
  181. // log anyway if it's an unsupported message.
  182. // The log mask will be used to adjust or suppress logging
  183. break;
  184. }
  185. logging_log_raw_sbp(parser_state.msg_type, parser_state.sender_id, parser_state.msg_len, parser_state.msg_buff);
  186. }
  187. bool
  188. AP_GPS_SBP::_attempt_state_update()
  189. {
  190. // If we currently have heartbeats
  191. // - NO FIX
  192. //
  193. // If we have a full update available, save it
  194. //
  195. uint32_t now = AP_HAL::millis();
  196. bool ret = false;
  197. if (now - last_heatbeat_received_ms > SBP_TIMEOUT_HEATBEAT) {
  198. state.status = AP_GPS::NO_FIX;
  199. Debug("No Heartbeats from Piksi! Driver Ready to Die!");
  200. } else if (last_pos_llh_rtk.tow == last_vel_ned.tow
  201. && abs((int32_t) (last_gps_time.tow - last_vel_ned.tow)) < 10000
  202. && abs((int32_t) (last_dops.tow - last_vel_ned.tow)) < 60000
  203. && last_vel_ned.tow > last_full_update_tow) {
  204. // Use the RTK position
  205. sbp_pos_llh_t *pos_llh = &last_pos_llh_rtk;
  206. // Update time state
  207. state.time_week = last_gps_time.wn;
  208. state.time_week_ms = last_vel_ned.tow;
  209. state.hdop = last_dops.hdop;
  210. // Update velocity state
  211. state.velocity[0] = (float)(last_vel_ned.n * 1.0e-3);
  212. state.velocity[1] = (float)(last_vel_ned.e * 1.0e-3);
  213. state.velocity[2] = (float)(last_vel_ned.d * 1.0e-3);
  214. state.have_vertical_velocity = true;
  215. float ground_vector_sq = state.velocity[0]*state.velocity[0] + state.velocity[1]*state.velocity[1];
  216. state.ground_speed = safe_sqrt(ground_vector_sq);
  217. state.ground_course = wrap_360(degrees(atan2f(state.velocity[1], state.velocity[0])));
  218. // Update position state
  219. state.location.lat = (int32_t) (pos_llh->lat * (double)1e7);
  220. state.location.lng = (int32_t) (pos_llh->lon * (double)1e7);
  221. state.location.alt = (int32_t) (pos_llh->height * 100);
  222. state.num_sats = pos_llh->n_sats;
  223. if (pos_llh->flags == 0) {
  224. state.status = AP_GPS::GPS_OK_FIX_3D;
  225. } else if (pos_llh->flags == 2) {
  226. state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
  227. } else if (pos_llh->flags == 1) {
  228. state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
  229. }
  230. last_full_update_tow = last_vel_ned.tow;
  231. last_full_update_cpu_ms = now;
  232. state.rtk_iar_num_hypotheses = last_iar_num_hypotheses;
  233. logging_log_full_update();
  234. ret = true;
  235. } else if (now - last_full_update_cpu_ms > SBP_TIMEOUT_PVT) {
  236. //INVARIANT: If we currently have a fix, ONLY return true after a full update.
  237. state.status = AP_GPS::NO_FIX;
  238. ret = true;
  239. } else {
  240. //No timeouts yet, no data yet, nothing has happened.
  241. }
  242. return ret;
  243. }
  244. bool
  245. AP_GPS_SBP::_detect(struct SBP_detect_state &state, uint8_t data)
  246. {
  247. // This switch reads one character at a time, if we find something that
  248. // looks like our preamble we'll try to read the full message length,
  249. // calculating the CRC. If the CRC matches, we have an SBP GPS!
  250. switch (state.state) {
  251. case SBP_detect_state::WAITING:
  252. if (data == SBP_PREAMBLE) {
  253. state.n_read = 0;
  254. state.crc_so_far = 0;
  255. state.state = SBP_detect_state::GET_TYPE;
  256. }
  257. break;
  258. case SBP_detect_state::GET_TYPE:
  259. *((uint8_t*)&(state.msg_type) + state.n_read) = data;
  260. state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
  261. state.n_read += 1;
  262. if (state.n_read >= 2) {
  263. state.n_read = 0;
  264. state.state = SBP_detect_state::GET_SENDER;
  265. }
  266. break;
  267. case SBP_detect_state::GET_SENDER:
  268. state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
  269. state.n_read += 1;
  270. if (state.n_read >= 2) {
  271. state.n_read = 0;
  272. state.state = SBP_detect_state::GET_LEN;
  273. }
  274. break;
  275. case SBP_detect_state::GET_LEN:
  276. state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
  277. state.msg_len = data;
  278. state.n_read = 0;
  279. state.state = SBP_detect_state::GET_MSG;
  280. break;
  281. case SBP_detect_state::GET_MSG:
  282. if (state.msg_type == SBP_HEARTBEAT_MSGTYPE && state.n_read < 4) {
  283. *((uint8_t*)&(state.heartbeat_buff) + state.n_read) = data;
  284. }
  285. state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
  286. state.n_read += 1;
  287. if (state.n_read >= state.msg_len) {
  288. state.n_read = 0;
  289. state.state = SBP_detect_state::GET_CRC;
  290. }
  291. break;
  292. case SBP_detect_state::GET_CRC:
  293. *((uint8_t*)&(state.crc) + state.n_read) = data;
  294. state.n_read += 1;
  295. if (state.n_read >= 2) {
  296. state.state = SBP_detect_state::WAITING;
  297. if (state.crc == state.crc_so_far
  298. && state.msg_type == SBP_HEARTBEAT_MSGTYPE) {
  299. struct sbp_heartbeat_t* heartbeat = ((struct sbp_heartbeat_t*)state.heartbeat_buff);
  300. return heartbeat->protocol_major == 0;
  301. }
  302. return false;
  303. }
  304. break;
  305. default:
  306. state.state = SBP_detect_state::WAITING;
  307. break;
  308. }
  309. return false;
  310. }
  311. #if SBP_HW_LOGGING
  312. void
  313. AP_GPS_SBP::logging_log_full_update()
  314. {
  315. if (!should_log()) {
  316. return;
  317. }
  318. struct log_SbpHealth pkt = {
  319. LOG_PACKET_HEADER_INIT(LOG_MSG_SBPHEALTH),
  320. time_us : AP_HAL::micros64(),
  321. crc_error_counter : crc_error_counter,
  322. last_injected_data_ms : last_injected_data_ms,
  323. last_iar_num_hypotheses : last_iar_num_hypotheses,
  324. };
  325. AP::logger().WriteBlock(&pkt, sizeof(pkt));
  326. };
  327. void
  328. AP_GPS_SBP::logging_log_raw_sbp(uint16_t msg_type,
  329. uint16_t sender_id,
  330. uint8_t msg_len,
  331. uint8_t *msg_buff) {
  332. if (!should_log()) {
  333. return;
  334. }
  335. //MASK OUT MESSAGES WE DON'T WANT TO LOG
  336. if (( ((uint16_t) gps._sbp_logmask) & msg_type) == 0) {
  337. return;
  338. }
  339. uint64_t time_us = AP_HAL::micros64();
  340. uint8_t pages = 1;
  341. if (msg_len > 48) {
  342. pages += (msg_len - 48) / 104 + 1;
  343. }
  344. struct log_SbpRAWH pkt = {
  345. LOG_PACKET_HEADER_INIT(LOG_MSG_SBPRAWH),
  346. time_us : time_us,
  347. msg_type : msg_type,
  348. sender_id : sender_id,
  349. index : 1,
  350. pages : pages,
  351. msg_len : msg_len,
  352. };
  353. memcpy(pkt.data, msg_buff, MIN(msg_len, 48));
  354. AP::logger().WriteBlock(&pkt, sizeof(pkt));
  355. for (uint8_t i = 0; i < pages - 1; i++) {
  356. struct log_SbpRAWM pkt2 = {
  357. LOG_PACKET_HEADER_INIT(LOG_MSG_SBPRAWM),
  358. time_us : time_us,
  359. msg_type : msg_type,
  360. sender_id : sender_id,
  361. index : uint8_t(i + 2),
  362. pages : pages,
  363. msg_len : msg_len,
  364. };
  365. memcpy(pkt2.data, &msg_buff[48 + i * 104], MIN(msg_len - (48 + i * 104), 104));
  366. AP::logger().WriteBlock(&pkt2, sizeof(pkt2));
  367. }
  368. };
  369. #endif // SBP_HW_LOGGING