CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

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