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_DroneCAN.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
// UAVCAN GPS driver
18
//
19
#include "AP_GPS_config.h"
20
21
#if AP_GPS_DRONECAN_ENABLED
22
23
#include <AP_HAL/AP_HAL.h>
24
25
#include "AP_GPS_DroneCAN.h"
26
27
#include <AP_CANManager/AP_CANManager.h>
28
#include <AP_DroneCAN/AP_DroneCAN.h>
29
#include <GCS_MAVLink/GCS.h>
30
31
#include <AP_Logger/AP_Logger.h>
32
33
#include <stdio.h>
34
#include <AP_BoardConfig/AP_BoardConfig.h>
35
36
#define GPS_PPS_EMULATION 0
37
38
extern const AP_HAL::HAL& hal;
39
40
#define GPS_UAVCAN_DEBUGGING 0
41
42
#if GPS_UAVCAN_DEBUGGING
43
#if defined(HAL_BUILD_AP_PERIPH)
44
extern "C" {
45
void can_printf(const char *fmt, ...);
46
}
47
# define Debug(fmt, args ...) do {can_printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args);} while(0)
48
#else
49
# define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
50
#endif
51
#else
52
# define Debug(fmt, args ...)
53
#endif
54
55
#define LOG_TAG "GPS"
56
57
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
58
#define NATIVE_TIME_OFFSET (AP_HAL::micros64() - AP_HAL::micros64())
59
#else
60
#define NATIVE_TIME_OFFSET 0
61
#endif
62
AP_GPS_DroneCAN::DetectedModules AP_GPS_DroneCAN::_detected_modules[];
63
HAL_Semaphore AP_GPS_DroneCAN::_sem_registry;
64
65
// Member Methods
66
AP_GPS_DroneCAN::AP_GPS_DroneCAN(AP_GPS &_gps,
67
AP_GPS::Params &_params,
68
AP_GPS::GPS_State &_state,
69
AP_GPS::GPS_Role _role) :
70
AP_GPS_Backend(_gps, _params, _state, nullptr),
71
interim_state(_state),
72
role(_role)
73
{
74
param_int_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_DroneCAN::handle_param_get_set_response_int, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &);
75
param_float_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_DroneCAN::handle_param_get_set_response_float, bool, AP_DroneCAN*, const uint8_t, const char*, float &);
76
param_save_cb = FUNCTOR_BIND_MEMBER(&AP_GPS_DroneCAN::handle_param_save_response, void, AP_DroneCAN*, const uint8_t, bool);
77
}
78
79
AP_GPS_DroneCAN::~AP_GPS_DroneCAN()
80
{
81
WITH_SEMAPHORE(_sem_registry);
82
83
_detected_modules[_detected_module].driver = nullptr;
84
85
#if GPS_MOVING_BASELINE
86
if (rtcm3_parser != nullptr) {
87
delete rtcm3_parser;
88
}
89
#endif
90
}
91
92
bool AP_GPS_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan)
93
{
94
const auto driver_index = ap_dronecan->get_driver_index();
95
96
return (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_fix2_msg_trampoline, driver_index) != nullptr)
97
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_aux_msg_trampoline, driver_index) != nullptr)
98
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_heading_msg_trampoline, driver_index) != nullptr)
99
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_status_msg_trampoline, driver_index) != nullptr)
100
#if GPS_MOVING_BASELINE
101
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_moving_baseline_msg_trampoline, driver_index) != nullptr)
102
&& (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_relposheading_msg_trampoline, driver_index) != nullptr)
103
#endif
104
;
105
}
106
107
AP_GPS_Backend* AP_GPS_DroneCAN::probe(AP_GPS &_gps, AP_GPS::GPS_State &_state)
108
{
109
WITH_SEMAPHORE(_sem_registry);
110
int8_t found_match = -1, last_match = -1;
111
AP_GPS_DroneCAN* backend = nullptr;
112
bool bad_override_config = false;
113
for (int8_t i = GPS_MAX_RECEIVERS - 1; i >= 0; i--) {
114
if (_detected_modules[i].driver == nullptr && _detected_modules[i].ap_dronecan != nullptr) {
115
if (_gps.params[_state.instance].override_node_id != 0 &&
116
_gps.params[_state.instance].override_node_id != _detected_modules[i].node_id) {
117
continue; // This device doesn't match the correct node
118
}
119
last_match = found_match;
120
for (uint8_t j = 0; j < GPS_MAX_RECEIVERS; j++) {
121
if (_detected_modules[i].node_id == _gps.params[j].override_node_id &&
122
(j != _state.instance)) {
123
//wrong instance
124
found_match = -1;
125
break;
126
}
127
found_match = i;
128
}
129
130
// Handle Duplicate overrides
131
for (uint8_t j = 0; j < GPS_MAX_RECEIVERS; j++) {
132
if (_gps.params[i].override_node_id != 0 && (i != j) &&
133
_gps.params[i].override_node_id == _gps.params[j].override_node_id) {
134
bad_override_config = true;
135
}
136
}
137
if (bad_override_config) {
138
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Same Node Id %lu set for multiple GPS", (unsigned long int)_gps.params[i].override_node_id.get());
139
last_match = i;
140
}
141
142
if (found_match == -1) {
143
found_match = last_match;
144
continue;
145
}
146
break;
147
}
148
}
149
150
if (found_match == -1) {
151
return NULL;
152
}
153
// initialise the backend based on the UAVCAN Moving baseline selection
154
switch (_gps.get_type(_state.instance)) {
155
case AP_GPS::GPS_TYPE_UAVCAN:
156
backend = NEW_NOTHROW AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_NORMAL);
157
break;
158
#if GPS_MOVING_BASELINE
159
case AP_GPS::GPS_TYPE_UAVCAN_RTK_BASE:
160
backend = NEW_NOTHROW AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_MB_BASE);
161
break;
162
case AP_GPS::GPS_TYPE_UAVCAN_RTK_ROVER:
163
backend = NEW_NOTHROW AP_GPS_DroneCAN(_gps, _gps.params[_state.instance], _state, AP_GPS::GPS_ROLE_MB_ROVER);
164
break;
165
#endif
166
default:
167
return NULL;
168
}
169
if (backend == nullptr) {
170
AP::can().log_text(AP_CANManager::LOG_ERROR,
171
LOG_TAG,
172
"Failed to register DroneCAN GPS Node %d on Bus %d\n",
173
_detected_modules[found_match].node_id,
174
_detected_modules[found_match].ap_dronecan->get_driver_index());
175
} else {
176
_detected_modules[found_match].driver = backend;
177
backend->_detected_module = found_match;
178
AP::can().log_text(AP_CANManager::LOG_INFO,
179
LOG_TAG,
180
"Registered DroneCAN GPS Node %d on Bus %d as instance %d\n",
181
_detected_modules[found_match].node_id,
182
_detected_modules[found_match].ap_dronecan->get_driver_index(),
183
_state.instance);
184
snprintf(backend->_name, ARRAY_SIZE(backend->_name), "DroneCAN%u-%u", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id);
185
_detected_modules[found_match].instance = _state.instance;
186
for (uint8_t i=0; i < GPS_MAX_RECEIVERS; i++) {
187
if (_detected_modules[found_match].node_id == AP::gps().params[i].node_id) {
188
if (i == _state.instance) {
189
// Nothing to do here
190
break;
191
}
192
// else swap
193
uint8_t tmp = AP::gps().params[_state.instance].node_id.get();
194
AP::gps().params[_state.instance].node_id.set_and_notify(_detected_modules[found_match].node_id);
195
AP::gps().params[i].node_id.set_and_notify(tmp);
196
}
197
}
198
#if GPS_MOVING_BASELINE
199
if (backend->role == AP_GPS::GPS_ROLE_MB_BASE) {
200
backend->rtcm3_parser = NEW_NOTHROW RTCM3_Parser;
201
if (backend->rtcm3_parser == nullptr) {
202
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DroneCAN%u-%u: failed RTCMv3 parser allocation", _detected_modules[found_match].ap_dronecan->get_driver_index()+1, _detected_modules[found_match].node_id);
203
}
204
}
205
#endif // GPS_MOVING_BASELINE
206
}
207
208
return backend;
209
}
210
211
bool AP_GPS_DroneCAN::inter_instance_pre_arm_checks(char failure_msg[], uint16_t failure_msg_len)
212
{
213
// lint parameters and detected node IDs:
214
for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
215
const auto &params_i = AP::gps().params[i];
216
// we are only interested in parameters for DroneCAN GPSs:
217
if (!is_dronecan_gps_type(params_i.type)) {
218
continue;
219
}
220
bool overriden_node_found = false;
221
bool bad_override_config = false;
222
if (params_i.override_node_id == 0) {
223
//anything goes
224
continue;
225
}
226
for (uint8_t j = 0; j < GPS_MAX_RECEIVERS; j++) {
227
const auto &params_j = AP::gps().params[j];
228
// we are only interested in parameters for DroneCAN GPSs:
229
if (!is_dronecan_gps_type(params_j.type)) {
230
continue;
231
}
232
if (params_i.override_node_id == params_j.override_node_id && (i != j)) {
233
bad_override_config = true;
234
break;
235
}
236
if (i == _detected_modules[j].instance && _detected_modules[j].driver) {
237
if (params_i.override_node_id == _detected_modules[j].node_id) {
238
overriden_node_found = true;
239
break;
240
}
241
}
242
}
243
if (bad_override_config) {
244
snprintf(failure_msg, failure_msg_len, "Same Node Id %lu set for multiple GPS", (unsigned long int)params_i.override_node_id.get());
245
return false;
246
}
247
248
if (!overriden_node_found) {
249
snprintf(failure_msg, failure_msg_len, "Selected GPS Node %lu not set as instance %d", (unsigned long int)params_i.override_node_id.get(), i + 1);
250
return false;
251
}
252
}
253
254
return true;
255
}
256
257
AP_GPS_DroneCAN* AP_GPS_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id)
258
{
259
if (ap_dronecan == nullptr) {
260
return nullptr;
261
}
262
263
for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
264
if (_detected_modules[i].driver != nullptr &&
265
_detected_modules[i].ap_dronecan == ap_dronecan &&
266
_detected_modules[i].node_id == node_id) {
267
return _detected_modules[i].driver;
268
}
269
}
270
271
bool already_detected = false;
272
// Check if there's an empty spot for possible registeration
273
for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
274
if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) {
275
// Already Detected
276
already_detected = true;
277
break;
278
}
279
}
280
if (!already_detected) {
281
for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) {
282
if (_detected_modules[i].ap_dronecan == nullptr) {
283
_detected_modules[i].ap_dronecan = ap_dronecan;
284
_detected_modules[i].node_id = node_id;
285
// Just set the Node ID in order of appearance
286
// This will be used to set select ids
287
AP::gps().params[i].node_id.set_and_notify(node_id);
288
break;
289
}
290
}
291
}
292
struct DetectedModules tempslot;
293
// Sort based on the node_id, larger values first
294
// we do this, so that we have repeatable GPS
295
// registration
296
for (uint8_t i = 1; i < GPS_MAX_RECEIVERS; i++) {
297
for (uint8_t j = i; j > 0; j--) {
298
if (_detected_modules[j].node_id > _detected_modules[j-1].node_id) {
299
tempslot = _detected_modules[j];
300
_detected_modules[j] = _detected_modules[j-1];
301
_detected_modules[j-1] = tempslot;
302
// also fix the _detected_module in the driver so that RTCM injection
303
// can determine if it has the bus to itself
304
if (_detected_modules[j].driver) {
305
_detected_modules[j].driver->_detected_module = j;
306
}
307
if (_detected_modules[j-1].driver) {
308
_detected_modules[j-1].driver->_detected_module = j-1;
309
}
310
}
311
}
312
}
313
return nullptr;
314
}
315
316
/*
317
handle velocity element of message
318
*/
319
void AP_GPS_DroneCAN::handle_velocity(const float vx, const float vy, const float vz)
320
{
321
if (!isnan(vx)) {
322
const Vector3f vel(vx, vy, vz);
323
interim_state.velocity = vel;
324
velocity_to_speed_course(interim_state);
325
// assume we have vertical velocity if we ever get a non-zero Z velocity
326
if (!isnan(vel.z) && !is_zero(vel.z)) {
327
interim_state.have_vertical_velocity = true;
328
} else {
329
interim_state.have_vertical_velocity = state.have_vertical_velocity;
330
}
331
} else {
332
interim_state.have_vertical_velocity = false;
333
}
334
}
335
336
void AP_GPS_DroneCAN::handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uint64_t timestamp_usec)
337
{
338
bool process = false;
339
seen_fix2 = true;
340
341
WITH_SEMAPHORE(sem);
342
343
if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_NO_FIX) {
344
interim_state.status = AP_GPS::GPS_Status::NO_FIX;
345
} else {
346
if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_TIME_ONLY) {
347
interim_state.status = AP_GPS::GPS_Status::NO_FIX;
348
} else if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_2D_FIX) {
349
interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_2D;
350
process = true;
351
} else if (msg.status == UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX) {
352
interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D;
353
process = true;
354
}
355
356
if (msg.gnss_time_standard == UAVCAN_EQUIPMENT_GNSS_FIX2_GNSS_TIME_STANDARD_UTC) {
357
uint64_t epoch_ms = msg.gnss_timestamp.usec;
358
if (epoch_ms != 0) {
359
epoch_ms /= 1000;
360
uint64_t gps_ms = epoch_ms - UNIX_OFFSET_MSEC;
361
interim_state.time_week = (uint16_t)(gps_ms / AP_MSEC_PER_WEEK);
362
interim_state.time_week_ms = (uint32_t)(gps_ms - (interim_state.time_week) * AP_MSEC_PER_WEEK);
363
}
364
}
365
366
if (interim_state.status == AP_GPS::GPS_Status::GPS_OK_FIX_3D) {
367
if (msg.mode == UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_DGPS) {
368
interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS;
369
} else if (msg.mode == UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_RTK) {
370
if (msg.sub_mode == UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FLOAT) {
371
interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT;
372
} else if (msg.sub_mode == UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FIXED) {
373
interim_state.status = AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED;
374
}
375
}
376
}
377
}
378
379
if (process) {
380
Location loc = { };
381
loc.lat = msg.latitude_deg_1e8 / 10;
382
loc.lng = msg.longitude_deg_1e8 / 10;
383
const int32_t alt_amsl_cm = msg.height_msl_mm / 10;
384
interim_state.have_undulation = true;
385
interim_state.undulation = (msg.height_msl_mm - msg.height_ellipsoid_mm) * 0.001;
386
interim_state.location = loc;
387
set_alt_amsl_cm(interim_state, alt_amsl_cm);
388
389
handle_velocity(msg.ned_velocity[0], msg.ned_velocity[1], msg.ned_velocity[2]);
390
391
if (msg.covariance.len == 6) {
392
if (!isnan(msg.covariance.data[0])) {
393
interim_state.horizontal_accuracy = sqrtf(msg.covariance.data[0]);
394
interim_state.have_horizontal_accuracy = true;
395
} else {
396
interim_state.have_horizontal_accuracy = false;
397
}
398
if (!isnan(msg.covariance.data[2])) {
399
interim_state.vertical_accuracy = sqrtf(msg.covariance.data[2]);
400
interim_state.have_vertical_accuracy = true;
401
} else {
402
interim_state.have_vertical_accuracy = false;
403
}
404
if (!isnan(msg.covariance.data[3]) &&
405
!isnan(msg.covariance.data[4]) &&
406
!isnan(msg.covariance.data[5])) {
407
interim_state.speed_accuracy = sqrtf((msg.covariance.data[3] + msg.covariance.data[4] + msg.covariance.data[5])/3);
408
interim_state.have_speed_accuracy = true;
409
} else {
410
interim_state.have_speed_accuracy = false;
411
}
412
}
413
414
interim_state.num_sats = msg.sats_used;
415
} else {
416
interim_state.have_vertical_velocity = false;
417
interim_state.have_vertical_accuracy = false;
418
interim_state.have_horizontal_accuracy = false;
419
interim_state.have_speed_accuracy = false;
420
interim_state.num_sats = 0;
421
}
422
423
if (!seen_aux) {
424
// if we haven't seen an Aux message then populate vdop and
425
// hdop from pdop. Some GPS modules don't provide the Aux message
426
interim_state.hdop = interim_state.vdop = msg.pdop * 100.0;
427
}
428
429
if ((msg.timestamp.usec > msg.gnss_timestamp.usec) && (msg.gnss_timestamp.usec > 0)) {
430
// we have a valid timestamp based on gnss_timestamp timescale, we can use that to correct our gps message time
431
interim_state.last_corrected_gps_time_us = jitter_correction.correct_offboard_timestamp_usec(msg.timestamp.usec, (timestamp_usec + NATIVE_TIME_OFFSET));
432
interim_state.last_gps_time_ms = interim_state.last_corrected_gps_time_us/1000U;
433
interim_state.last_corrected_gps_time_us -= msg.timestamp.usec - msg.gnss_timestamp.usec;
434
// this is also the time the message was received on the UART on other end.
435
interim_state.corrected_timestamp_updated = true;
436
} else {
437
interim_state.last_gps_time_ms = jitter_correction.correct_offboard_timestamp_usec(msg.timestamp.usec, timestamp_usec + NATIVE_TIME_OFFSET)/1000U;
438
}
439
440
#if GPS_PPS_EMULATION
441
// Emulates a PPS signal, can be used to check how close are we to real GPS time
442
static virtual_timer_t timeout_vt;
443
hal.gpio->pinMode(51, 1);
444
auto handle_timeout = [](void *arg)
445
{
446
(void)arg;
447
//we are called from ISR context
448
chSysLockFromISR();
449
hal.gpio->toggle(51);
450
chSysUnlockFromISR();
451
};
452
453
static uint64_t next_toggle, last_toggle;
454
455
next_toggle = (msg.timestamp.usec) + (1000000ULL - ((msg.timestamp.usec) % 1000000ULL));
456
457
next_toggle += jitter_correction.get_link_offset_usec();
458
if (next_toggle != last_toggle) {
459
chVTSet(&timeout_vt, chTimeUS2I(next_toggle - AP_HAL::micros64()), handle_timeout, nullptr);
460
last_toggle = next_toggle;
461
}
462
#endif
463
464
_new_data = true;
465
if (!seen_message) {
466
if (interim_state.status == AP_GPS::GPS_Status::NO_GPS) {
467
// the first time we see a fix message we change from
468
// NO_GPS to NO_FIX, indicating to user that a DroneCAN GPS
469
// has been seen
470
interim_state.status = AP_GPS::GPS_Status::NO_FIX;
471
}
472
seen_message = true;
473
}
474
}
475
476
void AP_GPS_DroneCAN::handle_aux_msg(const uavcan_equipment_gnss_Auxiliary& msg)
477
{
478
WITH_SEMAPHORE(sem);
479
480
if (!isnan(msg.hdop)) {
481
seen_aux = true;
482
interim_state.hdop = msg.hdop * 100.0;
483
}
484
485
if (!isnan(msg.vdop)) {
486
seen_aux = true;
487
interim_state.vdop = msg.vdop * 100.0;
488
}
489
}
490
491
void AP_GPS_DroneCAN::handle_heading_msg(const ardupilot_gnss_Heading& msg)
492
{
493
#if GPS_MOVING_BASELINE
494
if (seen_relposheading && gps.params[interim_state.instance].mb_params.type.get() != 0) {
495
// we prefer to use the relposheading to get yaw as it allows
496
// the user to more easily control the relative antenna positions
497
return;
498
}
499
#endif
500
501
WITH_SEMAPHORE(sem);
502
503
if (interim_state.gps_yaw_configured == false) {
504
interim_state.gps_yaw_configured = msg.heading_valid;
505
}
506
507
interim_state.have_gps_yaw = msg.heading_valid;
508
interim_state.gps_yaw = degrees(msg.heading_rad);
509
if (interim_state.have_gps_yaw) {
510
interim_state.gps_yaw_time_ms = AP_HAL::millis();
511
}
512
513
interim_state.have_gps_yaw_accuracy = msg.heading_accuracy_valid;
514
interim_state.gps_yaw_accuracy = degrees(msg.heading_accuracy_rad);
515
}
516
517
void AP_GPS_DroneCAN::handle_status_msg(const ardupilot_gnss_Status& msg)
518
{
519
WITH_SEMAPHORE(sem);
520
521
seen_status = true;
522
523
healthy = msg.healthy;
524
status_flags = msg.status;
525
if (error_code != msg.error_codes) {
526
#if HAL_LOGGING_ENABLED
527
AP::logger().Write_MessageF("GPS %d: error changed (0x%08x/0x%08x)",
528
(unsigned int)(state.instance + 1),
529
error_code,
530
msg.error_codes);
531
#endif
532
error_code = msg.error_codes;
533
}
534
}
535
536
#if GPS_MOVING_BASELINE
537
/*
538
handle moving baseline data.
539
*/
540
void AP_GPS_DroneCAN::handle_moving_baseline_msg(const ardupilot_gnss_MovingBaselineData& msg, uint8_t node_id)
541
{
542
WITH_SEMAPHORE(sem);
543
if (role != AP_GPS::GPS_ROLE_MB_BASE) {
544
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Incorrect Role set for DroneCAN GPS, %d should be Base", node_id);
545
return;
546
}
547
548
if (rtcm3_parser == nullptr) {
549
return;
550
}
551
for (int i=0; i < msg.data.len; i++) {
552
rtcm3_parser->read(msg.data.data[i]);
553
}
554
}
555
556
/*
557
handle relposheading message
558
*/
559
void AP_GPS_DroneCAN::handle_relposheading_msg(const ardupilot_gnss_RelPosHeading& msg, uint8_t node_id)
560
{
561
WITH_SEMAPHORE(sem);
562
563
interim_state.gps_yaw_configured = true;
564
seen_relposheading = true;
565
// push raw heading data to calculate moving baseline heading states
566
if (calculate_moving_base_yaw(interim_state,
567
msg.reported_heading_deg,
568
msg.relative_distance_m,
569
msg.relative_down_pos_m)) {
570
if (msg.reported_heading_acc_available) {
571
interim_state.gps_yaw_accuracy = msg.reported_heading_acc_deg;
572
}
573
interim_state.have_gps_yaw_accuracy = msg.reported_heading_acc_available;
574
}
575
}
576
577
// support for retrieving RTCMv3 data from a moving baseline base
578
bool AP_GPS_DroneCAN::get_RTCMV3(const uint8_t *&bytes, uint16_t &len)
579
{
580
WITH_SEMAPHORE(sem);
581
if (rtcm3_parser != nullptr) {
582
len = rtcm3_parser->get_len(bytes);
583
return len > 0;
584
}
585
return false;
586
}
587
588
// clear previous RTCM3 packet
589
void AP_GPS_DroneCAN::clear_RTCMV3(void)
590
{
591
WITH_SEMAPHORE(sem);
592
if (rtcm3_parser != nullptr) {
593
rtcm3_parser->clear_packet();
594
}
595
}
596
597
#endif // GPS_MOVING_BASELINE
598
599
void AP_GPS_DroneCAN::handle_fix2_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Fix2& msg)
600
{
601
WITH_SEMAPHORE(_sem_registry);
602
603
AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id);
604
if (driver != nullptr) {
605
driver->handle_fix2_msg(msg, transfer.timestamp_usec);
606
}
607
}
608
609
void AP_GPS_DroneCAN::handle_aux_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_gnss_Auxiliary& msg)
610
{
611
WITH_SEMAPHORE(_sem_registry);
612
613
AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id);
614
if (driver != nullptr) {
615
driver->handle_aux_msg(msg);
616
}
617
}
618
619
void AP_GPS_DroneCAN::handle_heading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Heading& msg)
620
{
621
WITH_SEMAPHORE(_sem_registry);
622
623
AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id);
624
if (driver != nullptr) {
625
driver->handle_heading_msg(msg);
626
}
627
}
628
629
void AP_GPS_DroneCAN::handle_status_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_Status& msg)
630
{
631
WITH_SEMAPHORE(_sem_registry);
632
633
AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id);
634
if (driver != nullptr) {
635
driver->handle_status_msg(msg);
636
}
637
}
638
639
#if GPS_MOVING_BASELINE
640
// Moving Baseline msg trampoline
641
void AP_GPS_DroneCAN::handle_moving_baseline_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_MovingBaselineData& msg)
642
{
643
WITH_SEMAPHORE(_sem_registry);
644
AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id);
645
if (driver != nullptr) {
646
driver->handle_moving_baseline_msg(msg, transfer.source_node_id);
647
}
648
}
649
650
// RelPosHeading msg trampoline
651
void AP_GPS_DroneCAN::handle_relposheading_msg_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_gnss_RelPosHeading& msg)
652
{
653
WITH_SEMAPHORE(_sem_registry);
654
AP_GPS_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id);
655
if (driver != nullptr) {
656
driver->handle_relposheading_msg(msg, transfer.source_node_id);
657
}
658
}
659
#endif
660
661
bool AP_GPS_DroneCAN::do_config()
662
{
663
AP_DroneCAN *ap_dronecan = _detected_modules[_detected_module].ap_dronecan;
664
if (ap_dronecan == nullptr) {
665
return false;
666
}
667
uint8_t node_id = _detected_modules[_detected_module].node_id;
668
669
switch(cfg_step) {
670
case STEP_SET_TYPE:
671
// GPS_TYPE was renamed GPS1_TYPE. Request both and
672
// handle whichever we receive.
673
ap_dronecan->get_parameter_on_node(node_id, "GPS_TYPE", &param_int_cb);
674
ap_dronecan->get_parameter_on_node(node_id, "GPS1_TYPE", &param_int_cb);
675
break;
676
case STEP_SET_MB_CAN_TX:
677
if (role != AP_GPS::GPS_Role::GPS_ROLE_NORMAL) {
678
ap_dronecan->get_parameter_on_node(node_id, "GPS_MB_ONLY_PORT", &param_int_cb);
679
} else {
680
cfg_step++;
681
}
682
break;
683
case STEP_SAVE_AND_REBOOT:
684
if (requires_save_and_reboot) {
685
ap_dronecan->save_parameters_on_node(node_id, &param_save_cb);
686
} else {
687
cfg_step++;
688
}
689
break;
690
case STEP_FINISHED:
691
return true;
692
default:
693
break;
694
}
695
return false;
696
}
697
698
// Consume new data and mark it received
699
bool AP_GPS_DroneCAN::read(void)
700
{
701
if (gps._auto_config >= AP_GPS::GPS_AUTO_CONFIG_ENABLE_ALL) {
702
if (!do_config()) {
703
return false;
704
}
705
}
706
707
WITH_SEMAPHORE(sem);
708
709
send_rtcm();
710
711
if (_new_data) {
712
_new_data = false;
713
714
// the encoding of accuracies in DroneCAN can result in infinite
715
// values. These cause problems with blending. Use 1000m and 1000m/s instead
716
interim_state.horizontal_accuracy = MIN(interim_state.horizontal_accuracy, 1000.0);
717
interim_state.vertical_accuracy = MIN(interim_state.vertical_accuracy, 1000.0);
718
interim_state.speed_accuracy = MIN(interim_state.speed_accuracy, 1000.0);
719
720
// prevent announcing multiple times
721
interim_state.announced_detection = state.announced_detection;
722
723
state = interim_state;
724
if (interim_state.last_corrected_gps_time_us) {
725
// If we were able to get a valid last_corrected_gps_time_us
726
// we have had a valid GPS message time, from which we calculate
727
// the time of week.
728
_last_itow_ms = interim_state.time_week_ms;
729
_have_itow = true;
730
}
731
return true;
732
}
733
if (!seen_message) {
734
// start with NO_GPS until we get first packet
735
state.status = AP_GPS::GPS_Status::NO_GPS;
736
}
737
738
return false;
739
}
740
741
bool AP_GPS_DroneCAN::is_healthy(void) const
742
{
743
// if we don't have any health reports, assume it's healthy
744
if (!seen_status) {
745
return true;
746
}
747
return healthy;
748
}
749
750
bool AP_GPS_DroneCAN::logging_healthy(void) const
751
{
752
// if we don't have status, assume it's valid
753
if (!seen_status) {
754
return true;
755
}
756
757
return (status_flags & ARDUPILOT_GNSS_STATUS_STATUS_LOGGING) != 0;
758
}
759
760
bool AP_GPS_DroneCAN::is_configured(void) const
761
{
762
// if we don't have status assume it's configured
763
if (!seen_status) {
764
return true;
765
}
766
767
return (status_flags & ARDUPILOT_GNSS_STATUS_STATUS_ARMABLE) != 0;
768
}
769
770
/*
771
send pending RTCM data
772
*/
773
void AP_GPS_DroneCAN::send_rtcm(void)
774
{
775
if (_rtcm_stream.buf == nullptr) {
776
return;
777
}
778
WITH_SEMAPHORE(sem);
779
780
const uint32_t now = AP_HAL::millis();
781
if (now - _rtcm_stream.last_send_ms < 20) {
782
// don't send more than 50 per second
783
return;
784
}
785
uint32_t outlen = 0;
786
const uint8_t *ptr = _rtcm_stream.buf->readptr(outlen);
787
if (ptr == nullptr || outlen == 0) {
788
return;
789
}
790
uavcan_equipment_gnss_RTCMStream msg {};
791
outlen = MIN(outlen, sizeof(msg.data.data));
792
msg.protocol_id = UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_PROTOCOL_ID_RTCM3;
793
memcpy(msg.data.data, ptr, outlen);
794
msg.data.len = outlen;
795
if (_detected_modules[_detected_module].ap_dronecan->rtcm_stream.broadcast(msg)) {
796
_rtcm_stream.buf->advance(outlen);
797
_rtcm_stream.last_send_ms = now;
798
}
799
}
800
801
/*
802
handle RTCM data from MAVLink GPS_RTCM_DATA, forwarding it over MAVLink
803
*/
804
void AP_GPS_DroneCAN::inject_data(const uint8_t *data, uint16_t len)
805
{
806
// we only handle this if we are the first DroneCAN GPS or we are
807
// using a different uavcan instance than the first GPS, as we
808
// send the data as broadcast on all DroneCAN device ports and we
809
// don't want to send duplicates
810
const uint32_t now_ms = AP_HAL::millis();
811
if (_detected_module == 0 ||
812
_detected_modules[_detected_module].ap_dronecan != _detected_modules[0].ap_dronecan ||
813
now_ms - _detected_modules[0].last_inject_ms > 2000) {
814
if (_rtcm_stream.buf == nullptr) {
815
// give enough space for a full round from a NTRIP server with all
816
// constellations
817
_rtcm_stream.buf = NEW_NOTHROW ByteBuffer(2400);
818
if (_rtcm_stream.buf == nullptr) {
819
return;
820
}
821
}
822
_detected_modules[_detected_module].last_inject_ms = now_ms;
823
_rtcm_stream.buf->write(data, len);
824
send_rtcm();
825
}
826
}
827
828
/*
829
handle param get/set response
830
*/
831
bool AP_GPS_DroneCAN::handle_param_get_set_response_int(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, int32_t &value)
832
{
833
Debug("AP_GPS_DroneCAN: param set/get response from %d %s %ld\n", node_id, name, value);
834
if (((strcmp(name, "GPS_TYPE") == 0) || (strcmp(name, "GPS1_TYPE") == 0)) && (cfg_step == STEP_SET_TYPE)) {
835
if (role == AP_GPS::GPS_ROLE_MB_BASE && value != AP_GPS::GPS_TYPE_UBLOX_RTK_BASE) {
836
value = (int32_t)AP_GPS::GPS_TYPE_UBLOX_RTK_BASE;
837
requires_save_and_reboot = true;
838
return true;
839
} else if (role == AP_GPS::GPS_ROLE_MB_ROVER && value != AP_GPS::GPS_TYPE_UBLOX_RTK_ROVER) {
840
value = (int32_t)AP_GPS::GPS_TYPE_UBLOX_RTK_ROVER;
841
requires_save_and_reboot = true;
842
return true;
843
} else {
844
cfg_step++;
845
}
846
}
847
848
if (strcmp(name, "GPS_MB_ONLY_PORT") == 0 && cfg_step == STEP_SET_MB_CAN_TX) {
849
if (option_set(AP_GPS::UAVCAN_MBUseDedicatedBus) && !value) {
850
// set up so that another CAN port is used for the Moving Baseline Data
851
// setting this value will allow another CAN port to be used as dedicated
852
// line for the Moving Baseline Data
853
value = 1;
854
requires_save_and_reboot = true;
855
return true;
856
} else if (!option_set(AP_GPS::UAVCAN_MBUseDedicatedBus) && value) {
857
// set up so that all CAN ports are used for the Moving Baseline Data
858
value = 0;
859
requires_save_and_reboot = true;
860
return true;
861
} else {
862
cfg_step++;
863
}
864
}
865
return false;
866
}
867
868
bool AP_GPS_DroneCAN::handle_param_get_set_response_float(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, float &value)
869
{
870
Debug("AP_GPS_DroneCAN: param set/get response from %d %s %f\n", node_id, name, value);
871
return false;
872
}
873
874
void AP_GPS_DroneCAN::handle_param_save_response(AP_DroneCAN* ap_dronecan, const uint8_t node_id, bool success)
875
{
876
Debug("AP_GPS_DroneCAN: param save response from %d %s\n", node_id, success ? "success" : "failure");
877
878
if (cfg_step != STEP_SAVE_AND_REBOOT) {
879
return;
880
}
881
882
if (success) {
883
cfg_step++;
884
}
885
// Also send reboot command
886
// this is ok as we are sending from DroneCAN thread context
887
Debug("AP_GPS_DroneCAN: sending reboot command %d\n", node_id);
888
ap_dronecan->send_reboot_request(node_id);
889
}
890
891
#if AP_DRONECAN_SEND_GPS
892
bool AP_GPS_DroneCAN::instance_exists(const AP_DroneCAN* ap_dronecan)
893
{
894
for (uint8_t i=0; i<ARRAY_SIZE(_detected_modules); i++) {
895
if (ap_dronecan == _detected_modules[i].ap_dronecan) {
896
return true;
897
}
898
}
899
return false;
900
}
901
#endif // AP_DRONECAN_SEND_GPS
902
903
#endif // AP_GPS_DRONECAN_ENABLED
904
905