AP_GPS_MTK19.cpp 7.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234
  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. // DIYDrones Custom Mediatek GPS driver for ArduPilot and ArduPilotMega.
  15. // Code by Michael Smith, Jordi Munoz and Jose Julio, Craig Elder, DIYDrones.com
  16. //
  17. // GPS configuration : Custom protocol per "DIYDrones Custom Binary Sentence Specification V1.6, v1.7, v1.8, v1.9"
  18. //
  19. // Note that this driver supports both the 1.6 and 1.9 protocol varients
  20. //
  21. #include "AP_GPS_MTK.h"
  22. #include "AP_GPS_MTK19.h"
  23. extern const AP_HAL::HAL& hal;
  24. AP_GPS_MTK19::AP_GPS_MTK19(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
  25. AP_GPS_Backend(_gps, _state, _port),
  26. _step(0),
  27. _payload_counter(0),
  28. _mtk_revision(0),
  29. _fix_counter(0)
  30. {
  31. AP_GPS_MTK::send_init_blob(_state.instance, _gps);
  32. }
  33. // Process bytes available from the stream
  34. //
  35. // The stream is assumed to contain only our custom message. If it
  36. // contains other messages, and those messages contain the preamble bytes,
  37. // it is possible for this code to become de-synchronised. Without
  38. // buffering the entire message and re-processing it from the top,
  39. // this is unavoidable.
  40. //
  41. // The lack of a standard header length field makes it impossible to skip
  42. // unrecognised messages.
  43. //
  44. bool
  45. AP_GPS_MTK19::read(void)
  46. {
  47. uint8_t data;
  48. int16_t numc;
  49. bool parsed = false;
  50. numc = port->available();
  51. for (int16_t i = 0; i < numc; i++) { // Process bytes received
  52. // read the next byte
  53. data = port->read();
  54. restart:
  55. switch(_step) {
  56. // Message preamble, class, ID detection
  57. //
  58. // If we fail to match any of the expected bytes, we
  59. // reset the state machine and re-consider the failed
  60. // byte as the first byte of the preamble. This
  61. // improves our chances of recovering from a mismatch
  62. // and makes it less likely that we will be fooled by
  63. // the preamble appearing as data in some other message.
  64. //
  65. case 0:
  66. if (data == PREAMBLE1_V16) {
  67. _mtk_revision = MTK_GPS_REVISION_V16;
  68. _step++;
  69. } else if (data == PREAMBLE1_V19) {
  70. _mtk_revision = MTK_GPS_REVISION_V19;
  71. _step++;
  72. }
  73. break;
  74. case 1:
  75. if (data == PREAMBLE2) {
  76. _step++;
  77. } else {
  78. _step = 0;
  79. goto restart;
  80. }
  81. break;
  82. case 2:
  83. if (sizeof(_buffer) == data) {
  84. _step++;
  85. _ck_b = _ck_a = data; // reset the checksum accumulators
  86. _payload_counter = 0;
  87. } else {
  88. _step = 0; // reset and wait for a message of the right class
  89. goto restart;
  90. }
  91. break;
  92. // Receive message data
  93. //
  94. case 3:
  95. _buffer[_payload_counter++] = data;
  96. _ck_b += (_ck_a += data);
  97. if (_payload_counter == sizeof(_buffer)) {
  98. _step++;
  99. }
  100. break;
  101. // Checksum and message processing
  102. //
  103. case 4:
  104. _step++;
  105. if (_ck_a != data) {
  106. _step = 0;
  107. goto restart;
  108. }
  109. break;
  110. case 5:
  111. _step = 0;
  112. if (_ck_b != data) {
  113. goto restart;
  114. }
  115. // parse fix
  116. if (_buffer.msg.fix_type == FIX_3D || _buffer.msg.fix_type == FIX_3D_SBAS) {
  117. state.status = AP_GPS::GPS_OK_FIX_3D;
  118. }else if (_buffer.msg.fix_type == FIX_2D || _buffer.msg.fix_type == FIX_2D_SBAS) {
  119. state.status = AP_GPS::GPS_OK_FIX_2D;
  120. }else{
  121. state.status = AP_GPS::NO_FIX;
  122. }
  123. if (_mtk_revision == MTK_GPS_REVISION_V16) {
  124. state.location.lat = _buffer.msg.latitude * 10; // V16, V17,V18 doc says *10e7 but device says otherwise
  125. state.location.lng = _buffer.msg.longitude * 10; // V16, V17,V18 doc says *10e7 but device says otherwise
  126. } else {
  127. state.location.lat = _buffer.msg.latitude;
  128. state.location.lng = _buffer.msg.longitude;
  129. }
  130. state.location.alt = _buffer.msg.altitude;
  131. state.ground_speed = _buffer.msg.ground_speed*0.01f;
  132. state.ground_course = wrap_360(_buffer.msg.ground_course*0.01f);
  133. state.num_sats = _buffer.msg.satellites;
  134. state.hdop = _buffer.msg.hdop;
  135. if (state.status >= AP_GPS::GPS_OK_FIX_2D) {
  136. if (_fix_counter == 0) {
  137. uint32_t bcd_time_ms;
  138. bcd_time_ms = _buffer.msg.utc_time;
  139. #if 0
  140. hal.console->printf("utc_date=%lu utc_time=%lu rev=%u\n",
  141. (unsigned long)_buffer.msg.utc_date,
  142. (unsigned long)_buffer.msg.utc_time,
  143. (unsigned)_mtk_revision);
  144. #endif
  145. make_gps_time(_buffer.msg.utc_date, bcd_time_ms);
  146. state.last_gps_time_ms = AP_HAL::millis();
  147. }
  148. // the _fix_counter is to reduce the cost of the GPS
  149. // BCD time conversion by only doing it every 10s
  150. // between those times we use the HAL system clock as
  151. // an offset from the last fix
  152. _fix_counter++;
  153. if (_fix_counter == 50) {
  154. _fix_counter = 0;
  155. }
  156. }
  157. fill_3d_velocity();
  158. parsed = true;
  159. }
  160. }
  161. return parsed;
  162. }
  163. /*
  164. detect a MTK16 or MTK19 GPS
  165. */
  166. bool
  167. AP_GPS_MTK19::_detect(struct MTK19_detect_state &state, uint8_t data)
  168. {
  169. restart:
  170. switch (state.step) {
  171. case 0:
  172. state.ck_b = state.ck_a = state.payload_counter = 0;
  173. if (data == PREAMBLE1_V16 || data == PREAMBLE1_V19) {
  174. state.step++;
  175. }
  176. break;
  177. case 1:
  178. if (PREAMBLE2 == data) {
  179. state.step++;
  180. } else {
  181. state.step = 0;
  182. goto restart;
  183. }
  184. break;
  185. case 2:
  186. if (data == sizeof(struct diyd_mtk_msg)) {
  187. state.step++;
  188. state.ck_b = state.ck_a = data;
  189. } else {
  190. state.step = 0;
  191. goto restart;
  192. }
  193. break;
  194. case 3:
  195. state.ck_b += (state.ck_a += data);
  196. if (++state.payload_counter == sizeof(struct diyd_mtk_msg))
  197. state.step++;
  198. break;
  199. case 4:
  200. state.step++;
  201. if (state.ck_a != data) {
  202. state.step = 0;
  203. goto restart;
  204. }
  205. break;
  206. case 5:
  207. state.step = 0;
  208. if (state.ck_b != data) {
  209. goto restart;
  210. }
  211. return true;
  212. }
  213. return false;
  214. }