APM:Libraries
AP_GPS_MTK19.cpp
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 //
17 // DIYDrones Custom Mediatek GPS driver for ArduPilot and ArduPilotMega.
18 // Code by Michael Smith, Jordi Munoz and Jose Julio, Craig Elder, DIYDrones.com
19 //
20 // GPS configuration : Custom protocol per "DIYDrones Custom Binary Sentence Specification V1.6, v1.7, v1.8, v1.9"
21 //
22 // Note that this driver supports both the 1.6 and 1.9 protocol varients
23 //
24 
25 #include "AP_GPS_MTK.h"
26 #include "AP_GPS_MTK19.h"
27 
28 extern const AP_HAL::HAL& hal;
29 
31  AP_GPS_Backend(_gps, _state, _port),
32  _step(0),
33  _payload_counter(0),
34  _mtk_revision(0),
35  _fix_counter(0)
36 {
38 }
39 
40 // Process bytes available from the stream
41 //
42 // The stream is assumed to contain only our custom message. If it
43 // contains other messages, and those messages contain the preamble bytes,
44 // it is possible for this code to become de-synchronised. Without
45 // buffering the entire message and re-processing it from the top,
46 // this is unavoidable.
47 //
48 // The lack of a standard header length field makes it impossible to skip
49 // unrecognised messages.
50 //
51 bool
53 {
54  uint8_t data;
55  int16_t numc;
56  bool parsed = false;
57 
58  numc = port->available();
59  for (int16_t i = 0; i < numc; i++) { // Process bytes received
60 
61  // read the next byte
62  data = port->read();
63 
64 restart:
65  switch(_step) {
66 
67  // Message preamble, class, ID detection
68  //
69  // If we fail to match any of the expected bytes, we
70  // reset the state machine and re-consider the failed
71  // byte as the first byte of the preamble. This
72  // improves our chances of recovering from a mismatch
73  // and makes it less likely that we will be fooled by
74  // the preamble appearing as data in some other message.
75  //
76  case 0:
77  if (data == PREAMBLE1_V16) {
79  _step++;
80  } else if (data == PREAMBLE1_V19) {
82  _step++;
83  }
84  break;
85  case 1:
86  if (data == PREAMBLE2) {
87  _step++;
88  } else {
89  _step = 0;
90  goto restart;
91  }
92  break;
93  case 2:
94  if (sizeof(_buffer) == data) {
95  _step++;
96  _ck_b = _ck_a = data; // reset the checksum accumulators
97  _payload_counter = 0;
98  } else {
99  _step = 0; // reset and wait for a message of the right class
100  goto restart;
101  }
102  break;
103 
104  // Receive message data
105  //
106  case 3:
107  _buffer[_payload_counter++] = data;
108  _ck_b += (_ck_a += data);
109  if (_payload_counter == sizeof(_buffer)) {
110  _step++;
111  }
112  break;
113 
114  // Checksum and message processing
115  //
116  case 4:
117  _step++;
118  if (_ck_a != data) {
119  _step = 0;
120  goto restart;
121  }
122  break;
123  case 5:
124  _step = 0;
125  if (_ck_b != data) {
126  goto restart;
127  }
128 
129  // parse fix
130  if (_buffer.msg.fix_type == FIX_3D || _buffer.msg.fix_type == FIX_3D_SBAS) {
132  }else if (_buffer.msg.fix_type == FIX_2D || _buffer.msg.fix_type == FIX_2D_SBAS) {
134  }else{
136  }
137 
139  state.location.lat = _buffer.msg.latitude * 10; // V16, V17,V18 doc says *10e7 but device says otherwise
140  state.location.lng = _buffer.msg.longitude * 10; // V16, V17,V18 doc says *10e7 but device says otherwise
141  } else {
142  state.location.lat = _buffer.msg.latitude;
143  state.location.lng = _buffer.msg.longitude;
144  }
145  state.location.alt = _buffer.msg.altitude;
146  state.ground_speed = _buffer.msg.ground_speed*0.01f;
147  state.ground_course = wrap_360(_buffer.msg.ground_course*0.01f);
148  state.num_sats = _buffer.msg.satellites;
149  state.hdop = _buffer.msg.hdop;
150 
152  if (_fix_counter == 0) {
153  uint32_t bcd_time_ms;
154  bcd_time_ms = _buffer.msg.utc_time;
155 #if 0
156  hal.console->printf("utc_date=%lu utc_time=%lu rev=%u\n",
157  (unsigned long)_buffer.msg.utc_date,
158  (unsigned long)_buffer.msg.utc_time,
159  (unsigned)_mtk_revision);
160 #endif
161  make_gps_time(_buffer.msg.utc_date, bcd_time_ms);
163  }
164  // the _fix_counter is to reduce the cost of the GPS
165  // BCD time conversion by only doing it every 10s
166  // between those times we use the HAL system clock as
167  // an offset from the last fix
168  _fix_counter++;
169  if (_fix_counter == 50) {
170  _fix_counter = 0;
171  }
172  }
173 
175 
176  parsed = true;
177  }
178  }
179  return parsed;
180 }
181 
182 
183 /*
184  detect a MTK16 or MTK19 GPS
185  */
186 bool
188 {
189 restart:
190  switch (state.step) {
191  case 0:
192  state.ck_b = state.ck_a = state.payload_counter = 0;
193  if (data == PREAMBLE1_V16 || data == PREAMBLE1_V19) {
194  state.step++;
195  }
196  break;
197  case 1:
198  if (PREAMBLE2 == data) {
199  state.step++;
200  } else {
201  state.step = 0;
202  goto restart;
203  }
204  break;
205  case 2:
206  if (data == sizeof(struct diyd_mtk_msg)) {
207  state.step++;
208  state.ck_b = state.ck_a = data;
209  } else {
210  state.step = 0;
211  goto restart;
212  }
213  break;
214  case 3:
215  state.ck_b += (state.ck_a += data);
216  if (++state.payload_counter == sizeof(struct diyd_mtk_msg))
217  state.step++;
218  break;
219  case 4:
220  state.step++;
221  if (state.ck_a != data) {
222  state.step = 0;
223  goto restart;
224  }
225  break;
226  case 5:
227  state.step = 0;
228  if (state.ck_b != data) {
229  goto restart;
230  }
231  return true;
232  }
233  return false;
234 }
Definition: AP_GPS.h:48
#define MTK_GPS_REVISION_V16
Definition: AP_GPS_MTK19.h:28
union AP_GPS_MTK19::@29 _buffer
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
Definition: AP_GPS.h:149
uint8_t instance
Definition: AP_GPS.h:129
AP_HAL::UARTDriver * console
Definition: HAL.h:110
GPS_Status status
driver fix status
Definition: AP_GPS.h:132
uint8_t _mtk_revision
Definition: AP_GPS_MTK19.h:75
uint8_t _ck_b
Definition: AP_GPS_MTK19.h:70
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
AP_GPS_MTK19(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
static bool _detect(struct MTK19_detect_state &state, uint8_t data)
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
float wrap_360(const T angle, float unit_mod)
Definition: AP_Math.cpp:123
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
uint32_t millis()
Definition: system.cpp:157
#define MTK_GPS_REVISION_V19
Definition: AP_GPS_MTK19.h:29
Receiving valid messages and 2D lock.
Definition: AP_GPS.h:99
AP_GPS::GPS_State & state
public state for this instance
Definition: GPS_Backend.h:71
virtual int16_t read()=0
bool read(void)
uint8_t _fix_counter
Definition: AP_GPS_MTK19.h:77
virtual uint32_t available()=0
Location location
last fix location
Definition: AP_GPS.h:135
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
void fill_3d_velocity(void)
Receiving valid GPS messages but no lock.
Definition: AP_GPS.h:98
static void send_init_blob(uint8_t instance, AP_GPS &gps)
Definition: AP_GPS_MTK.cpp:41
void make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
Definition: GPS_Backend.cpp:76
uint8_t _payload_counter
Definition: AP_GPS_MTK19.h:74
AP_HAL::UARTDriver * port
UART we are attached to.
Definition: GPS_Backend.h:69
float ground_speed
ground speed in m/sec
Definition: AP_GPS.h:136
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
uint8_t _ck_a
Definition: AP_GPS_MTK19.h:69
uint8_t _step
Definition: AP_GPS_MTK19.h:73
uint16_t hdop
horizontal dilution of precision in cm
Definition: AP_GPS.h:138
uint8_t num_sats
Number of visible satellites.
Definition: AP_GPS.h:140
float ground_course
ground course in degrees
Definition: AP_GPS.h:137