AP_GPS_ERB.cpp 9.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287
  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. // Emlid Reach Binary (ERB) GPS driver for ArduPilot.
  15. // ERB protocol: http://files.emlid.com/ERB.pdf
  16. #include "AP_GPS.h"
  17. #include "AP_GPS_ERB.h"
  18. #define ERB_DEBUGGING 0
  19. #define STAT_FIX_VALID 0x01
  20. extern const AP_HAL::HAL& hal;
  21. #if ERB_DEBUGGING
  22. # define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
  23. #else
  24. # define Debug(fmt, args ...)
  25. #endif
  26. // Process bytes available from the stream
  27. //
  28. // The stream is assumed to contain only messages we recognise. If it
  29. // contains other messages, and those messages contain the preamble
  30. // bytes, it is possible for this code to fail to synchronise to the
  31. // stream immediately. Without buffering the entire message and
  32. // re-processing it from the top, this is unavoidable. The parser
  33. // attempts to avoid this when possible.
  34. //
  35. bool
  36. AP_GPS_ERB::read(void)
  37. {
  38. uint8_t data;
  39. int16_t numc;
  40. bool parsed = false;
  41. numc = port->available();
  42. for (int16_t i = 0; i < numc; i++) { // Process bytes received
  43. // read the next byte
  44. data = port->read();
  45. reset:
  46. switch(_step) {
  47. // Message preamble detection
  48. //
  49. case 1:
  50. if (PREAMBLE2 == data) {
  51. _step++;
  52. break;
  53. }
  54. _step = 0;
  55. Debug("reset %u", __LINE__);
  56. FALLTHROUGH;
  57. case 0:
  58. if(PREAMBLE1 == data)
  59. _step++;
  60. break;
  61. // Message header processing
  62. //
  63. case 2:
  64. _step++;
  65. _msg_id = data;
  66. _ck_b = _ck_a = data; // reset the checksum accumulators
  67. break;
  68. case 3:
  69. _step++;
  70. _ck_b += (_ck_a += data); // checksum byte
  71. _payload_length = data; // payload length low byte
  72. break;
  73. case 4:
  74. _step++;
  75. _ck_b += (_ck_a += data); // checksum byte
  76. _payload_length += (uint16_t)(data<<8);
  77. _payload_counter = 0; // prepare to receive payload
  78. break;
  79. // Receive message data
  80. //
  81. case 5:
  82. _ck_b += (_ck_a += data); // checksum byte
  83. if (_payload_counter < sizeof(_buffer)) {
  84. _buffer[_payload_counter] = data;
  85. }
  86. if (++_payload_counter == _payload_length)
  87. _step++;
  88. break;
  89. // Checksum and message processing
  90. //
  91. case 6:
  92. _step++;
  93. if (_ck_a != data) {
  94. Debug("bad cka %x should be %x", data, _ck_a);
  95. _step = 0;
  96. goto reset;
  97. }
  98. break;
  99. case 7:
  100. _step = 0;
  101. if (_ck_b != data) {
  102. Debug("bad ckb %x should be %x", data, _ck_b);
  103. break; // bad checksum
  104. }
  105. if (_parse_gps()) {
  106. parsed = true;
  107. }
  108. break;
  109. }
  110. }
  111. return parsed;
  112. }
  113. bool
  114. AP_GPS_ERB::_parse_gps(void)
  115. {
  116. switch (_msg_id) {
  117. case MSG_VER:
  118. Debug("Version of ERB protocol %u.%u.%u",
  119. _buffer.ver.ver_high,
  120. _buffer.ver.ver_medium,
  121. _buffer.ver.ver_low);
  122. break;
  123. case MSG_POS:
  124. Debug("Message POS");
  125. _last_pos_time = _buffer.pos.time;
  126. state.location.lng = (int32_t)(_buffer.pos.longitude * (double)1e7);
  127. state.location.lat = (int32_t)(_buffer.pos.latitude * (double)1e7);
  128. state.location.alt = (int32_t)(_buffer.pos.altitude_msl * 100);
  129. state.status = next_fix;
  130. _new_position = true;
  131. state.horizontal_accuracy = _buffer.pos.horizontal_accuracy * 1.0e-3f;
  132. state.vertical_accuracy = _buffer.pos.vertical_accuracy * 1.0e-3f;
  133. state.have_horizontal_accuracy = true;
  134. state.have_vertical_accuracy = true;
  135. break;
  136. case MSG_STAT:
  137. Debug("Message STAT fix_status=%u fix_type=%u",
  138. _buffer.stat.fix_status,
  139. _buffer.stat.fix_type);
  140. if (_buffer.stat.fix_status & STAT_FIX_VALID) {
  141. if (_buffer.stat.fix_type == AP_GPS_ERB::FIX_FIX) {
  142. next_fix = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
  143. } else if (_buffer.stat.fix_type == AP_GPS_ERB::FIX_FLOAT) {
  144. next_fix = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
  145. } else if (_buffer.stat.fix_type == AP_GPS_ERB::FIX_SINGLE) {
  146. next_fix = AP_GPS::GPS_OK_FIX_3D;
  147. } else {
  148. next_fix = AP_GPS::NO_FIX;
  149. state.status = AP_GPS::NO_FIX;
  150. }
  151. } else {
  152. next_fix = AP_GPS::NO_FIX;
  153. state.status = AP_GPS::NO_FIX;
  154. }
  155. state.num_sats = _buffer.stat.satellites;
  156. if (next_fix >= AP_GPS::GPS_OK_FIX_3D) {
  157. // use the uart receive time to make packet timestamps more accurate
  158. set_uart_timestamp(_payload_length + sizeof(erb_header) + 2);
  159. state.last_gps_time_ms = AP_HAL::millis();
  160. state.time_week_ms = _buffer.stat.time;
  161. state.time_week = _buffer.stat.week;
  162. }
  163. break;
  164. case MSG_DOPS:
  165. Debug("Message DOPS");
  166. state.hdop = _buffer.dops.hDOP;
  167. state.vdop = _buffer.dops.vDOP;
  168. break;
  169. case MSG_VEL:
  170. Debug("Message VEL");
  171. _last_vel_time = _buffer.vel.time;
  172. state.ground_speed = _buffer.vel.speed_2d * 0.01f; // m/s
  173. // Heading 2D deg * 100000 rescaled to deg * 100
  174. state.ground_course = wrap_360(_buffer.vel.heading_2d * 1.0e-5f);
  175. state.have_vertical_velocity = true;
  176. state.velocity.x = _buffer.vel.vel_north * 0.01f;
  177. state.velocity.y = _buffer.vel.vel_east * 0.01f;
  178. state.velocity.z = _buffer.vel.vel_down * 0.01f;
  179. state.have_speed_accuracy = true;
  180. state.speed_accuracy = _buffer.vel.speed_accuracy * 0.01f;
  181. _new_speed = true;
  182. break;
  183. case MSG_RTK:
  184. Debug("Message RTK");
  185. state.rtk_baseline_coords_type = RTK_BASELINE_COORDINATE_SYSTEM_NED;
  186. state.rtk_num_sats = _buffer.rtk.base_num_sats;
  187. if (_buffer.rtk.age_cs == 0xFFFF) {
  188. state.rtk_age_ms = 0xFFFFFFFF;
  189. } else {
  190. state.rtk_age_ms = _buffer.rtk.age_cs * 10;
  191. }
  192. state.rtk_baseline_x_mm = _buffer.rtk.baseline_N_mm;
  193. state.rtk_baseline_y_mm = _buffer.rtk.baseline_E_mm;
  194. state.rtk_baseline_z_mm = _buffer.rtk.baseline_D_mm;
  195. state.rtk_accuracy = _buffer.rtk.ar_ratio;
  196. state.rtk_week_number = _buffer.rtk.base_week_number;
  197. state.rtk_time_week_ms = _buffer.rtk.base_time_week_ms;
  198. break;
  199. default:
  200. Debug("Unexpected message 0x%02x", (unsigned)_msg_id);
  201. return false;
  202. }
  203. // we only return true when we get new position and speed data
  204. // this ensures we don't use stale data
  205. if (_new_position && _new_speed && _last_vel_time == _last_pos_time) {
  206. _new_speed = _new_position = false;
  207. _fix_count++;
  208. return true;
  209. }
  210. return false;
  211. }
  212. /*
  213. detect a ERB GPS. Adds one byte, and returns true if the stream
  214. matches a ERB
  215. */
  216. bool
  217. AP_GPS_ERB::_detect(struct ERB_detect_state &state, uint8_t data)
  218. {
  219. reset:
  220. switch (state.step) {
  221. case 1:
  222. if (PREAMBLE2 == data) {
  223. state.step++;
  224. break;
  225. }
  226. state.step = 0;
  227. FALLTHROUGH;
  228. case 0:
  229. if (PREAMBLE1 == data)
  230. state.step++;
  231. break;
  232. case 2:
  233. state.step++;
  234. state.ck_b = state.ck_a = data;
  235. break;
  236. case 3:
  237. state.step++;
  238. state.ck_b += (state.ck_a += data);
  239. state.payload_length = data;
  240. break;
  241. case 4:
  242. state.step++;
  243. state.ck_b += (state.ck_a += data);
  244. state.payload_counter = 0;
  245. break;
  246. case 5:
  247. state.ck_b += (state.ck_a += data);
  248. if (++state.payload_counter == state.payload_length)
  249. state.step++;
  250. break;
  251. case 6:
  252. state.step++;
  253. if (state.ck_a != data) {
  254. state.step = 0;
  255. goto reset;
  256. }
  257. break;
  258. case 7:
  259. state.step = 0;
  260. if (state.ck_b == data) {
  261. return true;
  262. } else {
  263. goto reset;
  264. }
  265. }
  266. return false;
  267. }