AP_GPS_MTK.cpp 6.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218
  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, DIYDrones.com
  16. //
  17. // GPS configuration : Custom protocol per "DIYDrones Custom Binary Sentence Specification V1.1"
  18. //
  19. #include "AP_GPS.h"
  20. #include "AP_GPS_MTK.h"
  21. // initialisation blobs to send to the GPS to try to get it into the
  22. // right mode
  23. const char AP_GPS_MTK::_initialisation_blob[] = MTK_OUTPUT_5HZ SBAS_ON WAAS_ON MTK_NAVTHRES_OFF;
  24. AP_GPS_MTK::AP_GPS_MTK(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
  25. AP_GPS_Backend(_gps, _state, _port)
  26. {
  27. gps.send_blob_start(state.instance, _initialisation_blob, sizeof(_initialisation_blob));
  28. }
  29. /*
  30. send an initialisation blob to configure the GPS
  31. */
  32. void AP_GPS_MTK::send_init_blob(uint8_t instance, AP_GPS &gps)
  33. {
  34. gps.send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob));
  35. }
  36. // Process bytes available from the stream
  37. //
  38. // The stream is assumed to contain only our custom message. If it
  39. // contains other messages, and those messages contain the preamble bytes,
  40. // it is possible for this code to become de-synchronised. Without
  41. // buffering the entire message and re-processing it from the top,
  42. // this is unavoidable.
  43. //
  44. // The lack of a standard header length field makes it impossible to skip
  45. // unrecognised messages.
  46. //
  47. bool
  48. AP_GPS_MTK::read(void)
  49. {
  50. uint8_t data;
  51. int16_t numc;
  52. bool parsed = false;
  53. numc = port->available();
  54. for (int16_t i = 0; i < numc; i++) { // Process bytes received
  55. // read the next byte
  56. data = port->read();
  57. restart:
  58. switch(_step) {
  59. // Message preamble, class, ID detection
  60. //
  61. // If we fail to match any of the expected bytes, we
  62. // reset the state machine and re-consider the failed
  63. // byte as the first byte of the preamble. This
  64. // improves our chances of recovering from a mismatch
  65. // and makes it less likely that we will be fooled by
  66. // the preamble appearing as data in some other message.
  67. //
  68. case 0:
  69. if(PREAMBLE1 == data)
  70. _step++;
  71. break;
  72. case 1:
  73. if (PREAMBLE2 == data) {
  74. _step++;
  75. break;
  76. }
  77. _step = 0;
  78. goto restart;
  79. case 2:
  80. if (MESSAGE_CLASS == data) {
  81. _step++;
  82. _ck_b = _ck_a = data; // reset the checksum accumulators
  83. } else {
  84. _step = 0; // reset and wait for a message of the right class
  85. goto restart;
  86. }
  87. break;
  88. case 3:
  89. if (MESSAGE_ID == data) {
  90. _step++;
  91. _ck_b += (_ck_a += data);
  92. _payload_counter = 0;
  93. } else {
  94. _step = 0;
  95. goto restart;
  96. }
  97. break;
  98. // Receive message data
  99. //
  100. case 4:
  101. _buffer[_payload_counter++] = data;
  102. _ck_b += (_ck_a += data);
  103. if (_payload_counter == sizeof(_buffer))
  104. _step++;
  105. break;
  106. // Checksum and message processing
  107. //
  108. case 5:
  109. _step++;
  110. if (_ck_a != data) {
  111. _step = 0;
  112. }
  113. break;
  114. case 6:
  115. _step = 0;
  116. if (_ck_b != data) {
  117. break;
  118. }
  119. // set fix type
  120. if (_buffer.msg.fix_type == FIX_3D) {
  121. state.status = AP_GPS::GPS_OK_FIX_3D;
  122. }else if (_buffer.msg.fix_type == FIX_2D) {
  123. state.status = AP_GPS::GPS_OK_FIX_2D;
  124. }else{
  125. state.status = AP_GPS::NO_FIX;
  126. }
  127. state.location.lat = swap_int32(_buffer.msg.latitude) * 10;
  128. state.location.lng = swap_int32(_buffer.msg.longitude) * 10;
  129. state.location.alt = swap_int32(_buffer.msg.altitude);
  130. state.ground_speed = swap_int32(_buffer.msg.ground_speed) * 0.01f;
  131. state.ground_course = wrap_360(swap_int32(_buffer.msg.ground_course) * 1.0e-6f);
  132. state.num_sats = _buffer.msg.satellites;
  133. if (state.status >= AP_GPS::GPS_OK_FIX_2D) {
  134. make_gps_time(0, swap_int32(_buffer.msg.utc_time)*10);
  135. }
  136. // we don't change _last_gps_time as we don't know the
  137. // full date
  138. fill_3d_velocity();
  139. parsed = true;
  140. }
  141. }
  142. return parsed;
  143. }
  144. /*
  145. detect a MTK GPS
  146. */
  147. bool
  148. AP_GPS_MTK::_detect(struct MTK_detect_state &state, uint8_t data)
  149. {
  150. switch (state.step) {
  151. case 1:
  152. if (PREAMBLE2 == data) {
  153. state.step++;
  154. break;
  155. }
  156. state.step = 0;
  157. FALLTHROUGH;
  158. case 0:
  159. state.ck_b = state.ck_a = state.payload_counter = 0;
  160. if(PREAMBLE1 == data)
  161. state.step++;
  162. break;
  163. case 2:
  164. if (MESSAGE_CLASS == data) {
  165. state.step++;
  166. state.ck_b = state.ck_a = data;
  167. } else {
  168. state.step = 0;
  169. }
  170. break;
  171. case 3:
  172. if (MESSAGE_ID == data) {
  173. state.step++;
  174. state.ck_b += (state.ck_a += data);
  175. state.payload_counter = 0;
  176. } else {
  177. state.step = 0;
  178. }
  179. break;
  180. case 4:
  181. state.ck_b += (state.ck_a += data);
  182. if (++state.payload_counter == sizeof(struct diyd_mtk_msg))
  183. state.step++;
  184. break;
  185. case 5:
  186. state.step++;
  187. if (state.ck_a != data) {
  188. state.step = 0;
  189. }
  190. break;
  191. case 6:
  192. state.step = 0;
  193. if (state.ck_b == data) {
  194. return true;
  195. }
  196. }
  197. return false;
  198. }