Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_GPS/AP_GPS_SBP.cpp
9518 views
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
// Swift Navigation SBP GPS driver for ArduPilot.
18
// Code by Niels Joubert
19
//
20
// Swift Binary Protocol format: http://docs.swift-nav.com/
21
//
22
23
24
#include "AP_GPS.h"
25
#include "AP_GPS_SBP.h"
26
#include <AP_Logger/AP_Logger.h>
27
28
#if AP_GPS_SBP_ENABLED
29
30
extern const AP_HAL::HAL& hal;
31
32
#define SBP_DEBUGGING 1
33
34
#define SBP_TIMEOUT_HEATBEAT 4000
35
#define SBP_TIMEOUT_PVT 500
36
37
#if SBP_DEBUGGING
38
# define Debug(fmt, args ...) \
39
do { \
40
hal.console->printf("%s:%d: " fmt "\n", \
41
__FUNCTION__, __LINE__, \
42
## args); \
43
hal.scheduler->delay(1); \
44
} while(0)
45
#else
46
# define Debug(fmt, args ...)
47
#endif
48
49
AP_GPS_SBP::AP_GPS_SBP(AP_GPS &_gps,
50
AP_GPS::Params &_params,
51
AP_GPS::GPS_State &_state,
52
AP_HAL::UARTDriver *_port) :
53
AP_GPS_Backend(_gps, _params, _state, _port)
54
{
55
56
Debug("SBP Driver Initialized");
57
58
parser_state.state = sbp_parser_state_t::WAITING;
59
60
//Externally visible state
61
state.status = AP_GPS::NO_FIX;
62
state.last_gps_time_ms = last_heatbeat_received_ms = AP_HAL::millis();
63
64
}
65
66
// Process all bytes available from the stream
67
//
68
bool
69
AP_GPS_SBP::read(void)
70
{
71
72
//Invariant: Calling this function processes *all* data current in the UART buffer.
73
//
74
//IMPORTANT NOTICE: This function is NOT CALLED for several seconds
75
// during arming. That should not cause the driver to die. Process *all* waiting messages
76
77
_sbp_process();
78
79
return _attempt_state_update();
80
81
}
82
83
void
84
AP_GPS_SBP::inject_data(const uint8_t *data, uint16_t len)
85
{
86
87
if (port->txspace() > len) {
88
last_injected_data_ms = AP_HAL::millis();
89
port->write(data, len);
90
} else {
91
Debug("PIKSI: Not enough TXSPACE");
92
}
93
94
}
95
96
//This attempts to reads all SBP messages from the incoming port.
97
//Returns true if a new message was read, false if we failed to read a message.
98
void
99
AP_GPS_SBP::_sbp_process()
100
{
101
102
while (port->available() > 0) {
103
uint8_t temp = port->read();
104
#if AP_GPS_DEBUG_LOGGING_ENABLED
105
log_data(&temp, 1);
106
#endif
107
uint16_t crc;
108
109
110
//This switch reads one character at a time,
111
//parsing it into buffers until a full message is dispatched
112
switch (parser_state.state) {
113
case sbp_parser_state_t::WAITING:
114
if (temp == SBP_PREAMBLE) {
115
parser_state.n_read = 0;
116
parser_state.state = sbp_parser_state_t::GET_TYPE;
117
}
118
break;
119
120
case sbp_parser_state_t::GET_TYPE:
121
*((uint8_t*)&(parser_state.msg_type) + parser_state.n_read) = temp;
122
parser_state.n_read += 1;
123
if (parser_state.n_read >= 2) {
124
parser_state.n_read = 0;
125
parser_state.state = sbp_parser_state_t::GET_SENDER;
126
}
127
break;
128
129
case sbp_parser_state_t::GET_SENDER:
130
*((uint8_t*)&(parser_state.sender_id) + parser_state.n_read) = temp;
131
parser_state.n_read += 1;
132
if (parser_state.n_read >= 2) {
133
parser_state.n_read = 0;
134
parser_state.state = sbp_parser_state_t::GET_LEN;
135
}
136
break;
137
138
case sbp_parser_state_t::GET_LEN:
139
parser_state.msg_len = temp;
140
parser_state.n_read = 0;
141
parser_state.state = sbp_parser_state_t::GET_MSG;
142
break;
143
144
case sbp_parser_state_t::GET_MSG:
145
*((uint8_t*)&(parser_state.msg_buff) + parser_state.n_read) = temp;
146
parser_state.n_read += 1;
147
if (parser_state.n_read >= parser_state.msg_len) {
148
parser_state.n_read = 0;
149
parser_state.state = sbp_parser_state_t::GET_CRC;
150
}
151
break;
152
153
case sbp_parser_state_t::GET_CRC:
154
*((uint8_t*)&(parser_state.crc) + parser_state.n_read) = temp;
155
parser_state.n_read += 1;
156
if (parser_state.n_read >= 2) {
157
parser_state.state = sbp_parser_state_t::WAITING;
158
159
crc = crc16_ccitt((uint8_t*)&(parser_state.msg_type), 2, 0);
160
crc = crc16_ccitt((uint8_t*)&(parser_state.sender_id), 2, crc);
161
crc = crc16_ccitt(&(parser_state.msg_len), 1, crc);
162
crc = crc16_ccitt(parser_state.msg_buff, parser_state.msg_len, crc);
163
if (parser_state.crc == crc) {
164
_sbp_process_message();
165
} else {
166
Debug("CRC Error Occurred!");
167
crc_error_counter += 1;
168
}
169
170
parser_state.state = sbp_parser_state_t::WAITING;
171
}
172
break;
173
174
default:
175
parser_state.state = sbp_parser_state_t::WAITING;
176
break;
177
}
178
}
179
}
180
181
182
//INVARIANT: A fully received message with correct CRC is currently in parser_state
183
void
184
AP_GPS_SBP::_sbp_process_message() {
185
switch (parser_state.msg_type) {
186
case SBP_HEARTBEAT_MSGTYPE:
187
last_heatbeat_received_ms = AP_HAL::millis();
188
break;
189
190
case SBP_GPS_TIME_MSGTYPE:
191
memcpy(&last_gps_time, parser_state.msg_buff, sizeof(last_gps_time));
192
check_new_itow(last_gps_time.tow, parser_state.msg_len);
193
break;
194
195
case SBP_VEL_NED_MSGTYPE:
196
memcpy(&last_vel_ned, parser_state.msg_buff, sizeof(last_vel_ned));
197
check_new_itow(last_vel_ned.tow, parser_state.msg_len);
198
break;
199
200
case SBP_POS_LLH_MSGTYPE: {
201
struct sbp_pos_llh_t *pos_llh = (struct sbp_pos_llh_t*)parser_state.msg_buff;
202
check_new_itow(pos_llh->tow, parser_state.msg_len);
203
// Check if this is a single point or RTK solution
204
// flags = 0 -> single point
205
if (pos_llh->flags == 0) {
206
last_pos_llh_spp = *pos_llh;
207
} else if (pos_llh->flags == 1 || pos_llh->flags == 2) {
208
last_pos_llh_rtk = *pos_llh;
209
}
210
break;
211
}
212
213
case SBP_DOPS_MSGTYPE:
214
memcpy(&last_dops, parser_state.msg_buff, sizeof(last_dops));
215
check_new_itow(last_dops.tow, parser_state.msg_len);
216
break;
217
218
case SBP_TRACKING_STATE_MSGTYPE:
219
//INTENTIONALLY BLANK
220
//Currently unhandled, but logged after switch statement.
221
break;
222
223
case SBP_IAR_STATE_MSGTYPE: {
224
sbp_iar_state_t *iar = (struct sbp_iar_state_t*)parser_state.msg_buff;
225
last_iar_num_hypotheses = iar->num_hypotheses;
226
break;
227
}
228
229
default:
230
// log anyway if it's an unsupported message.
231
// The log mask will be used to adjust or suppress logging
232
break;
233
}
234
}
235
236
bool
237
AP_GPS_SBP::_attempt_state_update()
238
{
239
240
// If we currently have heartbeats
241
// - NO FIX
242
//
243
// If we have a full update available, save it
244
//
245
uint32_t now = AP_HAL::millis();
246
bool ret = false;
247
248
if (now - last_heatbeat_received_ms > SBP_TIMEOUT_HEATBEAT) {
249
250
state.status = AP_GPS::NO_FIX;
251
Debug("No Heartbeats from Piksi! Driver Ready to Die!");
252
253
} else if (last_pos_llh_rtk.tow == last_vel_ned.tow
254
&& abs((int32_t) (last_gps_time.tow - last_vel_ned.tow)) < 10000
255
&& abs((int32_t) (last_dops.tow - last_vel_ned.tow)) < 60000
256
&& last_vel_ned.tow > last_full_update_tow) {
257
258
// Use the RTK position
259
sbp_pos_llh_t *pos_llh = &last_pos_llh_rtk;
260
261
// Update time state
262
state.time_week = last_gps_time.wn;
263
state.time_week_ms = last_vel_ned.tow;
264
265
state.hdop = last_dops.hdop;
266
267
// Update velocity state
268
state.velocity[0] = (float)(last_vel_ned.n * 1.0e-3);
269
state.velocity[1] = (float)(last_vel_ned.e * 1.0e-3);
270
state.velocity[2] = (float)(last_vel_ned.d * 1.0e-3);
271
state.have_vertical_velocity = true;
272
273
velocity_to_speed_course(state);
274
275
// Update position state
276
277
state.location.lat = (int32_t) (pos_llh->lat * (double)1e7);
278
state.location.lng = (int32_t) (pos_llh->lon * (double)1e7);
279
state.location.alt = (int32_t) (pos_llh->height * 100);
280
state.num_sats = pos_llh->n_sats;
281
282
if (pos_llh->flags == 0) {
283
state.status = AP_GPS::GPS_OK_FIX_3D;
284
} else if (pos_llh->flags == 2) {
285
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
286
} else if (pos_llh->flags == 1) {
287
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
288
}
289
290
last_full_update_tow = last_vel_ned.tow;
291
last_full_update_cpu_ms = now;
292
state.rtk_iar_num_hypotheses = last_iar_num_hypotheses;
293
294
#if HAL_LOGGING_ENABLED
295
logging_log_full_update();
296
#endif
297
ret = true;
298
299
} else if (now - last_full_update_cpu_ms > SBP_TIMEOUT_PVT) {
300
301
//INVARIANT: If we currently have a fix, ONLY return true after a full update.
302
303
state.status = AP_GPS::NO_FIX;
304
ret = true;
305
306
} else {
307
308
//No timeouts yet, no data yet, nothing has happened.
309
310
}
311
312
return ret;
313
314
}
315
316
317
318
bool
319
AP_GPS_SBP::_detect(struct SBP_detect_state &state, uint8_t data)
320
{
321
// This switch reads one character at a time, if we find something that
322
// looks like our preamble we'll try to read the full message length,
323
// calculating the CRC. If the CRC matches, we have an SBP GPS!
324
325
switch (state.state) {
326
case SBP_detect_state::WAITING:
327
if (data == SBP_PREAMBLE) {
328
state.n_read = 0;
329
state.crc_so_far = 0;
330
state.state = SBP_detect_state::GET_TYPE;
331
}
332
break;
333
334
case SBP_detect_state::GET_TYPE:
335
*((uint8_t*)&(state.msg_type) + state.n_read) = data;
336
state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
337
state.n_read += 1;
338
if (state.n_read >= 2) {
339
state.n_read = 0;
340
state.state = SBP_detect_state::GET_SENDER;
341
}
342
break;
343
344
case SBP_detect_state::GET_SENDER:
345
state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
346
state.n_read += 1;
347
if (state.n_read >= 2) {
348
state.n_read = 0;
349
state.state = SBP_detect_state::GET_LEN;
350
}
351
break;
352
353
case SBP_detect_state::GET_LEN:
354
state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
355
state.msg_len = data;
356
state.n_read = 0;
357
state.state = SBP_detect_state::GET_MSG;
358
break;
359
360
case SBP_detect_state::GET_MSG:
361
if (state.msg_type == SBP_HEARTBEAT_MSGTYPE && state.n_read < 4) {
362
*((uint8_t*)&(state.heartbeat_buff) + state.n_read) = data;
363
}
364
state.crc_so_far = crc16_ccitt(&data, 1, state.crc_so_far);
365
state.n_read += 1;
366
if (state.n_read >= state.msg_len) {
367
state.n_read = 0;
368
state.state = SBP_detect_state::GET_CRC;
369
}
370
break;
371
372
case SBP_detect_state::GET_CRC:
373
*((uint8_t*)&(state.crc) + state.n_read) = data;
374
state.n_read += 1;
375
if (state.n_read >= 2) {
376
state.state = SBP_detect_state::WAITING;
377
if (state.crc == state.crc_so_far
378
&& state.msg_type == SBP_HEARTBEAT_MSGTYPE) {
379
struct sbp_heartbeat_t* heartbeat = ((struct sbp_heartbeat_t*)state.heartbeat_buff);
380
return heartbeat->protocol_major == 0;
381
}
382
return false;
383
}
384
break;
385
386
default:
387
state.state = SBP_detect_state::WAITING;
388
break;
389
}
390
return false;
391
}
392
393
#if HAL_LOGGING_ENABLED
394
void
395
AP_GPS_SBP::logging_log_full_update()
396
{
397
398
if (!should_log()) {
399
return;
400
}
401
402
struct log_SbpHealth pkt = {
403
LOG_PACKET_HEADER_INIT(LOG_MSG_SBPHEALTH),
404
time_us : AP_HAL::micros64(),
405
crc_error_counter : crc_error_counter,
406
last_injected_data_ms : last_injected_data_ms,
407
last_iar_num_hypotheses : last_iar_num_hypotheses,
408
};
409
410
AP::logger().WriteBlock(&pkt, sizeof(pkt));
411
};
412
#endif // HAL_LOGGING_ENABLED
413
414
#endif // AP_GPS_SBP_ENABLED
415
416