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