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_ExternalAHRS/AP_ExternalAHRS_VectorNav.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
support for serial connected AHRS systems
17
*/
18
19
#define ALLOW_DOUBLE_MATH_FUNCTIONS
20
21
#include "AP_ExternalAHRS_config.h"
22
23
#if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED
24
25
#include "AP_ExternalAHRS_VectorNav.h"
26
#include <AP_Math/AP_Math.h>
27
#include <AP_Math/crc.h>
28
#include <AP_Baro/AP_Baro.h>
29
#include <AP_Compass/AP_Compass.h>
30
#include <AP_GPS/AP_GPS.h>
31
#include <AP_InertialSensor/AP_InertialSensor.h>
32
#include <GCS_MAVLink/GCS.h>
33
#include <AP_Logger/AP_Logger.h>
34
#include <AP_SerialManager/AP_SerialManager.h>
35
#include <AP_Common/NMEA.h>
36
#include <stdio.h>
37
#include <AP_BoardConfig/AP_BoardConfig.h>
38
39
extern const AP_HAL::HAL &hal;
40
41
42
/*
43
TYPE::VN_AHRS configures 2 packets: high-rate IMU and mid-rate EKF
44
Header for IMU packet
45
$VNWRG,75,3,16,01,0721*D415
46
Common group (Group 1)
47
TimeStartup
48
AngularRate
49
Accel
50
Imu
51
MagPres
52
Header for EKF packet
53
$VNWRG,76,3,16,11,0001,0106*B36B
54
Common group (Group 1)
55
TimeStartup
56
Attitude group (Group 4)
57
Ypr
58
Quaternion
59
YprU
60
*/
61
62
struct PACKED VN_IMU_packet {
63
static constexpr uint8_t header[]{0x01, 0x21, 0x07};
64
uint64_t timeStartup;
65
float gyro[3];
66
float accel[3];
67
float uncompAccel[3];
68
float uncompAngRate[3];
69
float mag[3];
70
float temp;
71
float pressure;
72
};
73
constexpr uint8_t VN_IMU_packet::header[];
74
constexpr uint8_t VN_IMU_LENGTH = sizeof(VN_IMU_packet) + sizeof(VN_IMU_packet::header) + 1 + 2; // Includes sync byte and CRC
75
76
struct PACKED VN_AHRS_ekf_packet {
77
static constexpr uint8_t header[]{0x11, 0x01, 0x00, 0x06, 0x01};
78
uint64_t timeStartup;
79
float ypr[3];
80
float quaternion[4];
81
float yprU[3];
82
};
83
constexpr uint8_t VN_AHRS_ekf_packet::header[];
84
constexpr uint8_t VN_AHRS_EKF_LENGTH = sizeof(VN_AHRS_ekf_packet) + sizeof(VN_AHRS_ekf_packet::header) + 1 + 2; // Includes sync byte and CRC
85
86
/*
87
TYPE::VN_INS configures 3 packets: high-rate IMU, mid-rate EKF, and 5Hz GNSS
88
Header for IMU packet
89
$VNWRG,75,3,16,01,0721*D415
90
Common group (Group 1)
91
TimeStartup
92
AngularRate
93
Accel
94
Imu
95
MagPres
96
Header for EKF packet
97
$VNWRG,76,3,16,31,0001,0106,0613*097A
98
Common group (Group 1)
99
TimeStartup
100
Attitude group (Group 4)
101
Ypr
102
Quaternion
103
YprU
104
Ins group (Group 5)
105
InsStatus
106
PosLla
107
VelNed
108
PosU
109
VelU
110
Header for GNSS packet
111
$VNWRG,77,1,160,49,0003,26B8,0018*4FD9
112
Common group (Group 1)
113
TimeStartup
114
TimeGps
115
Gnss1 group (Group 3)
116
NumSats
117
GnssFix
118
GnssPosLla
119
GnssVelNed
120
PosU1
121
VelU1
122
GnssDop
123
Gnss2 group (Group 6)
124
NumSats
125
GnssFix
126
*/
127
128
union Ins_Status {
129
uint16_t _value;
130
struct {
131
uint16_t mode : 2;
132
uint16_t gnssFix : 1;
133
uint16_t resv1 : 2;
134
uint16_t imuErr : 1;
135
uint16_t magPresErr : 1;
136
uint16_t gnssErr : 1;
137
uint16_t resv2 : 1;
138
uint16_t gnssHeadingIns : 2;
139
};
140
};
141
142
struct PACKED VN_INS_ekf_packet {
143
static constexpr uint8_t header[]{0x31, 0x01, 0x00, 0x06, 0x01, 0x13, 0x06};
144
uint64_t timeStartup;
145
float ypr[3];
146
float quaternion[4];
147
float yprU[3];
148
uint16_t insStatus;
149
double posLla[3];
150
float velNed[3];
151
float posU;
152
float velU;
153
};
154
constexpr uint8_t VN_INS_ekf_packet::header[];
155
constexpr uint8_t VN_INS_EKF_LENGTH = sizeof(VN_INS_ekf_packet) + sizeof(VN_INS_ekf_packet::header) + 1 + 2; // Includes sync byte and CRC
156
157
struct PACKED VN_INS_gnss_packet {
158
static constexpr uint8_t header[]{0x49, 0x03, 0x00, 0xB8, 0x26, 0x18, 0x00};
159
uint64_t timeStartup;
160
uint64_t timeGps;
161
uint8_t numSats1;
162
uint8_t fix1;
163
double posLla1[3];
164
float velNed1[3];
165
float posU1[3];
166
float velU1;
167
float dop1[7];
168
uint8_t numSats2;
169
uint8_t fix2;
170
};
171
constexpr uint8_t VN_INS_gnss_packet::header[];
172
constexpr uint8_t VN_INS_GNSS_LENGTH = sizeof(VN_INS_gnss_packet) + sizeof(VN_INS_gnss_packet::header) + 1 + 2; // Includes sync byte and CRC
173
174
// constructor
175
AP_ExternalAHRS_VectorNav::AP_ExternalAHRS_VectorNav(AP_ExternalAHRS *_frontend,
176
AP_ExternalAHRS::state_t &_state) :
177
AP_ExternalAHRS_backend(_frontend, _state)
178
{
179
auto &sm = AP::serialmanager();
180
uart = sm.find_serial(AP_SerialManager::SerialProtocol_AHRS, 0);
181
if (!uart) {
182
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "VectorNav ExternalAHRS no UART");
183
return;
184
}
185
baudrate = sm.find_baudrate(AP_SerialManager::SerialProtocol_AHRS, 0);
186
port_num = sm.find_portnum(AP_SerialManager::SerialProtocol_AHRS, 0);
187
188
bufsize = MAX(MAX(MAX(VN_IMU_LENGTH, VN_INS_EKF_LENGTH), VN_INS_GNSS_LENGTH), VN_AHRS_EKF_LENGTH);
189
190
pktbuf = NEW_NOTHROW uint8_t[bufsize];
191
latest_ins_ekf_packet = NEW_NOTHROW VN_INS_ekf_packet;
192
latest_ins_gnss_packet = NEW_NOTHROW VN_INS_gnss_packet;
193
194
if (!pktbuf || !latest_ins_ekf_packet) {
195
AP_BoardConfig::allocation_error("VectorNav ExternalAHRS");
196
}
197
198
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_ExternalAHRS_VectorNav::update_thread, void), "AHRS", 2048, AP_HAL::Scheduler::PRIORITY_SPI, 0)) {
199
AP_HAL::panic("VectorNav Failed to start ExternalAHRS update thread");
200
}
201
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "VectorNav ExternalAHRS initialised");
202
}
203
204
/*
205
check the UART for more data
206
returns true if the function should be called again straight away
207
*/
208
#define SYNC_BYTE 0xFA
209
bool AP_ExternalAHRS_VectorNav::check_uart()
210
{
211
if (!setup_complete) {
212
return false;
213
}
214
WITH_SEMAPHORE(state.sem);
215
// ensure we own the uart
216
uart->begin(0);
217
uint32_t n = uart->available();
218
if (n == 0) {
219
return false;
220
}
221
if (pktoffset < bufsize) {
222
ssize_t nread = uart->read(&pktbuf[pktoffset], MIN(n, unsigned(bufsize-pktoffset)));
223
if (nread <= 0) {
224
return false;
225
}
226
pktoffset += nread;
227
}
228
229
bool match_header1 = false;
230
bool match_header2 = false;
231
bool match_header3 = false;
232
bool match_header4 = false;
233
234
if (pktbuf[0] != SYNC_BYTE) {
235
goto reset;
236
}
237
238
239
match_header1 = (0 == memcmp(&pktbuf[1], VN_IMU_packet::header, MIN(sizeof(VN_IMU_packet::header), unsigned(pktoffset - 1))));
240
if (type == TYPE::VN_AHRS) {
241
match_header2 = (0 == memcmp(&pktbuf[1], VN_AHRS_ekf_packet::header, MIN(sizeof(VN_AHRS_ekf_packet::header), unsigned(pktoffset - 1))));
242
} else {
243
match_header3 = (0 == memcmp(&pktbuf[1], VN_INS_ekf_packet::header, MIN(sizeof(VN_INS_ekf_packet::header), unsigned(pktoffset - 1))));
244
match_header4 = (0 == memcmp(&pktbuf[1], VN_INS_gnss_packet::header, MIN(sizeof(VN_INS_gnss_packet::header), unsigned(pktoffset - 1))));
245
}
246
if (!match_header1 && !match_header2 && !match_header3 && !match_header4) {
247
goto reset;
248
}
249
250
if (match_header1 && pktoffset >= VN_IMU_LENGTH) {
251
uint16_t crc = crc16_ccitt(&pktbuf[1], VN_IMU_LENGTH - 1, 0);
252
if (crc == 0) {
253
process_imu_packet(&pktbuf[sizeof(VN_IMU_packet::header) + 1]);
254
memmove(&pktbuf[0], &pktbuf[VN_IMU_LENGTH], pktoffset - VN_IMU_LENGTH);
255
pktoffset -= VN_IMU_LENGTH;
256
} else {
257
goto reset;
258
}
259
} else if (match_header2 && pktoffset >= VN_AHRS_EKF_LENGTH) {
260
uint16_t crc = crc16_ccitt(&pktbuf[1], VN_AHRS_EKF_LENGTH - 1, 0);
261
if (crc == 0) {
262
process_ahrs_ekf_packet(&pktbuf[sizeof(VN_AHRS_ekf_packet::header) + 1]);
263
memmove(&pktbuf[0], &pktbuf[VN_AHRS_EKF_LENGTH], pktoffset - VN_AHRS_EKF_LENGTH);
264
pktoffset -= VN_AHRS_EKF_LENGTH;
265
} else {
266
goto reset;
267
}
268
} else if (match_header3 && pktoffset >= VN_INS_EKF_LENGTH) {
269
uint16_t crc = crc16_ccitt(&pktbuf[1], VN_INS_EKF_LENGTH - 1, 0);
270
if (crc == 0) {
271
process_ins_ekf_packet(&pktbuf[sizeof(VN_INS_ekf_packet::header) + 1]);
272
memmove(&pktbuf[0], &pktbuf[VN_INS_EKF_LENGTH], pktoffset - VN_INS_EKF_LENGTH);
273
pktoffset -= VN_INS_EKF_LENGTH;
274
} else {
275
goto reset;
276
}
277
} else if (match_header4 && pktoffset >= VN_INS_GNSS_LENGTH) {
278
uint16_t crc = crc16_ccitt(&pktbuf[1], VN_INS_GNSS_LENGTH - 1, 0);
279
if (crc == 0) {
280
process_ins_gnss_packet(&pktbuf[sizeof(VN_INS_gnss_packet::header) + 1]);
281
memmove(&pktbuf[0], &pktbuf[VN_INS_GNSS_LENGTH], pktoffset - VN_INS_GNSS_LENGTH);
282
pktoffset -= VN_INS_GNSS_LENGTH;
283
} else {
284
goto reset;
285
}
286
}
287
return true;
288
289
reset:
290
uint8_t *p = (uint8_t *)memchr(&pktbuf[1], SYNC_BYTE, pktoffset-1);
291
if (p) {
292
uint8_t newlen = pktoffset - (p - pktbuf);
293
memmove(&pktbuf[0], p, newlen);
294
pktoffset = newlen;
295
} else {
296
pktoffset = 0;
297
}
298
return true;
299
}
300
301
// Send command and wait for response
302
// Only run from thread! This blocks and retries until a non-error response is received
303
#define READ_REQUEST_RETRY_MS 500
304
void AP_ExternalAHRS_VectorNav::run_command(const char * fmt, ...)
305
{
306
va_list ap;
307
308
va_start(ap, fmt);
309
hal.util->vsnprintf(message_to_send, sizeof(message_to_send), fmt, ap);
310
va_end(ap);
311
312
uint32_t request_sent = 0;
313
while (true) {
314
hal.scheduler->delay(1);
315
316
const uint32_t now = AP_HAL::millis();
317
if (now - request_sent > READ_REQUEST_RETRY_MS) {
318
nmea_printf(uart, "$%s", message_to_send);
319
request_sent = now;
320
}
321
322
int16_t nbytes = uart->available();
323
while (nbytes-- > 0) {
324
char c = uart->read();
325
if (decode(c)) {
326
if (nmea.error_response && nmea.sentence_done) {
327
// Received a valid VNERR. Try to resend after the timeout length
328
break;
329
}
330
return;
331
}
332
}
333
}
334
}
335
336
// add a single character to the buffer and attempt to decode
337
// returns true if a complete sentence was successfully decoded
338
bool AP_ExternalAHRS_VectorNav::decode(char c)
339
{
340
switch (c) {
341
case ',':
342
// end of a term, add to checksum
343
nmea.checksum ^= c;
344
FALLTHROUGH;
345
case '\r':
346
case '\n':
347
case '*':
348
{
349
if (nmea.sentence_done) {
350
return false;
351
}
352
if (nmea.term_is_checksum) {
353
nmea.sentence_done = true;
354
uint8_t checksum = 16 * char_to_hex(nmea.term[0]) + char_to_hex(nmea.term[1]);
355
return ((checksum == nmea.checksum) && nmea.sentence_valid);
356
}
357
358
// null terminate and decode latest term
359
nmea.term[nmea.term_offset] = 0;
360
if (nmea.sentence_valid) {
361
nmea.sentence_valid = decode_latest_term();
362
}
363
364
// move onto next term
365
nmea.term_number++;
366
nmea.term_offset = 0;
367
nmea.term_is_checksum = (c == '*');
368
return false;
369
}
370
371
case '$': // sentence begin
372
nmea.sentence_valid = true;
373
nmea.term_number = 0;
374
nmea.term_offset = 0;
375
nmea.checksum = 0;
376
nmea.term_is_checksum = false;
377
nmea.sentence_done = false;
378
nmea.error_response = false;
379
return false;
380
}
381
382
// ordinary characters are added to term
383
if (nmea.term_offset < sizeof(nmea.term) - 1) {
384
nmea.term[nmea.term_offset++] = c;
385
}
386
if (!nmea.term_is_checksum) {
387
nmea.checksum ^= c;
388
}
389
390
return false;
391
}
392
393
// decode the most recently consumed term
394
// returns true if new term is valid
395
bool AP_ExternalAHRS_VectorNav::decode_latest_term()
396
{
397
// Check the first two terms (In most cases header + reg number) that they match the sent
398
// message. If not, the response is invalid.
399
switch (nmea.term_number) {
400
case 0:
401
if (strncmp(nmea.term, "VNERR", nmea.term_offset) == 0) {
402
nmea.error_response = true; // Message will be printed on next term
403
} else if (strncmp(nmea.term, message_to_send, nmea.term_offset) != 0) {
404
return false;
405
}
406
return true;
407
case 1:
408
if (nmea.error_response) {
409
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "VectorNav received VNERR code: %s", nmea.term);
410
} else if (strlen(message_to_send) > 6 &&
411
strncmp(nmea.term, &message_to_send[6], nmea.term_offset) != 0) { // Start after "VNXXX,"
412
return false;
413
}
414
return true;
415
case 2:
416
if (strncmp(nmea.term, "VN-", 3) == 0) {
417
// This term is the model number
418
strncpy(model_name, nmea.term, sizeof(model_name));
419
}
420
return true;
421
default:
422
return true;
423
}
424
}
425
426
void AP_ExternalAHRS_VectorNav::initialize() {
427
// Open port in the thread
428
uart->begin(baudrate, 1024, 512);
429
430
// Pause asynchronous communications to simplify packet finding
431
run_command("VNASY,0");
432
433
// Stop ASCII async outputs for both UARTs. If only active UART is disabled, we get a baudrate
434
// overflow on the other UART when configuring binary outputs (reg 75 and 76) to both UARTs
435
run_command("VNWRG,06,0,1");
436
run_command("VNWRG,06,0,2");
437
438
// Read Model Number Register, ID 1
439
run_command("VNRRG,01");
440
441
// Setup for messages respective model types (on both UARTs)
442
if (strncmp(model_name, "VN-1", 4) == 0) {
443
// VN-1X0
444
type = TYPE::VN_AHRS;
445
446
// These assumes unit is still configured at its default rate of 800hz
447
run_command("VNWRG,75,3,%u,01,0721", unsigned(800 / get_rate()));
448
run_command("VNWRG,76,3,16,11,0001,0106");
449
} else {
450
// Default to setup for sensors other than VN-100 or VN-110
451
// This assumes unit is still configured at its default IMU rate of 400hz for VN-300, 800hz for others
452
uint16_t imu_rate = 800; // Default for everything but VN-300
453
if (strncmp(model_name, "VN-300", 6) == 0) {
454
imu_rate = 400;
455
}
456
if (strncmp(model_name, "VN-3", 4) == 0) {
457
has_dual_gnss = true;
458
}
459
run_command("VNWRG,75,3,%u,01,0721", unsigned(imu_rate / get_rate()));
460
run_command("VNWRG,76,3,%u,31,0001,0106,0613", unsigned(imu_rate / 50));
461
run_command("VNWRG,77,3,%u,49,0003,26B8,0018", unsigned(imu_rate / 5));
462
}
463
464
// Resume asynchronous communications
465
run_command("VNASY,1");
466
setup_complete = true;
467
}
468
469
void AP_ExternalAHRS_VectorNav::update_thread() {
470
initialize();
471
while (true) {
472
if (!check_uart()) {
473
hal.scheduler->delay(1);
474
}
475
}
476
}
477
478
const char* AP_ExternalAHRS_VectorNav::get_name() const
479
{
480
if (setup_complete) {
481
return model_name;
482
}
483
return nullptr;
484
}
485
486
// Input data struct for EAHA logging message, used by both AHRS mode and INS mode
487
struct AP_ExternalAHRS_VectorNav::VNAT {
488
uint64_t timeUs;
489
float quat[4];
490
float ypr[3];
491
float yprU[3];
492
};
493
494
495
void AP_ExternalAHRS_VectorNav::write_vnat(const VNAT& data_to_log) const {
496
497
#if HAL_LOGGING_ENABLED
498
// @LoggerMessage: VNAT
499
// @Description: VectorNav Attitude data
500
// @Field: TimeUS: Time since system startup
501
// @Field: Q1: Attitude quaternion 1
502
// @Field: Q2: Attitude quaternion 2
503
// @Field: Q3: Attitude quaternion 3
504
// @Field: Q4: Attitude quaternion 4
505
// @Field: Yaw: Yaw
506
// @Field: Pitch: Pitch
507
// @Field: Roll: Roll
508
// @Field: YU: Yaw unceratainty
509
// @Field: PU: Pitch uncertainty
510
// @Field: RU: Roll uncertainty
511
512
AP::logger().WriteStreaming("VNAT", "TimeUS,Q1,Q2,Q3,Q4,Yaw,Pitch,Roll,YU,PU,RU",
513
"s----dddddd", "F0000000000",
514
"Qffffffffff",
515
data_to_log.timeUs,
516
data_to_log.quat[0], data_to_log.quat[1], data_to_log.quat[2], data_to_log.quat[3],
517
data_to_log.ypr[0], data_to_log.ypr[1], data_to_log.ypr[2],
518
data_to_log.yprU[0], data_to_log.yprU[1], data_to_log.yprU[2]);
519
#endif
520
}
521
522
523
524
// process INS mode INS packet
525
void AP_ExternalAHRS_VectorNav::process_imu_packet(const uint8_t *b)
526
{
527
const struct VN_IMU_packet &pkt = *(struct VN_IMU_packet *)b;
528
529
last_pkt1_ms = AP_HAL::millis();
530
531
const bool use_uncomp = option_is_set(AP_ExternalAHRS::OPTIONS::VN_UNCOMP_IMU);
532
533
{
534
WITH_SEMAPHORE(state.sem);
535
if (use_uncomp) {
536
state.accel = Vector3f{pkt.uncompAccel[0], pkt.uncompAccel[1], pkt.uncompAccel[2]};
537
state.gyro = Vector3f{pkt.uncompAngRate[0], pkt.uncompAngRate[1], pkt.uncompAngRate[2]};
538
} else {
539
state.accel = Vector3f{pkt.accel[0], pkt.accel[1], pkt.accel[2]};
540
state.gyro = Vector3f{pkt.gyro[0], pkt.gyro[1], pkt.gyro[2]};
541
}
542
}
543
544
#if AP_BARO_EXTERNALAHRS_ENABLED
545
{
546
AP_ExternalAHRS::baro_data_message_t baro;
547
baro.instance = 0;
548
baro.pressure_pa = pkt.pressure * 1e3;
549
baro.temperature = pkt.temp;
550
551
AP::baro().handle_external(baro);
552
}
553
#endif
554
555
#if AP_COMPASS_EXTERNALAHRS_ENABLED
556
{
557
AP_ExternalAHRS::mag_data_message_t mag;
558
mag.field = Vector3f{pkt.mag[0], pkt.mag[1], pkt.mag[2]};
559
mag.field *= 1000; // to mGauss
560
561
AP::compass().handle_external(mag);
562
}
563
#endif
564
565
{
566
AP_ExternalAHRS::ins_data_message_t ins;
567
568
ins.accel = state.accel;
569
ins.gyro = state.gyro;
570
ins.temperature = pkt.temp;
571
572
AP::ins().handle_external(ins);
573
}
574
575
#if HAL_LOGGING_ENABLED
576
// @LoggerMessage: VNIM
577
// @Description: VectorNav IMU data
578
// @Field: TimeUS: Time since system startup
579
// @Field: Temp: Temprature
580
// @Field: Pres: Pressure
581
// @Field: MX: Magnetic feild X-axis
582
// @Field: MY: Magnetic feild Y-axis
583
// @Field: MZ: Magnetic feild Z-axis
584
// @Field: AX: Acceleration X-axis
585
// @Field: AY: Acceleration Y-axis
586
// @Field: AZ: Acceleration Z-axis
587
// @Field: GX: Rotation rate X-axis
588
// @Field: GY: Rotation rate Y-axis
589
// @Field: GZ: Rotation rate Z-axis
590
591
AP::logger().WriteStreaming("VNIM", "TimeUS,Temp,Pres,MX,MY,MZ,AX,AY,AZ,GX,GY,GZ",
592
"sdPGGGoooEEE", "F00000000000",
593
"Qfffffffffff",
594
AP_HAL::micros64(),
595
pkt.temp, pkt.pressure*1e3,
596
pkt.mag[0], pkt.mag[1], pkt.mag[2],
597
state.accel[0], state.accel[1], state.accel[2],
598
state.gyro[0], state.gyro[1], state.gyro[2],
599
state.quat[0], state.quat[1], state.quat[2], state.quat[3]);
600
#endif // HAL_LOGGING_ENABLED
601
}
602
603
// process AHRS mode AHRS packet
604
void AP_ExternalAHRS_VectorNav::process_ahrs_ekf_packet(const uint8_t *b) {
605
const struct VN_AHRS_ekf_packet &pkt = *(struct VN_AHRS_ekf_packet *)b;
606
607
last_pkt2_ms = AP_HAL::millis();
608
609
state.quat = Quaternion{pkt.quaternion[3], pkt.quaternion[0], pkt.quaternion[1], pkt.quaternion[2]};
610
state.have_quaternion = true;
611
612
#if HAL_LOGGING_ENABLED
613
VNAT data_to_log;
614
data_to_log.timeUs = AP_HAL::micros64();
615
memcpy(data_to_log.quat, pkt.quaternion, sizeof(pkt.quaternion));
616
memcpy(data_to_log.ypr, pkt.ypr, sizeof(pkt.ypr));
617
memcpy(data_to_log.yprU, pkt.yprU, sizeof(pkt.yprU));
618
619
write_vnat(data_to_log);
620
#endif // HAL_LOGGING_ENABLED
621
}
622
623
// process INS mode EKF packet
624
void AP_ExternalAHRS_VectorNav::process_ins_ekf_packet(const uint8_t *b) {
625
const struct VN_INS_ekf_packet &pkt = *(struct VN_INS_ekf_packet *)b;
626
627
last_pkt2_ms = AP_HAL::millis();
628
*latest_ins_ekf_packet = pkt;
629
630
state.quat = Quaternion{pkt.quaternion[3], pkt.quaternion[0], pkt.quaternion[1], pkt.quaternion[2]};
631
state.have_quaternion = true;
632
633
state.velocity = Vector3f{pkt.velNed[0], pkt.velNed[1], pkt.velNed[2]};
634
state.have_velocity = true;
635
636
state.location = Location{int32_t(pkt.posLla[0] * 1.0e7), int32_t(pkt.posLla[1] * 1.0e7), int32_t(pkt.posLla[2] * 1.0e2), Location::AltFrame::ABSOLUTE};
637
state.last_location_update_us = AP_HAL::micros();
638
state.have_location = true;
639
640
#if HAL_LOGGING_ENABLED
641
VNAT data_to_log;
642
auto now = AP_HAL::micros64();
643
data_to_log.timeUs = now;
644
memcpy(data_to_log.quat, pkt.quaternion, sizeof(pkt.quaternion));
645
memcpy(data_to_log.ypr, pkt.ypr, sizeof(pkt.ypr));
646
memcpy(data_to_log.yprU, pkt.yprU, sizeof(pkt.yprU));
647
write_vnat(data_to_log);
648
649
// @LoggerMessage: VNKF
650
// @Description: VectorNav INS Kalman Filter data
651
// @Field: TimeUS: Time since system startup
652
// @Field: InsStatus: VectorNav INS health status
653
// @Field: Lat: Latitude
654
// @Field: Lon: Longitude
655
// @Field: Alt: Altitude
656
// @Field: VelN: Velocity Northing
657
// @Field: VelE: Velocity Easting
658
// @Field: VelD: Velocity Downing
659
// @Field: PosU: Filter estimated position uncertainty
660
// @Field: VelU: Filter estimated Velocity uncertainty
661
662
AP::logger().WriteStreaming("VNKF", "TimeUS,InsStatus,Lat,Lon,Alt,VelN,VelE,VelD,PosU,VelU",
663
"s-ddmnnndn", "F000000000",
664
"QHdddfffff",
665
now,
666
pkt.insStatus,
667
pkt.posLla[0], pkt.posLla[1], pkt.posLla[2],
668
pkt.velNed[0], pkt.velNed[1], pkt.velNed[2],
669
pkt.posU, pkt.velU);
670
#endif // HAL_LOGGING_ENABLED
671
672
}
673
674
// process INS mode GNSS packet
675
void AP_ExternalAHRS_VectorNav::process_ins_gnss_packet(const uint8_t *b) {
676
const struct VN_INS_gnss_packet &pkt = *(struct VN_INS_gnss_packet *)b;
677
AP_ExternalAHRS::gps_data_message_t gps;
678
679
680
last_pkt3_ms = AP_HAL::millis();
681
*latest_ins_gnss_packet = pkt;
682
683
// get ToW in milliseconds
684
gps.gps_week = pkt.timeGps / (AP_MSEC_PER_WEEK * 1000000ULL);
685
gps.ms_tow = (pkt.timeGps / 1000000ULL) % (60 * 60 * 24 * 7 * 1000ULL);
686
gps.fix_type = AP_GPS_FixType(pkt.fix1);
687
gps.satellites_in_view = pkt.numSats1;
688
689
gps.horizontal_pos_accuracy = pkt.posU1[0];
690
gps.vertical_pos_accuracy = pkt.posU1[2];
691
gps.horizontal_vel_accuracy = pkt.velU1;
692
693
gps.hdop = pkt.dop1[4];
694
gps.vdop = pkt.dop1[3];
695
696
gps.latitude = pkt.posLla1[0] * 1.0e7;
697
gps.longitude = pkt.posLla1[1] * 1.0e7;
698
gps.msl_altitude = pkt.posLla1[2] * 1.0e2;
699
700
gps.ned_vel_north = pkt.velNed1[0];
701
gps.ned_vel_east = pkt.velNed1[1];
702
gps.ned_vel_down = pkt.velNed1[2];
703
704
if (!state.have_origin && gps.fix_type >= AP_GPS_FixType::FIX_3D) {
705
WITH_SEMAPHORE(state.sem);
706
state.origin = Location{int32_t(pkt.posLla1[0] * 1.0e7), int32_t(pkt.posLla1[1] * 1.0e7),
707
int32_t(pkt.posLla1[2] * 1.0e2), Location::AltFrame::ABSOLUTE};
708
state.have_origin = true;
709
}
710
uint8_t instance;
711
if (AP::gps().get_first_external_instance(instance)) {
712
AP::gps().handle_external(gps, instance);
713
}
714
}
715
716
// get serial port number for the uart
717
int8_t AP_ExternalAHRS_VectorNav::get_port(void) const
718
{
719
if (!uart) {
720
return -1;
721
}
722
return port_num;
723
};
724
725
// accessors for AP_AHRS
726
bool AP_ExternalAHRS_VectorNav::healthy(void) const
727
{
728
const uint32_t now = AP_HAL::millis();
729
return (now - last_pkt1_ms < 40) && (now - last_pkt2_ms < 500) && (type == TYPE::VN_AHRS ? true: now - last_pkt3_ms < 1000);
730
}
731
732
bool AP_ExternalAHRS_VectorNav::initialised(void) const
733
{
734
if (!setup_complete) {
735
return false;
736
}
737
return last_pkt1_ms != UINT32_MAX && last_pkt2_ms != UINT32_MAX && (type == TYPE::VN_AHRS ? true : last_pkt3_ms != UINT32_MAX);
738
}
739
740
bool AP_ExternalAHRS_VectorNav::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const
741
{
742
if (!setup_complete) {
743
hal.util->snprintf(failure_msg, failure_msg_len, "VectorNav setup failed");
744
return false;
745
}
746
if (!healthy()) {
747
hal.util->snprintf(failure_msg, failure_msg_len, "VectorNav unhealthy");
748
return false;
749
}
750
if (type == TYPE::VN_INS) {
751
if (latest_ins_gnss_packet->fix1 < 3) {
752
hal.util->snprintf(failure_msg, failure_msg_len, "VectorNav no GPS1 lock");
753
return false;
754
}
755
if (has_dual_gnss && (latest_ins_gnss_packet->fix2 < 3)) {
756
hal.util->snprintf(failure_msg, failure_msg_len, "VectorNav no GPS2 lock");
757
return false;
758
}
759
}
760
return true;
761
}
762
763
/*
764
get filter status. We don't know the meaning of the status bits yet,
765
so assume all OK if we have GPS lock
766
*/
767
void AP_ExternalAHRS_VectorNav::get_filter_status(nav_filter_status &status) const
768
{
769
memset(&status, 0, sizeof(status));
770
status.flags.initalized = initialised();
771
if (healthy()) {
772
if (type == TYPE::VN_AHRS) {
773
status.flags.attitude = true;
774
} else {
775
status.flags.attitude = true;
776
if (latest_ins_ekf_packet) {
777
status.flags.vert_vel = true;
778
status.flags.vert_pos = true;
779
780
status.flags.horiz_vel = true;
781
status.flags.horiz_pos_rel = true;
782
status.flags.horiz_pos_abs = true;
783
status.flags.pred_horiz_pos_rel = true;
784
status.flags.pred_horiz_pos_abs = true;
785
status.flags.using_gps = true;
786
}
787
}
788
}
789
}
790
791
// get variances
792
bool AP_ExternalAHRS_VectorNav::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const
793
{
794
const struct VN_INS_ekf_packet &pkt = *(struct VN_INS_ekf_packet *)latest_ins_ekf_packet;
795
velVar = pkt.velU * vel_gate_scale;
796
posVar = pkt.posU * pos_gate_scale;
797
hgtVar = pkt.posU * hgt_gate_scale;
798
tasVar = 0;
799
return true;
800
}
801
802
#endif // AP_EXTERNAL_AHRS_VECTORNAV_ENABLED
803
804