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_SBF.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
// Septentrio GPS driver for ArduPilot.
18
// Code by Michael Oborne
19
//
20
21
#include "AP_GPS.h"
22
#include "AP_GPS_SBF.h"
23
#include <GCS_MAVLink/GCS.h>
24
#include <AP_InternalError/AP_InternalError.h>
25
#include <stdio.h>
26
#include <ctype.h>
27
28
#if AP_GPS_SBF_ENABLED
29
extern const AP_HAL::HAL& hal;
30
31
#define SBF_DEBUGGING 0
32
33
#if SBF_DEBUGGING
34
# define Debug(fmt, args ...) \
35
do { \
36
hal.console->printf("%s:%d: " fmt "\n", \
37
__FUNCTION__, __LINE__, \
38
## args); \
39
hal.scheduler->delay(1); \
40
} while(0)
41
#else
42
# define Debug(fmt, args ...)
43
#endif
44
45
#ifndef GPS_SBF_STREAM_NUMBER
46
#define GPS_SBF_STREAM_NUMBER 1
47
#endif
48
49
#define SBF_EXCESS_COMMAND_BYTES 5 // 2 start bytes + validity byte + space byte + endline byte
50
51
#define RX_ERROR_MASK (CONGESTION | \
52
MISSEDEVENT | \
53
CPUOVERLOAD | \
54
INVALIDCONFIG | \
55
OUTOFGEOFENCE)
56
57
constexpr const char *AP_GPS_SBF::portIdentifiers[];
58
constexpr const char* AP_GPS_SBF::_initialisation_blob[];
59
constexpr const char* AP_GPS_SBF::sbas_on_blob[];
60
61
AP_GPS_SBF::AP_GPS_SBF(AP_GPS &_gps,
62
AP_GPS::Params &_params,
63
AP_GPS::GPS_State &_state,
64
AP_HAL::UARTDriver *_port) :
65
AP_GPS_Backend(_gps, _params, _state, _port)
66
{
67
sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
68
69
_config_last_ack_time = AP_HAL::millis();
70
71
// if we ever parse RTK observations it will always be of type NED, so set it once
72
state.rtk_baseline_coords_type = RTK_BASELINE_COORDINATE_SYSTEM_NED;
73
74
// yaw available when option bit set or using dual antenna
75
if (option_set(AP_GPS::DriverOptions::SBF_UseBaseForYaw) ||
76
(get_type() == AP_GPS::GPS_Type::GPS_TYPE_SBF_DUAL_ANTENNA)) {
77
state.gps_yaw_configured = true;
78
}
79
}
80
81
AP_GPS_SBF::~AP_GPS_SBF (void) {
82
free(config_string);
83
}
84
85
// Process all bytes available from the stream
86
//
87
bool
88
AP_GPS_SBF::read(void)
89
{
90
bool ret = false;
91
uint32_t available_bytes = port->available();
92
for (uint32_t i = 0; i < available_bytes; i++) {
93
uint8_t temp = port->read();
94
#if AP_GPS_DEBUG_LOGGING_ENABLED
95
log_data(&temp, 1);
96
#endif
97
ret |= parse(temp);
98
}
99
100
const uint32_t now = AP_HAL::millis();
101
if (gps._auto_config != AP_GPS::GPS_AUTO_CONFIG_DISABLE) {
102
if (config_step != Config_State::Complete) {
103
if (now > _init_blob_time) {
104
if (now > _config_last_ack_time + 2000) {
105
const size_t port_enable_len = strlen(_port_enable);
106
if (port_enable_len <= port->txspace()) {
107
// try to enable input on the GPS port if we have not made progress on configuring it
108
Debug("SBF Sending port enable");
109
port->write((const uint8_t*)_port_enable, port_enable_len);
110
_config_last_ack_time = now;
111
}
112
} else if (readyForCommand) {
113
if (config_string == nullptr) {
114
switch (config_step) {
115
case Config_State::Baud_Rate:
116
if (asprintf(&config_string, "scs,COM%d,baud%d,bits8,No,bit1,%s\n",
117
(int)params.com_port,
118
230400,
119
port->get_flow_control() != AP_HAL::UARTDriver::flow_control::FLOW_CONTROL_ENABLE ? "none" : "RTS|CTS") == -1) {
120
config_string = nullptr;
121
}
122
break;
123
case Config_State::SSO:
124
const char *extra_config;
125
switch (get_type()) {
126
case AP_GPS::GPS_Type::GPS_TYPE_SBF_DUAL_ANTENNA:
127
extra_config = "+AttCovEuler+AuxAntPositions";
128
break;
129
case AP_GPS::GPS_Type::GPS_TYPE_SBF:
130
default:
131
extra_config = "";
132
break;
133
}
134
if (asprintf(&config_string, "sso,Stream%d,COM%d,PVTGeodetic+DOP+ReceiverStatus+VelCovGeodetic+BaseVectorGeod%s,msec100\n",
135
(int)GPS_SBF_STREAM_NUMBER,
136
(int)params.com_port,
137
extra_config) == -1) {
138
config_string = nullptr;
139
}
140
break;
141
case Config_State::Constellation:
142
if ((params.gnss_mode&0x6F)!=0) {
143
//IMES not taken into account by Septentrio receivers
144
if (asprintf(&config_string, "sst, %s%s%s%s%s%s\n", (params.gnss_mode&(1U<<0))!=0 ? "GPS" : "",
145
(params.gnss_mode&(1U<<1))!=0 ? ((params.gnss_mode&0x01)==0 ? "SBAS" : "+SBAS") : "",
146
(params.gnss_mode&(1U<<2))!=0 ? ((params.gnss_mode&0x03)==0 ? "GALILEO" : "+GALILEO") : "",
147
(params.gnss_mode&(1U<<3))!=0 ? ((params.gnss_mode&0x07)==0 ? "BEIDOU" : "+BEIDOU") : "",
148
(params.gnss_mode&(1U<<5))!=0 ? ((params.gnss_mode&0x0F)==0 ? "QZSS" : "+QZSS") : "",
149
(params.gnss_mode&(1U<<6))!=0 ? ((params.gnss_mode&0x2F)==0 ? "GLONASS" : "+GLONASS") : "") == -1) {
150
config_string=nullptr;
151
}
152
}
153
break;
154
case Config_State::Blob:
155
if (asprintf(&config_string, "%s\n", _initialisation_blob[_init_blob_index]) == -1) {
156
config_string = nullptr;
157
}
158
break;
159
case Config_State::SBAS:
160
switch ((AP_GPS::SBAS_Mode)gps._sbas_mode) {
161
case AP_GPS::SBAS_Mode::Disabled:
162
if (asprintf(&config_string, "%s\n", sbas_off) == -1) {
163
config_string = nullptr;
164
}
165
break;
166
case AP_GPS::SBAS_Mode::Enabled:
167
if (asprintf(&config_string, "%s\n", sbas_on_blob[_init_blob_index]) == -1) {
168
config_string = nullptr;
169
}
170
break;
171
case AP_GPS::SBAS_Mode::DoNotChange:
172
config_string = nullptr;
173
config_step = Config_State::Complete;
174
break;
175
}
176
break;
177
case Config_State::SGA:
178
{
179
const char *targetGA = "none";
180
if (get_type() == AP_GPS::GPS_Type::GPS_TYPE_SBF_DUAL_ANTENNA) {
181
targetGA = "MultiAntenna";
182
}
183
if (asprintf(&config_string, "sga, %s\n", targetGA)) {
184
config_string = nullptr;
185
}
186
break;
187
}
188
case Config_State::Complete:
189
// should never reach here, why search for a config if we have fully configured already
190
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
191
break;
192
}
193
}
194
195
if (config_string != nullptr) {
196
const size_t config_length = strlen(config_string);
197
if (config_length <= port->txspace()) {
198
Debug("SBF sending init string: %s", config_string);
199
port->write((const uint8_t*)config_string, config_length);
200
readyForCommand = false;
201
}
202
}
203
}
204
}
205
} else if (gps._raw_data == 2) { // only manage disarm/rearms when the user opts into it
206
if (hal.util->get_soft_armed()) {
207
_has_been_armed = true;
208
} else if (_has_been_armed && (RxState & SBF_DISK_MOUNTED)) {
209
// since init is done at this point and unmounting should be rate limited,
210
// take over the _init_blob_time variable
211
if (now > _init_blob_time) {
212
unmount_disk();
213
_init_blob_time = now + 1000;
214
}
215
}
216
}
217
}
218
219
// yaw timeout after 300 milliseconds
220
if ((now - state.gps_yaw_time_ms) > 300) {
221
state.have_gps_yaw = false;
222
state.have_gps_yaw_accuracy = false;
223
}
224
225
return ret;
226
}
227
228
bool AP_GPS_SBF::logging_healthy(void) const
229
{
230
switch (gps._raw_data) {
231
case 1:
232
default:
233
return (RxState & SBF_DISK_MOUNTED) && (RxState & SBF_DISK_ACTIVITY);
234
case 2:
235
return ((RxState & SBF_DISK_MOUNTED) && (RxState & SBF_DISK_ACTIVITY)) || (!hal.util->get_soft_armed() && _has_been_armed);
236
}
237
}
238
239
bool
240
AP_GPS_SBF::parse(uint8_t temp)
241
{
242
switch (sbf_msg.sbf_state)
243
{
244
default:
245
case sbf_msg_parser_t::PREAMBLE1:
246
if (temp == SBF_PREAMBLE1) {
247
sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE2;
248
sbf_msg.read = 0;
249
} else {
250
// attempt to detect command prompt
251
portIdentifier[portLength++] = (char)temp;
252
bool foundPossiblePort = false;
253
for (const char *portId : portIdentifiers) {
254
if (strncmp(portId, portIdentifier, MIN(portLength, 3)) == 0) {
255
// we found one of the COM/USB/IP related ports
256
if (portLength == 4) {
257
// validate that we have an ascii number
258
if (isdigit((char)temp)) {
259
foundPossiblePort = true;
260
break;
261
}
262
} else if (portLength >= sizeof(portIdentifier)) {
263
if ((char)temp == '>') {
264
readyForCommand = true;
265
Debug("SBF: Ready for command");
266
}
267
} else {
268
foundPossiblePort = true;
269
}
270
break;
271
}
272
}
273
if (!foundPossiblePort) {
274
portLength = 0;
275
}
276
}
277
break;
278
case sbf_msg_parser_t::PREAMBLE2:
279
if (temp == SBF_PREAMBLE2) {
280
sbf_msg.sbf_state = sbf_msg_parser_t::CRC1;
281
} else if (temp == 'R') {
282
Debug("SBF got a response\n");
283
sbf_msg.sbf_state = sbf_msg_parser_t::COMMAND_LINE;
284
}
285
else
286
{
287
sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
288
}
289
break;
290
case sbf_msg_parser_t::CRC1:
291
sbf_msg.crc = temp;
292
sbf_msg.sbf_state = sbf_msg_parser_t::CRC2;
293
break;
294
case sbf_msg_parser_t::CRC2:
295
sbf_msg.crc += (uint16_t)(temp << 8);
296
sbf_msg.sbf_state = sbf_msg_parser_t::BLOCKID1;
297
break;
298
case sbf_msg_parser_t::BLOCKID1:
299
sbf_msg.blockid = temp;
300
sbf_msg.sbf_state = sbf_msg_parser_t::BLOCKID2;
301
break;
302
case sbf_msg_parser_t::BLOCKID2:
303
sbf_msg.blockid += (uint16_t)(temp << 8);
304
sbf_msg.sbf_state = sbf_msg_parser_t::LENGTH1;
305
break;
306
case sbf_msg_parser_t::LENGTH1:
307
sbf_msg.length = temp;
308
sbf_msg.sbf_state = sbf_msg_parser_t::LENGTH2;
309
break;
310
case sbf_msg_parser_t::LENGTH2:
311
sbf_msg.length += (uint16_t)(temp << 8);
312
sbf_msg.sbf_state = sbf_msg_parser_t::DATA;
313
if (sbf_msg.length % 4 != 0) {
314
sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
315
Debug("bad packet length=%u\n", (unsigned)sbf_msg.length);
316
}
317
if (sbf_msg.length < 8) {
318
Debug("bad packet length=%u\n", (unsigned)sbf_msg.length);
319
sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
320
crc_error_counter++; // this is a probable buffer overflow, but this
321
// indicates not enough bytes to do a crc
322
break;
323
}
324
break;
325
case sbf_msg_parser_t::DATA:
326
if (sbf_msg.read < sizeof(sbf_msg.data)) {
327
sbf_msg.data.bytes[sbf_msg.read] = temp;
328
}
329
sbf_msg.read++;
330
if (sbf_msg.read >= (sbf_msg.length - 8)) {
331
if (sbf_msg.read > sizeof(sbf_msg.data)) {
332
// not interested in these large messages
333
sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
334
break;
335
}
336
uint16_t crc = crc16_ccitt((uint8_t*)&sbf_msg.blockid, 2, 0);
337
crc = crc16_ccitt((uint8_t*)&sbf_msg.length, 2, crc);
338
crc = crc16_ccitt((uint8_t*)&sbf_msg.data, sbf_msg.length - 8, crc);
339
340
sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
341
342
if (sbf_msg.crc == crc) {
343
return process_message();
344
} else {
345
Debug("crc fail\n");
346
crc_error_counter++;
347
}
348
}
349
break;
350
case sbf_msg_parser_t::COMMAND_LINE:
351
if (sbf_msg.read < (sizeof(sbf_msg.data) - 1)) {
352
sbf_msg.data.bytes[sbf_msg.read] = temp;
353
} else {
354
// we don't have enough buffer to compare the commands
355
// most probable cause is that a user injected a longer command then
356
// we have buffer for, or it could be a corruption, either way we
357
// simply ignore the result
358
sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
359
break;
360
}
361
sbf_msg.read++;
362
if (temp == '\n') {
363
sbf_msg.data.bytes[sbf_msg.read] = 0;
364
365
// received the result, lets assess it
366
if (sbf_msg.data.bytes[0] == ':') {
367
// valid command, determine if it was the one we were trying
368
// to send in the configuration sequence
369
if (config_string != nullptr) {
370
if (!strncmp(config_string, (char *)(sbf_msg.data.bytes + 2),
371
sbf_msg.read - SBF_EXCESS_COMMAND_BYTES)) {
372
Debug("SBF Ack Command: %s\n", sbf_msg.data.bytes);
373
free(config_string);
374
config_string = nullptr;
375
switch (config_step) {
376
case Config_State::Baud_Rate:
377
config_step = Config_State::SSO;
378
break;
379
case Config_State::SSO:
380
config_step = Config_State::Constellation;
381
break;
382
case Config_State::Constellation:
383
config_step = Config_State::Blob;
384
break;
385
case Config_State::Blob:
386
_init_blob_index++;
387
if (_init_blob_index >= ARRAY_SIZE(_initialisation_blob)) {
388
config_step = Config_State::SBAS;
389
_init_blob_index = 0;
390
}
391
break;
392
case Config_State::SBAS:
393
_init_blob_index++;
394
if ((gps._sbas_mode == AP_GPS::SBAS_Mode::Disabled)
395
||_init_blob_index >= ARRAY_SIZE(sbas_on_blob)) {
396
config_step = Config_State::SGA;
397
}
398
break;
399
case Config_State::SGA:
400
config_step = Config_State::Complete;
401
break;
402
case Config_State::Complete:
403
// should never reach here, this implies that we validated a config string when we hadn't sent any
404
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
405
break;
406
}
407
_config_last_ack_time = AP_HAL::millis();
408
} else {
409
Debug("SBF Ack command (unexpected): %s\n", sbf_msg.data.bytes);
410
}
411
}
412
} else {
413
// rejected command, send it out as a debug
414
Debug("SBF NACK Command: %s\n", sbf_msg.data.bytes);
415
}
416
// resume normal parsing
417
sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
418
break;
419
}
420
break;
421
}
422
423
return false;
424
}
425
426
static bool is_DNU(double value)
427
{
428
constexpr double DNU = -2e-10f;
429
#pragma GCC diagnostic push
430
#pragma GCC diagnostic ignored "-Wfloat-equal" // suppress -Wfloat-equal as it's false positive when testing for DNU values
431
return value != DNU;
432
#pragma GCC diagnostic pop
433
}
434
435
bool
436
AP_GPS_SBF::process_message(void)
437
{
438
uint16_t blockid = (sbf_msg.blockid & 8191u);
439
440
Debug("BlockID %d", blockid);
441
442
switch (blockid) {
443
case PVTGeodetic:
444
{
445
const msg4007 &temp = sbf_msg.data.msg4007u;
446
447
// Update time state
448
if (temp.WNc != 65535) {
449
state.time_week = temp.WNc;
450
state.time_week_ms = (uint32_t)(temp.TOW);
451
}
452
453
check_new_itow(temp.TOW, sbf_msg.length);
454
state.last_gps_time_ms = AP_HAL::millis();
455
456
// Update velocity state (don't use −2·10^10)
457
if (temp.Vn > -200000) {
458
state.velocity.x = (float)(temp.Vn);
459
state.velocity.y = (float)(temp.Ve);
460
state.velocity.z = (float)(-temp.Vu);
461
462
state.have_vertical_velocity = true;
463
464
velocity_to_speed_course(state);
465
state.rtk_age_ms = temp.MeanCorrAge * 10;
466
467
// value is expressed as twice the rms error = int16 * 0.01/2
468
state.horizontal_accuracy = (float)temp.HAccuracy * 0.005f;
469
state.vertical_accuracy = (float)temp.VAccuracy * 0.005f;
470
state.have_horizontal_accuracy = true;
471
state.have_vertical_accuracy = true;
472
}
473
474
// Update position state (don't use -2·10^10)
475
if (temp.Latitude > -200000) {
476
state.location.lat = (int32_t)(temp.Latitude * RAD_TO_DEG_DOUBLE * (double)1e7);
477
state.location.lng = (int32_t)(temp.Longitude * RAD_TO_DEG_DOUBLE * (double)1e7);
478
state.have_undulation = !is_DNU(temp.Undulation);
479
double height = temp.Height; // in metres
480
if (state.have_undulation) {
481
height -= temp.Undulation;
482
state.undulation = -temp.Undulation;
483
}
484
set_alt_amsl_cm(state, (float)height * 1e2f); // m -> cm
485
}
486
487
state.num_sats = temp.NrSV;
488
if (temp.NrSV == 255) {
489
// Do-Not-Use value for NrSV field in PVTGeodetic message
490
state.num_sats = 0;
491
}
492
493
Debug("temp.Mode=0x%02x\n", (unsigned)temp.Mode);
494
switch (temp.Mode & 15) {
495
case 0: // no pvt
496
state.status = AP_GPS::NO_FIX;
497
break;
498
case 1: // standalone
499
state.status = AP_GPS::GPS_OK_FIX_3D;
500
break;
501
case 2: // dgps
502
state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
503
break;
504
case 3: // fixed location
505
state.status = AP_GPS::GPS_OK_FIX_3D;
506
break;
507
case 4: // rtk fixed
508
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
509
break;
510
case 5: // rtk float
511
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
512
break;
513
case 6: // sbas
514
state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
515
break;
516
case 7: // moving rtk fixed
517
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
518
break;
519
case 8: // moving rtk float
520
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
521
break;
522
}
523
524
if ((temp.Mode & 64) > 0) { // gps is in base mode
525
state.status = AP_GPS::NO_FIX;
526
} else if ((temp.Mode & 128) > 0) { // gps only has 2d fix
527
state.status = AP_GPS::GPS_OK_FIX_2D;
528
}
529
530
return true;
531
}
532
case DOP:
533
{
534
const msg4001 &temp = sbf_msg.data.msg4001u;
535
check_new_itow(temp.TOW, sbf_msg.length);
536
537
state.hdop = temp.HDOP;
538
state.vdop = temp.VDOP;
539
break;
540
}
541
case ReceiverStatus:
542
{
543
const msg4014 &temp = sbf_msg.data.msg4014u;
544
check_new_itow(temp.TOW, sbf_msg.length);
545
RxState = temp.RxState;
546
if ((RxError & RX_ERROR_MASK) != (temp.RxError & RX_ERROR_MASK)) {
547
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %u: SBF error changed (0x%08x/0x%08x)", (unsigned int)(state.instance + 1),
548
(unsigned int)(RxError & RX_ERROR_MASK), (unsigned int)(temp.RxError & RX_ERROR_MASK));
549
}
550
RxError = temp.RxError;
551
break;
552
}
553
case VelCovGeodetic:
554
{
555
const msg5908 &temp = sbf_msg.data.msg5908u;
556
557
check_new_itow(temp.TOW, sbf_msg.length);
558
// select the maximum variance, as the EKF will apply it to all the columns in it's estimate
559
// FIXME: Support returning the covariance matrix to the EKF
560
float max_variance_squared = MAX(temp.Cov_VnVn, MAX(temp.Cov_VeVe, temp.Cov_VuVu));
561
if (is_positive(max_variance_squared)) {
562
state.have_speed_accuracy = true;
563
state.speed_accuracy = sqrt(max_variance_squared);
564
} else {
565
state.have_speed_accuracy = false;
566
}
567
break;
568
}
569
case AttEulerCov:
570
{
571
// yaw accuracy is taken from this message even though we actually calculate the yaw ourself (see AuxAntPositions below)
572
// this is OK based on the assumption that the calculation methods are similar and that inaccuracy arises from the sensor readings
573
if (get_type() == AP_GPS::GPS_Type::GPS_TYPE_SBF_DUAL_ANTENNA) {
574
const msg5939 &temp = sbf_msg.data.msg5939u;
575
576
check_new_itow(temp.TOW, sbf_msg.length);
577
578
constexpr double floatDNU = -2e-10f;
579
constexpr uint8_t errorBits = 0x8F; // Bits 0-1 are aux 1 baseline
580
// Bits 2-3 are aux 2 baseline
581
// Bit 7 is attitude not requested
582
#pragma GCC diagnostic push
583
#pragma GCC diagnostic ignored "-Wfloat-equal" // suppress -Wfloat-equal as it's false positive when testing for DNU values
584
if (((temp.Error & errorBits) == 0)
585
&& (temp.Cov_HeadHead != floatDNU)) {
586
#pragma GCC diagnostic pop
587
state.gps_yaw_accuracy = sqrtf(temp.Cov_HeadHead);
588
state.have_gps_yaw_accuracy = true;
589
} else {
590
state.gps_yaw_accuracy = false;
591
}
592
}
593
break;
594
}
595
case AuxAntPositions:
596
{
597
#if GPS_MOVING_BASELINE
598
if (get_type() == AP_GPS::GPS_Type::GPS_TYPE_SBF_DUAL_ANTENNA) {
599
// calculate yaw using reported antenna positions in earth-frame
600
// note that this calculation does not correct for the vehicle's roll and pitch meaning it is inaccurate at very high lean angles
601
const msg5942 &temp = sbf_msg.data.msg5942u;
602
check_new_itow(temp.TOW, sbf_msg.length);
603
if (temp.N > 0 && temp.ant1.Error == 0 && temp.ant1.AmbiguityType == 0) {
604
// valid RTK integer fix
605
const float rel_heading_deg = degrees(atan2f(temp.ant1.DeltaEast, temp.ant1.DeltaNorth));
606
calculate_moving_base_yaw(rel_heading_deg,
607
Vector3f(temp.ant1.DeltaNorth, temp.ant1.DeltaEast, temp.ant1.DeltaUp).length(),
608
-temp.ant1.DeltaUp);
609
}
610
}
611
#endif
612
break;
613
}
614
case BaseVectorGeod:
615
{
616
#pragma GCC diagnostic push
617
#pragma GCC diagnostic ignored "-Wfloat-equal" // suppress -Wfloat-equal as it's false positive when testing for DNU values
618
const msg4028 &temp = sbf_msg.data.msg4028u;
619
620
// just breakout any consts we need for Do Not Use (DNU) reasons
621
constexpr double doubleDNU = -2e-10;
622
constexpr uint16_t uint16DNU = 65535;
623
624
check_new_itow(temp.TOW, sbf_msg.length);
625
626
if (temp.N == 0) { // no sub blocks so just bail, we can't do anything useful here
627
state.rtk_num_sats = 0;
628
state.rtk_age_ms = 0;
629
state.rtk_baseline_y_mm = 0;
630
state.rtk_baseline_x_mm = 0;
631
state.rtk_baseline_z_mm = 0;
632
break;
633
}
634
635
state.rtk_num_sats = temp.info.NrSV;
636
637
state.rtk_age_ms = (temp.info.CorrAge != 65535) ? ((uint32_t)temp.info.CorrAge) * 10 : 0;
638
639
// copy the position as long as the data isn't DNU, we require NED, and heading before accepting any of it
640
if ((temp.info.DeltaEast != doubleDNU) && (temp.info.DeltaNorth != doubleDNU) && (temp.info.DeltaUp != doubleDNU) &&
641
(temp.info.Azimuth != uint16DNU)) {
642
643
state.rtk_baseline_y_mm = temp.info.DeltaEast * 1e3;
644
state.rtk_baseline_x_mm = temp.info.DeltaNorth * 1e3;
645
state.rtk_baseline_z_mm = temp.info.DeltaUp * -1e3;
646
647
#if GPS_MOVING_BASELINE
648
// copy the baseline data as a yaw source
649
if (option_set(AP_GPS::DriverOptions::SBF_UseBaseForYaw)) {
650
calculate_moving_base_yaw(temp.info.Azimuth * 0.01f + 180.0f,
651
Vector3f(temp.info.DeltaNorth, temp.info.DeltaEast, temp.info.DeltaUp).length(),
652
-temp.info.DeltaUp);
653
}
654
#endif // GPS_MOVING_BASELINE
655
656
} else if (option_set(AP_GPS::DriverOptions::SBF_UseBaseForYaw)) {
657
state.rtk_baseline_y_mm = 0;
658
state.rtk_baseline_x_mm = 0;
659
state.rtk_baseline_z_mm = 0;
660
state.have_gps_yaw = false;
661
}
662
663
#pragma GCC diagnostic pop
664
break;
665
}
666
}
667
668
return false;
669
}
670
671
void AP_GPS_SBF::broadcast_configuration_failure_reason(void) const
672
{
673
if (gps._auto_config != AP_GPS::GPS_AUTO_CONFIG_DISABLE &&
674
config_step != Config_State::Complete) {
675
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %u: SBF is not fully configured (%u/%u/%u/%u)",
676
state.instance + 1,
677
(unsigned)config_step,
678
_init_blob_index,
679
(unsigned)ARRAY_SIZE(_initialisation_blob),
680
(unsigned)ARRAY_SIZE(sbas_on_blob));
681
}
682
}
683
684
bool AP_GPS_SBF::is_configured (void) const {
685
return ((gps._auto_config == AP_GPS::GPS_AUTO_CONFIG_DISABLE) ||
686
(config_step == Config_State::Complete) ||AP_SIM_GPS_SBF_ENABLED);
687
}
688
689
bool AP_GPS_SBF::is_healthy (void) const {
690
return (RxError & RX_ERROR_MASK) == 0;
691
}
692
693
void AP_GPS_SBF::mount_disk (void) const {
694
const char* command = "emd, DSK1, Mount\n";
695
Debug("Mounting disk");
696
port->write((const uint8_t*)command, strlen(command));
697
}
698
699
void AP_GPS_SBF::unmount_disk (void) const {
700
const char* command = "emd, DSK1, Unmount\n";
701
GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "SBF unmounting disk");
702
port->write((const uint8_t*)command, strlen(command));
703
}
704
705
bool AP_GPS_SBF::prepare_for_arming(void) {
706
bool is_logging = true; // assume that its logging until proven otherwise
707
if (gps._raw_data) {
708
if (!(RxState & SBF_DISK_MOUNTED)){
709
is_logging = false;
710
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: SBF disk is not mounted", state.instance + 1);
711
712
// simply attempt to mount the disk, no need to check if the command was
713
// ACK/NACK'd as we don't continuously attempt to remount the disk
714
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: Attempting to mount disk", state.instance + 1);
715
mount_disk();
716
// reset the flag to indicate if we should be logging
717
_has_been_armed = false;
718
}
719
else if (RxState & SBF_DISK_FULL) {
720
is_logging = false;
721
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: SBF disk is full", state.instance + 1);
722
}
723
else if (!(RxState & SBF_DISK_ACTIVITY)) {
724
is_logging = false;
725
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: SBF is not currently logging", state.instance + 1);
726
}
727
}
728
729
return is_logging;
730
}
731
732
#endif
733
734