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/GPS_Backend.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
#include "AP_GPS_config.h"
17
18
#if AP_GPS_ENABLED
19
20
#include "AP_GPS.h"
21
#include "GPS_Backend.h"
22
#include <AP_Logger/AP_Logger.h>
23
#include <time.h>
24
#include <AP_Common/time.h>
25
#include <AP_InternalError/AP_InternalError.h>
26
#include <AP_AHRS/AP_AHRS.h>
27
28
#define GPS_BACKEND_DEBUGGING 0
29
30
#if GPS_BACKEND_DEBUGGING
31
# define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
32
#else
33
# define Debug(fmt, args ...)
34
#endif
35
36
#include <GCS_MAVLink/GCS.h>
37
38
#if AP_GPS_DEBUG_LOGGING_ENABLED
39
#include <AP_Filesystem/AP_Filesystem.h>
40
#endif
41
42
extern const AP_HAL::HAL& hal;
43
44
AP_GPS_Backend::AP_GPS_Backend(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :
45
port(_port),
46
gps(_gps),
47
state(_state),
48
params(_params)
49
{
50
state.have_speed_accuracy = false;
51
state.have_horizontal_accuracy = false;
52
state.have_vertical_accuracy = false;
53
}
54
55
/**
56
fill in time_week_ms and time_week from BCD date and time components
57
assumes MTK19 millisecond form of bcd_time
58
*/
59
void AP_GPS_Backend::make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
60
{
61
struct tm tm {};
62
63
tm.tm_year = 100U + bcd_date % 100U;
64
tm.tm_mon = ((bcd_date / 100U) % 100U)-1;
65
tm.tm_mday = bcd_date / 10000U;
66
67
uint32_t v = bcd_milliseconds;
68
uint16_t msec = v % 1000U; v /= 1000U;
69
tm.tm_sec = v % 100U; v /= 100U;
70
tm.tm_min = v % 100U; v /= 100U;
71
tm.tm_hour = v % 100U;
72
73
// convert from time structure to unix time
74
time_t unix_time = ap_mktime(&tm);
75
76
// convert to time since GPS epoch
77
const uint32_t unix_to_GPS_secs = 315964800UL;
78
const uint16_t leap_seconds_unix = GPS_LEAPSECONDS_MILLIS/1000U;
79
uint32_t ret = unix_time + leap_seconds_unix - unix_to_GPS_secs;
80
81
// get GPS week and time
82
state.time_week = ret / AP_SEC_PER_WEEK;
83
state.time_week_ms = (ret % AP_SEC_PER_WEEK) * AP_MSEC_PER_SEC;
84
state.time_week_ms += msec;
85
}
86
87
/*
88
get the last time of week in ms
89
*/
90
uint32_t AP_GPS_Backend::get_last_itow_ms(void) const
91
{
92
if (!_have_itow) {
93
return state.time_week_ms;
94
}
95
return (_pseudo_itow_delta_ms == 0)?(_last_itow_ms):((_pseudo_itow/1000ULL) + _pseudo_itow_delta_ms);
96
}
97
98
/*
99
fill in 3D velocity for a GPS that doesn't give vertical velocity numbers
100
*/
101
void AP_GPS_Backend::fill_3d_velocity(void)
102
{
103
float gps_heading = radians(state.ground_course);
104
105
state.velocity.x = state.ground_speed * cosf(gps_heading);
106
state.velocity.y = state.ground_speed * sinf(gps_heading);
107
state.velocity.z = 0;
108
state.have_vertical_velocity = false;
109
}
110
111
/*
112
fill in 3D velocity for a GPS that doesn't give vertical velocity numbers
113
*/
114
void AP_GPS_Backend::velocity_to_speed_course(AP_GPS::GPS_State &s)
115
{
116
s.ground_course = wrap_360(degrees(atan2f(s.velocity.y, s.velocity.x)));
117
s.ground_speed = s.velocity.xy().length();
118
}
119
120
void
121
AP_GPS_Backend::inject_data(const uint8_t *data, uint16_t len)
122
{
123
// not all backends have valid ports
124
if (port != nullptr) {
125
if (port->txspace() > len) {
126
port->write(data, len);
127
} else {
128
Debug("GPS %d: Not enough TXSPACE", state.instance + 1);
129
}
130
}
131
}
132
133
void AP_GPS_Backend::_detection_message(char *buffer, const uint8_t buflen) const
134
{
135
const uint8_t instance = state.instance;
136
const struct AP_GPS::detect_state dstate = gps.detect_state[instance];
137
138
if (dstate.auto_detected_baud) {
139
hal.util->snprintf(buffer, buflen,
140
"GPS %d: probing for %s at %d baud",
141
instance + 1,
142
name(),
143
int(dstate.probe_baud));
144
} else {
145
hal.util->snprintf(buffer, buflen,
146
"GPS %d: specified as %s",
147
instance + 1,
148
name());
149
}
150
}
151
152
153
void AP_GPS_Backend::broadcast_gps_type() const
154
{
155
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
156
_detection_message(buffer, sizeof(buffer));
157
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s", buffer);
158
}
159
160
#if HAL_LOGGING_ENABLED
161
void AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages() const
162
{
163
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
164
_detection_message(buffer, sizeof(buffer));
165
AP::logger().Write_Message(buffer);
166
}
167
168
bool AP_GPS_Backend::should_log() const
169
{
170
return gps.should_log();
171
}
172
#endif
173
174
175
#if AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED
176
void AP_GPS_Backend::send_mavlink_gps_rtk(mavlink_channel_t chan)
177
{
178
const uint8_t instance = state.instance;
179
// send status
180
switch (instance) {
181
case 0:
182
mavlink_msg_gps_rtk_send(chan,
183
0, // Not implemented yet
184
0, // Not implemented yet
185
state.rtk_week_number,
186
state.rtk_time_week_ms,
187
0, // Not implemented yet
188
0, // Not implemented yet
189
state.rtk_num_sats,
190
state.rtk_baseline_coords_type,
191
state.rtk_baseline_x_mm,
192
state.rtk_baseline_y_mm,
193
state.rtk_baseline_z_mm,
194
state.rtk_accuracy,
195
state.rtk_iar_num_hypotheses);
196
break;
197
case 1:
198
mavlink_msg_gps2_rtk_send(chan,
199
0, // Not implemented yet
200
0, // Not implemented yet
201
state.rtk_week_number,
202
state.rtk_time_week_ms,
203
0, // Not implemented yet
204
0, // Not implemented yet
205
state.rtk_num_sats,
206
state.rtk_baseline_coords_type,
207
state.rtk_baseline_x_mm,
208
state.rtk_baseline_y_mm,
209
state.rtk_baseline_z_mm,
210
state.rtk_accuracy,
211
state.rtk_iar_num_hypotheses);
212
break;
213
}
214
}
215
#endif // AP_GPS_GPS_RTK_SENDING_ENABLED || AP_GPS_GPS2_RTK_SENDING_ENABLED
216
217
218
219
/*
220
set a timestamp based on arrival time on uart at current byte,
221
assuming the message started nbytes ago
222
*/
223
void AP_GPS_Backend::set_uart_timestamp(uint16_t nbytes)
224
{
225
if (port) {
226
state.last_corrected_gps_time_us = port->receive_time_constraint_us(nbytes);
227
state.corrected_timestamp_updated = true;
228
}
229
}
230
231
232
void AP_GPS_Backend::check_new_itow(uint32_t itow, uint32_t msg_length)
233
{
234
if (itow != _last_itow_ms) {
235
_last_itow_ms = itow;
236
_have_itow = true;
237
238
/*
239
we need to calculate a pseudo-itow, which copes with the
240
iTow from the GPS changing in unexpected ways. We assume
241
that timestamps from the GPS are always in multiples of
242
50ms. That means we can't handle a GPS with an update rate
243
of more than 20Hz. We could do more, but we'd need the GPS
244
poll time to be higher
245
*/
246
const uint32_t gps_min_period_ms = 50;
247
248
// get the time the packet arrived on the UART
249
uint64_t uart_us;
250
if (_last_pps_time_us != 0 && (state.status >= AP_GPS::GPS_OK_FIX_2D)) {
251
// pps is only reliable when we have some sort of GPS fix
252
uart_us = _last_pps_time_us;
253
_last_pps_time_us = 0;
254
} else if (port) {
255
uart_us = port->receive_time_constraint_us(msg_length);
256
} else {
257
uart_us = AP_HAL::micros64();
258
}
259
260
uint32_t now = AP_HAL::millis();
261
uint32_t dt_ms = now - _last_ms;
262
_last_ms = now;
263
264
// round to nearest 50ms period
265
dt_ms = ((dt_ms + (gps_min_period_ms/2)) / gps_min_period_ms) * gps_min_period_ms;
266
267
// work out an actual message rate. If we get 5 messages in a
268
// row with a new rate we switch rate
269
if (_last_rate_ms == dt_ms) {
270
if (_rate_counter < 5) {
271
_rate_counter++;
272
} else if (_rate_ms != dt_ms) {
273
_rate_ms = dt_ms;
274
}
275
} else {
276
_rate_counter = 0;
277
_last_rate_ms = dt_ms;
278
if (_rate_ms != 0) {
279
set_pps_desired_freq(1000/_rate_ms);
280
}
281
}
282
if (_rate_ms == 0) {
283
// only allow 5Hz to 20Hz in user config
284
_rate_ms = constrain_int16(gps.get_rate_ms(state.instance), 50, 200);
285
}
286
287
// round to calculated message rate
288
dt_ms = ((dt_ms + (_rate_ms/2)) / _rate_ms) * _rate_ms;
289
290
// calculate pseudo-itow
291
_pseudo_itow += dt_ms * 1000U;
292
293
// use msg arrival time, and correct for jitter
294
uint64_t local_us = jitter_correction.correct_offboard_timestamp_usec(_pseudo_itow, uart_us);
295
state.last_corrected_gps_time_us = local_us;
296
state.corrected_timestamp_updated = true;
297
298
#ifndef HAL_BUILD_AP_PERIPH
299
// look for lagged data from the GPS. This is meant to detect
300
// the case that the GPS is trying to push more data into the
301
// UART than can fit (eg. with GPS_RAW_DATA at 115200).
302
// This is disabled on AP_Periph as it is better to catch missed packet rate at the flight
303
// controller level
304
float expected_lag;
305
if (gps.get_lag(state.instance, expected_lag)) {
306
float lag_s = (now - (state.last_corrected_gps_time_us/1000U)) * 0.001;
307
if (lag_s > expected_lag+0.05) {
308
// more than 50ms over expected lag, increment lag counter
309
state.lagged_sample_count++;
310
} else {
311
state.lagged_sample_count = 0;
312
}
313
}
314
#endif // HAL_BUILD_AP_PERIPH
315
316
if (state.status >= AP_GPS::GPS_OK_FIX_2D) {
317
// we must have a decent fix to calculate difference between itow and pseudo-itow
318
_pseudo_itow_delta_ms = itow - (_pseudo_itow/1000ULL);
319
}
320
}
321
}
322
323
#if GPS_MOVING_BASELINE
324
bool AP_GPS_Backend::calculate_moving_base_yaw(float reported_heading_deg, const float reported_distance, const float reported_D) {
325
return calculate_moving_base_yaw(state, reported_heading_deg, reported_distance, reported_D);
326
}
327
328
bool AP_GPS_Backend::calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state, const float reported_heading_deg, const float reported_distance, const float reported_D) {
329
constexpr float minimum_antenna_seperation = 0.05; // meters
330
constexpr float permitted_error_length_pct = 0.2; // percentage
331
#if HAL_LOGGING_ENABLED || AP_AHRS_ENABLED
332
float min_D = 0.0f;
333
float max_D = 0.0f;
334
#endif
335
bool selectedOffset = false;
336
Vector3f offset;
337
switch (MovingBase::Type(gps.params[interim_state.instance].mb_params.type)) {
338
case MovingBase::Type::RelativeToAlternateInstance:
339
offset = gps.params[interim_state.instance^1].antenna_offset.get() - gps.params[interim_state.instance].antenna_offset.get();
340
selectedOffset = true;
341
break;
342
case MovingBase::Type::RelativeToCustomBase:
343
offset = gps.params[interim_state.instance].mb_params.base_offset.get();
344
selectedOffset = true;
345
break;
346
}
347
348
if (!selectedOffset) {
349
// invalid type, let's throw up a flag
350
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
351
goto bad_yaw;
352
}
353
354
{
355
const float offset_dist = offset.length();
356
const float min_dist = MIN(offset_dist, reported_distance);
357
358
if (offset_dist < minimum_antenna_seperation) {
359
// offsets have to be sufficiently large to get a meaningful angle off of them
360
Debug("Insufficent antenna offset (%f, %f, %f)", (double)offset.x, (double)offset.y, (double)offset.z);
361
goto bad_yaw;
362
}
363
364
if (reported_distance < minimum_antenna_seperation) {
365
// if the reported distance is less then the minimum separation it's not sufficiently robust
366
Debug("Reported baseline distance (%f) was less then the minimum antenna separation (%f)",
367
(double)reported_distance, (double)minimum_antenna_seperation);
368
goto bad_yaw;
369
}
370
371
372
if (fabsf(offset_dist - reported_distance) > (min_dist * permitted_error_length_pct)) {
373
// the magnitude of the vector is much further then we were expecting
374
Debug("Offset=%.2f vs reported-distance=%.2f (max-delta=%.2f)",
375
offset_dist, reported_distance, (double)(min_dist * permitted_error_length_pct));
376
goto bad_yaw;
377
}
378
379
#if AP_AHRS_ENABLED
380
{
381
// get vehicle rotation, projected back in time using the gyro
382
// this is not 100% accurate, but it is good enough for
383
// this test. To do it completely accurately we'd need an
384
// interface into DCM, EKF2 and EKF3 to ask for a
385
// historical attitude. That is far too complex to justify
386
// for this use case
387
const auto &ahrs = AP::ahrs();
388
const Vector3f &gyro = ahrs.get_gyro();
389
Matrix3f rot_body_to_ned_min_lag = ahrs.get_rotation_body_to_ned();
390
rot_body_to_ned_min_lag.rotate(gyro * -AP_GPS_MB_MIN_LAG);
391
Matrix3f rot_body_to_ned_max_lag = ahrs.get_rotation_body_to_ned();
392
rot_body_to_ned_max_lag.rotate(gyro * -AP_GPS_MB_MAX_LAG);
393
394
// apply rotation to the offset to get the Z offset in NED
395
const Vector3f antenna_tilt_min_lag = rot_body_to_ned_min_lag * offset;
396
const Vector3f antenna_tilt_max_lag = rot_body_to_ned_max_lag * offset;
397
min_D = MIN(-antenna_tilt_min_lag.z, -antenna_tilt_max_lag.z);
398
max_D = MAX(-antenna_tilt_min_lag.z, -antenna_tilt_max_lag.z);
399
min_D -= permitted_error_length_pct * min_dist;
400
max_D += permitted_error_length_pct * min_dist;
401
if (reported_D < min_D || reported_D > max_D) {
402
// the vertical component is out of range, reject it
403
Debug("bad alt_err %f < %f < %f", (double)min_D, (double)reported_D, (double)max_D);
404
goto bad_yaw;
405
}
406
}
407
#endif // AP_AHRS_ENABLED
408
409
{
410
// at this point the offsets are looking okay, go ahead and actually calculate a useful heading
411
const float rotation_offset_rad = Vector2f(-offset.x, -offset.y).angle();
412
interim_state.gps_yaw = wrap_360(reported_heading_deg - degrees(rotation_offset_rad));
413
interim_state.have_gps_yaw = true;
414
interim_state.gps_yaw_time_ms = AP_HAL::millis();
415
}
416
goto good_yaw;
417
}
418
419
bad_yaw:
420
interim_state.have_gps_yaw = false;
421
422
good_yaw:
423
424
#if HAL_LOGGING_ENABLED
425
// this log message helps diagnose GPS yaw issues
426
// @LoggerMessage: GPYW
427
// @Description: GPS Yaw
428
// @Field: TimeUS: Time since system startup
429
// @Field: Id: instance
430
// @Field: RHD: reported heading,deg
431
// @Field: RDist: antenna separation,m
432
// @Field: RDown: vertical antenna separation,m
433
// @Field: MinCDown: minimum tolerable vertical antenna separation,m
434
// @Field: MaxCDown: maximum tolerable vertical antenna separation,m
435
// @Field: OK: 1 if have yaw
436
AP::logger().WriteStreaming("GPYW", "TimeUS,Id,RHD,RDist,RDown,MinCDown,MaxCDown,OK",
437
"s#dmmmm-",
438
"F-------",
439
"QBfffffB",
440
AP_HAL::micros64(),
441
state.instance,
442
reported_heading_deg,
443
reported_distance,
444
reported_D,
445
min_D,
446
max_D,
447
interim_state.have_gps_yaw);
448
#endif
449
450
return interim_state.have_gps_yaw;
451
}
452
#endif // GPS_MOVING_BASELINE
453
454
/*
455
set altitude in location structure, honouring the driver option for
456
MSL vs ellipsoid height
457
*/
458
void AP_GPS_Backend::set_alt_amsl_cm(AP_GPS::GPS_State &_state, int32_t alt_amsl_cm)
459
{
460
if (option_set(AP_GPS::HeightEllipsoid) && _state.have_undulation) {
461
// user has asked ArduPilot to use ellipsoid height in the
462
// canonical height for mission and navigation
463
_state.location.alt = alt_amsl_cm - _state.undulation*100;
464
} else {
465
_state.location.alt = alt_amsl_cm;
466
}
467
}
468
469
#if AP_GPS_DEBUG_LOGGING_ENABLED
470
471
/*
472
log some data for debugging
473
474
the logging format matches that used by SITL with SIM_GPS_TYPE=7,
475
allowing for development of GPS drivers based on logged data
476
*/
477
void AP_GPS_Backend::log_data(const uint8_t *data, uint16_t length)
478
{
479
if (state.instance < 2) {
480
logging[state.instance].buf.write(data, length);
481
}
482
if (!log_thread_created) {
483
log_thread_created = true;
484
hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_GPS_Backend::logging_start, void), "gps_log", 4096, AP_HAL::Scheduler::PRIORITY_IO, 0);
485
}
486
}
487
488
AP_GPS_Backend::loginfo AP_GPS_Backend::logging[2];
489
bool AP_GPS_Backend::log_thread_created;
490
491
// logging loop, needs to be static to allow for re-alloc of GPS backends
492
void AP_GPS_Backend::logging_loop(void)
493
{
494
while (true) {
495
hal.scheduler->delay(10);
496
static uint16_t lognum;
497
for (uint8_t instance=0; instance<2; instance++) {
498
if (logging[instance].fd == -1 && logging[instance].buf.available()) {
499
char fname[] = "gpsN_XXX.log";
500
fname[3] = '1' + instance;
501
if (lognum == 0) {
502
for (lognum=1; lognum<1000; lognum++) {
503
struct stat st;
504
hal.util->snprintf(&fname[5], 8, "%03u.log", lognum);
505
if (AP::FS().stat(fname, &st) != 0) {
506
break;
507
}
508
}
509
}
510
hal.util->snprintf(&fname[5], 8, "%03u.log", lognum);
511
logging[instance].fd = AP::FS().open(fname, O_WRONLY|O_CREAT|O_APPEND);
512
}
513
if (logging[instance].fd != -1) {
514
uint32_t n = 0;
515
const uint8_t *p;
516
while ((p = logging[instance].buf.readptr(n)) != nullptr && n != 0) {
517
struct {
518
uint32_t magic = 0x7fe53b04U;
519
uint32_t time_ms;
520
uint32_t n;
521
} header;
522
header.n = n;
523
header.time_ms = AP_HAL::millis();
524
// short writes are unlikely and are ignored (only FS full errors)
525
AP::FS().write(logging[instance].fd, (const uint8_t *)&header, sizeof(header));
526
AP::FS().write(logging[instance].fd, p, n);
527
logging[instance].buf.advance(n);
528
AP::FS().fsync(logging[instance].fd);
529
}
530
}
531
}
532
}
533
}
534
535
// logging thread start, needs to be non-static for thread_create
536
void AP_GPS_Backend::logging_start(void)
537
{
538
logging_loop();
539
}
540
#endif // AP_GPS_DEBUG_LOGGING_ENABLED
541
542
#endif // AP_GPS_ENABLED
543
544