-
Notifications
You must be signed in to change notification settings - Fork 5
/
Copy pathref_outline.rst
1632 lines (1415 loc) · 103 KB
/
ref_outline.rst
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
Reference Manual
=================
1. Introduction
------------------------
INS1000 is an integrated navigation system consisting of an inertial measurement unit (IMU) and other sensors. Thus it can output continuously the position, velocity and attitude information of the vehicle. A dual-antenna GNSS receiver is used as the primary aiding sensor. Also supported is a distance measurement indicator (DMI) which can be attached to a wheel of the vehicle/robot to measure the rotation rate of the wheel. Integration of a DMI would give an improved solution in challenging environments: urban canyons, tunnels or indoor. This document explains how to use the system.
2. The IMU Frame and the Body Frame
------------------------------------
The IMU frame is the frame in which the IMU’s measurement output is generated. The direction of the axes of an IMU can be identified using the accelerometer signal. When an accelerometer is placed in upward direction on a level surface, its output should be approximately 9.8 :math:`m/s^{2}`.On the other hand, if it is place in downward direction, the output should be -9.8 :math:`m/s^{2}`. The positive direction of all three axes of an IMU can be identified this way.
The body frame is the frame in which the inertial navigation solution is generated. The center of the IMU frame coincides with that of the body frame. However, there can be differences in the attitude between the two frames due to physical limitations in the installation of the IMU. For a vehicle, the forward-right-down is typically the body frame of choice. Thus, there will be a rotation matrix :math:`C_{IMU}^{b}` to transform the IMU measurements to the body frame and, for the example below, it is written as
.. math::
C_{IMU}^{b} = \begin{bmatrix}
c_{11}& c_{12} & c_{13} \\
c_{21}& c_{22} & c_{23}\\
c_{31}& c_{32} & c_{33}
\end{bmatrix}=\begin{bmatrix}
1 & 0 & 0\\
0 & -1 & 0 \\
0 & 0 & -1
\end{bmatrix}
.. figure:: media/ref/The_IMU_frame_and_the_body_frame.png
:scale: 100 %
:align: center
Figure 1: The IMU frame and the body frame
+----------+----------+----------+--------------------------+
| IMU X | IMU Y | IMU Z | Transformation Matrix |
+==========+==========+==========+==========================+
| Forward | Right | Down | [1,0,0; 0,1,0; 0,0,1] |
+----------+----------+----------+--------------------------+
| Forward | Left | Up | [1,0,0; 0,-1,0; 0,0,-1] |
+----------+----------+----------+--------------------------+
| Forward | Down | Left | [1,0,0; 0,0,-1; 0,1,0] |
+----------+----------+----------+--------------------------+
| Forward | Up | Right | [1,0,0; 0,0,1; 0,-1,0] |
+----------+----------+----------+--------------------------+
| Backward | Left | Down | [-1,0,0; 0,-1,0; 0,0,1] |
+----------+----------+----------+--------------------------+
| Backward | Right | Up | [-1,0,0; 0,1,0; 0,0,-1] |
+----------+----------+----------+--------------------------+
| Backward | Up | Left | [-1,0,0; 0,0,-1; 0,-1,0] |
+----------+----------+----------+--------------------------+
| Backward | Down | Right | [-1,0,0; 0,0,1; 0,1,0] |
+----------+----------+----------+--------------------------+
| Right | Backward | Down | [0,-1,0; 1,0,0; 0,0,1] |
+----------+----------+----------+--------------------------+
| Right | Forward | Up | [0,1,0; 1,0,0; 0,0,-1] |
+----------+----------+----------+--------------------------+
| Right | Up | Backward | [0,0,-1; 1,0,0; 0,-1,0] |
+----------+----------+----------+--------------------------+
| Right | Down | Forward | [0,0,1; 1,0,0; 0,1,0] |
+----------+----------+----------+--------------------------+
| Left | Forward | Down | [0,1,0; -1,0,0; 0,0,1] |
+----------+----------+----------+--------------------------+
| Left | Backward | Up | [0,-1,0; -1,0,0; 0,0,-1] |
+----------+----------+----------+--------------------------+
| Left | Up | Forward | [0,0,1; -1,0,0; 0,-1,0] |
+----------+----------+----------+--------------------------+
| Left | Down | Backward | [0,0,-1; -1,0,0; 0,1,0] |
+----------+----------+----------+--------------------------+
| Up | Forward | Left | [0,1,0; 0,0,-1; -1,0,0] |
+----------+----------+----------+--------------------------+
| Up | Backward | Right | [0,-1,0; 0,0,1; -1,0,0] |
+----------+----------+----------+--------------------------+
| Up | Right | Forward | [0,0,1; 0,1,0; -1,0,0] |
+----------+----------+----------+--------------------------+
| Up | Left | Backward | [0,0,-1; 0,-1,0; -1,0,0] |
+----------+----------+----------+--------------------------+
| Down | Forward | Right | [0,1,0; 0,0,1; 1,0,0] |
+----------+----------+----------+--------------------------+
| Down | Backward | Left | [0,-1,0; 0,0,-1; 1,0,0] |
+----------+----------+----------+--------------------------+
| Down | Left | Forward | [0,0,1; 0,-1,0; 1,0,0] |
+----------+----------+----------+--------------------------+
| Down | Right | Backward | [0,0,-1; 0,1,0; 1,0,0] |
+----------+----------+----------+--------------------------+
Table 1: List of IMU to body frame transformation matrices
3. Measuring Lever Arm
------------------------
The lever-arm is the relative position of other sensors from the center of the IMU. To make the measurement process easier, we make a cross-mark on top of the IMU housing and publishes the vector from the center of the IMU to the mark, :math:`l_{I}^{IMU}`, which is called the internal lever-arm. Thus users can measure the relative position from the cross-mark to other sensors which is referred to as the external lever-arm in the body frame, :math:`l_{E}^{b}`. Therefore, the total lever-arm vector is computed as follows:
.. math::
C_{IMU}^{b}l_{I}^{IMU}+l_{E}^{b}
The following methods can be used to precisely measure the lever-arms:
- Computer Aided Design (CAD) Software
- Close-range Photogrammetry
- Precision Surveying using total stations or theodolites together with GNSS
4. NTRIP Client
------------------------
A base station can send out RTCM messages to support the RTK, which enables cm-level positioning accuracy. Networked Transport of RTCM via Internet Protocol (NTRIP) is a protocol to stream the RTCM data over the internet. The user can configure the NTRIP client settings using the control software.
5. User ICD Messages
------------------------
As shown in Figure 2, all ICD messages are composed of header, payload and checksum parts. The header's size is 6 bytes containing 2 sync bytes, message ID, message sub-ID and payload length.
+---------------------+---------+---------------------+
| Header (6 bytes) | Payload | CheckSum (2 bytes) |
+---------------------+---------+---------------------+
Figure 2: Message structure
The checksum shall be computed over the payload part using the Fletcher-16 algorithm as below sample code. Note that all multi-byte entries are written in little-endian format.
.. code-block:: c++
:linenos:
checksum_A = checksum_B = 0;
for (i = 0; i < payload_length; ++i)
{
checksum_A += payload[i];
checksum_B += checksum_A;
}
5.1. Kalman Filter Navigation Message (1 Hz)
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This message is an output of the navigation message at the center of the IMU in 1 Hz synchronized with the GNSS measurements. If the inertial navigator is not running, however, this message contains GNSS-only solutions of the primary GNSS antenna.
+-------+----------+------------------------------------+--------------------------------+
| Field | Type | Description | Content |
+=======+==========+====================================+================================+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+----------+------------------------------------+--------------------------------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+----------+------------------------------------+--------------------------------+
| 3 | uint8_t | Message type | 0x05 |
+-------+----------+------------------------------------+--------------------------------+
| 4 | uint8_t | Message sub-ID | 0x01 |
+-------+----------+------------------------------------+--------------------------------+
| 5 | uint16_t | Payload length | 91 |
+-------+----------+------------------------------------+--------------------------------+
| 6 | double | System time | seconds |
+-------+----------+------------------------------------+--------------------------------+
| 7 | double | GPS time; see Note 1 | seconds |
+-------+----------+------------------------------------+--------------------------------+
| 8 | double | Latitude | radians |
+-------+----------+------------------------------------+--------------------------------+
| 9 | double | Longitude | radians |
+-------+----------+------------------------------------+--------------------------------+
| 10 | double | Ellipsoidal height | m |
+-------+----------+------------------------------------+--------------------------------+
| 11 | double | Velocity in north | m/s |
+-------+----------+------------------------------------+--------------------------------+
| 12 | double | Velocity in east | m/s |
+-------+----------+------------------------------------+--------------------------------+
| 13 | double | Velocity in down | m/s |
+-------+----------+------------------------------------+--------------------------------+
| 14 | double | Roll, rotation about the x-axis | radians |
+-------+----------+------------------------------------+--------------------------------+
| 15 | double | Pitch, rotation about the y-axis | radians |
+-------+----------+------------------------------------+--------------------------------+
| 16 | double | Heading, rotation about the z-axis | radians |
+-------+----------+------------------------------------+--------------------------------+
| 17 | uint8_t | Position mode | See Note 2 |
+-------+----------+------------------------------------+--------------------------------+
| 18 | uint8_t | Velocity mode | See Note 2 |
+-------+----------+------------------------------------+--------------------------------+
| 19 | uint8_t | Attitude status | 0: Invalid, 1: Coarse, 2: Fine |
+-------+----------+------------------------------------+--------------------------------+
| 20 | uint8_t | Checksum A | |
+-------+----------+------------------------------------+--------------------------------+
| 21 | uint8_t | Checksum B | |
+-------+----------+------------------------------------+--------------------------------+
.. note::
1. GPS seconds since starting week; thus this will not rollover after 604800.
#. Position and velocity mode are defined as follows:
- 0: Invalid,
- 1: Dead-reckoning (navigating with inertial measurements only),
- 2: Stand-alone (autonomous or single point positioning),
- 3: Precise point positioning (using precise ephemeris data)
- 4: Code differential (using code-corrections from base stations or SBAS)
- 5: RTK float
- 6: RTK fixed
- 7: User aiding (aiding by the user input)
5.2. Satellite Signal Strength
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This message delivers the satellite signal strength information obtained from the GNSS observable.
+-------+----------+-----------------------------+-----------------------+
| Field | Type | Description | Content |
+=======+==========+=============================+=======================+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+----------+-----------------------------+-----------------------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+----------+-----------------------------+-----------------------+
| 3 | uint8_t | Message type | 0x05 |
+-------+----------+-----------------------------+-----------------------+
| 4 | uint8_t | Message sub-ID | 0x02 |
+-------+----------+-----------------------------+-----------------------+
| 5 | uint16_t | Payload length | 19 + N_SV * 10 |
+-------+----------+-----------------------------+-----------------------+
| 6 | double | System time | seconds |
+-------+----------+-----------------------------+-----------------------+
| 7 | double | GPS time | |
+-------+----------+-----------------------------+-----------------------+
| 8 | uint8_t | Receiver ID | |
+-------+----------+-----------------------------+-----------------------+
| 9 | uint8_t | Antenna ID | |
+-------+----------+-----------------------------+-----------------------+
| 10 | uint8_t | Number of satellites (N_SV) | |
+-------+----------+-----------------------------+-----------------------+
| 11 | uint8_t | SV system; see Note 1 | First satellite data |
+-------+----------+-----------------------------+-----------------------|
| 12 | uint8_t | SVID; see Note 2 | |
+-------+----------+-----------------------------+-----------------------|
| 13 | float | L1 C/N0 (dB-Hz) | |
+-------+----------+-----------------------------+-----------------------|
| 14 | float | L2 C/N0 (dB-Hz) | |
+-------+----------+-----------------------------+-----------------------+
| 15 | uint8_t | SV system | Second satellite data |
+-------+----------+-----------------------------+-----------------------|
| 16 | uint8_t | SVID | |
+-------+----------+-----------------------------+-----------------------|
| 17 | float | L1 C/N0 (dB-Hz) | |
+-------+----------+-----------------------------+-----------------------|
| 18 | float | L2 C/N0 (dB-Hz) | |
+-------+----------+-----------------------------+-----------------------+
| ... | | | |
+-------+----------+-----------------------------+-----------------------+
| | uint8_t | Checksum A | |
+-------+----------+-----------------------------+-----------------------+
| | uint8_t | Checksum B | |
+-------+----------+-----------------------------+-----------------------+
.. note::
1. 0: GPS, 1: GLONASS, 2: Galileo, 3: QZSS, 4: Beidou, 5: SBAS
#. SVID is the unique satellite number used in each satellite system; for GPS it is the PRN number and for GLONASS it is the SLOT number.
5.3. SV Visibility
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+-------+----------+-----------------+-----------------------+
| Field | Type | Description | Content |
+=======+==========+=================+=======================+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+----------+-----------------+-----------------------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+----------+-----------------+-----------------------+
| 3 | uint8_t | Message type | 0x05 |
+-------+----------+-----------------+-----------------------+
| 4 | uint8_t | Message sub-ID | 0x03 |
+-------+----------+-----------------+-----------------------+
| 5 | uint16_t | Payload length | 18 + N_SV * 10 |
+-------+----------+-----------------+-----------------------+
| 6 | double | System time | seconds |
+-------+----------+-----------------+-----------------------+
| 7 | double | GPS time | seconds |
+-------+----------+-----------------+-----------------------+
| 8 | uint8_t | Receiver number | |
+-------+----------+-----------------+-----------------------+
| 9 | uint8_t | N_SV | Number of SV data |
+-------+----------+-----------------+-----------------------+
| 10 | uint8_t | SV system | First satellite data |
+-------+----------+-----------------+-----------------------|
| 11 | uint8_t | SVID | |
+-------+----------+-----------------+-----------------------|
| 12 | float | Azimuth (deg) | |
+-------+----------+-----------------+-----------------------|
| 13 | float | Elevation (deg) | |
+-------+----------+-----------------+-----------------------+
| 14 | uint8_t | SV system | Second satellite data |
+-------+----------+-----------------+-----------------------|
| 15 | uint8_t | SVID | |
+-------+----------+-----------------+-----------------------|
| 16 | float | Azimuth (deg) | |
+-------+----------+-----------------+-----------------------|
| 17 | float | Elevation (deg) | |
+-------+----------+-----------------+-----------------------+
| ... | | | |
+-------+----------+-----------------+-----------------------+
| | uint8_t | Checksum A | |
+-------+----------+-----------------+-----------------------+
| | uint8_t | Checksum B | |
+-------+----------+-----------------+-----------------------+
5.4. Install Parameters
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+-------+--------------+-----------------------------------+--------------------+
| Field | Type | Description | Content |
+=======+==============+===================================+====================+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+--------------+-----------------------------------+--------------------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+--------------+-----------------------------------+--------------------+
| 3 | uint8_t | Message type | 0x05 |
+-------+--------------+-----------------------------------+--------------------+
| 4 | uint8_t | Message sub-ID | 0x04 |
+-------+--------------+-----------------------------------+--------------------+
| 5 | uint16_t | Payload length | 72+N_ANT*32 |
+-------+--------------+-----------------------------------+--------------------+
| 6 | double[3][3] | IMU axes transformation matrix | |
+-------+--------------+-----------------------------------+--------------------+
| 7 | uint8_t | N_ANT | Number of antennas |
+-------+--------------+-----------------------------------+--------------------+
| 8 | double[3] | Lever-arm vector of 1st antenna | m |
+-------+--------------+-----------------------------------+--------------------+
| 9 | double | Lever-arm variance of 1st antenna | :math:`m^{2}` |
+-------+--------------+-----------------------------------+--------------------+
| 10 | double[3] | Lever-arm vector of 2nd antenna | m |
+-------+--------------+-----------------------------------+--------------------+
| 11 | double | Lever-arm variance of 2nd antenna | :math:`m^{2}` |
+-------+--------------+-----------------------------------+--------------------+
| … | | | |
+-------+--------------+-----------------------------------+--------------------+
| | uint8_t | Checksum A | |
+-------+--------------+-----------------------------------+--------------------+
| | uint8_t | Checksum B | |
+-------+--------------+-----------------------------------+--------------------+
5.5. Nav Uncertainty Message
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+-------+----------+----------------+---------+
| Field | Type | Description | Content |
+=======+==========+================+=========+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+----------+----------------+---------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+----------+----------------+---------+
| 3 | uint8_t | Message type | 0x05 |
+-------+----------+----------------+---------+
| 4 | uint8_t | Message sub-ID | 0x05 |
+-------+----------+----------------+---------+
| 5 | uint16_t | Payload length | 32 |
+-------+----------+----------------+---------+
| 6 | double | System time | seconds |
+-------+----------+----------------+---------+
| 7 | double | Position RMS | m |
+-------+----------+----------------+---------+
| 8 | double | Velocity RMS | m/s |
+-------+----------+----------------+---------+
| 9 | double | Attitude RMS | deg |
+-------+----------+----------------+---------+
| 10 | uint8_t | Checksum A | |
+-------+----------+----------------+---------+
| 11 | uint8_t | Checksum B | |
+-------+----------+----------------+---------+
5.6. Product ID Message
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This message contains the identification number of the product. To receive this message send the message defined in Section 8.1.
+-------+----------+----------------+---------+
| Field | Type | Description | Content |
+=======+==========+================+=========+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+----------+----------------+---------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+----------+----------------+---------+
| 3 | uint8_t | Message type | 0x05 |
+-------+----------+----------------+---------+
| 4 | uint8_t | Message sub-ID | 0x06 |
+-------+----------+----------------+---------+
| 5 | uint16_t | Payload length | 2 |
+-------+----------+----------------+---------+
| 6 | uint16_t | Product ID | |
+-------+----------+----------------+---------+
| 7 | uint8_t | Checksum A | |
+-------+----------+----------------+---------+
| 8 | uint8_t | Checksum B | |
+-------+----------+----------------+---------+
5.7. Navigation Data Message (High Rate)
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+-------+-----------+---------------------------------+----------------------------+
| Field | Type | Description | Content |
+=======+===========+=================================+============================+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+-----------+---------------------------------+----------------------------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+-----------+---------------------------------+----------------------------+
| 3 | uint8_t | Message type | 0x05 |
+-------+-----------+---------------------------------+----------------------------+
| 4 | uint8_t | Message sub-ID | 0x07 |
+-------+-----------+---------------------------------+----------------------------+
| 5 | uint16_t | Payload length | 99 |
+-------+-----------+---------------------------------+----------------------------+
| 6 | double | System time | seconds |
+-------+-----------+---------------------------------+----------------------------+
| 7 | double | GPS time of week | seconds |
+-------+-----------+---------------------------------+----------------------------+
| 8 | double | Latitude | deg |
+-------+-----------+---------------------------------+----------------------------+
| 9 | double | Longitude | deg |
+-------+-----------+---------------------------------+----------------------------+
| 10 | double | Ellipsoidal height | m |
+-------+-----------+---------------------------------+----------------------------+
| 11 | double[3] | Velocity in NED | m/s |
+-------+-----------+---------------------------------+----------------------------+
| 12 | double[4] | Body to NED attitude quaternion | See Note 1 in Section 6.13 |
+-------+-----------+---------------------------------+----------------------------+
| 13 | uint8_t | Alignment mode | |
+-------+-----------+---------------------------------+----------------------------+
| 14 | uint16_t | GPS week number | |
+-------+-----------+---------------------------------+----------------------------+
| 15 | uint8_t | Checksum A | |
+-------+-----------+---------------------------------+----------------------------+
| 16 | uint8_t | Checksum B | |
+-------+-----------+---------------------------------+----------------------------+
5.8. Scaled Raw IMU Data
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This message contains scaled raw IMU data. The reference frame of this data is the IMU frame.
+-------+-----------+----------------+-----------------+
| Field | Type | Description | Content |
+=======+===========+================+=================+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+-----------+----------------+-----------------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+-----------+----------------+-----------------+
| 3 | uint8_t | Message type | 0x05 |
+-------+-----------+----------------+-----------------+
| 4 | uint8_t | Message sub-ID | 0x08 |
+-------+-----------+----------------+-----------------+
| 5 | uint16_t | Payload length | 56 |
+-------+-----------+----------------+-----------------+
| 6 | double | System time | seconds |
+-------+-----------+----------------+-----------------+
| 7 | double[3] | Acceleration | :math:`m/s^{2}` |
+-------+-----------+----------------+-----------------+
| 8 | double[3] | Rotation rate | degrees/s |
+-------+-----------+----------------+-----------------+
| 9 | uint8_t | Checksum A | |
+-------+-----------+----------------+-----------------+
| 10 | uint8_t | Checksum B | |
+-------+-----------+----------------+-----------------+
5.9. Solution Status (1 Hz)
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This message shows the Kalman filter solution status. The RMS of the position, velocity and attitude is the squre-root of the diagonal elements of the covariance matrix of the Kalman filter.
+-------+-----------+-------------------------------------------------+---------+
| Field | Type | Description | Content |
+=======+===========+=================================================+=========+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+-----------+-------------------------------------------------+---------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+-----------+-------------------------------------------------+---------+
| 3 | uint8_t | Message type | 0x05 |
+-------+-----------+-------------------------------------------------+---------+
| 4 | uint8_t | Message sub-ID | 0x09 |
+-------+-----------+-------------------------------------------------+---------+
| 5 | uint16_t | Payload length | 92 |
+-------+-----------+-------------------------------------------------+---------+
| 6 | double | System time | seconds |
+-------+-----------+-------------------------------------------------+---------+
| 7 | uint8_t | Number of SVs used | |
+-------+-----------+-------------------------------------------------+---------+
| 8 | uint8_t | Processing mode | |
+-------+-----------+-------------------------------------------------+---------+
| 9 | uint16_t | GPS week number; if 0 time is not synced to GPS | |
+-------+-----------+-------------------------------------------------+---------+
| 10 | double | GPS time of week | seconds |
+-------+-----------+-------------------------------------------------+---------+
| 11 | double[3] | Position RMS (NED) | m |
+-------+-----------+-------------------------------------------------+---------+
| 12 | double[3] | Velocity RMS (NED) | m/s |
+-------+-----------+-------------------------------------------------+---------+
| 13 | double[3] | Attitude RMS (NED) | deg |
+-------+-----------+-------------------------------------------------+---------+
| 14 | uint8_t | Checksum A | |
+-------+-----------+-------------------------------------------------+---------+
| 15 | uint8_t | Checksum B | |
+-------+-----------+-------------------------------------------------+---------+
5.10. Repackaged GSV Message
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This is a repackaged NMEA GSV message generated by the receiver.
+-----------+-------------+-----------------+----------------------+
| Field | Type | Description | Content |
+===========+=============+=================+======================+
| 1 | uint8_t | Sync 1 | 0xAF |
+-----------+-------------+-----------------+----------------------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-----------+-------------+-----------------+----------------------+
| 3 | uint8_t | Message type | 0x05 |
+-----------+-------------+-----------------+----------------------+
| 4 | uint8_t | Message sub-ID | 0x0A |
+-----------+-------------+-----------------+----------------------+
| 5 | uint16_t | Payload length | length 12 + N_SV * 5 |
+-----------+-------------+-----------------+----------------------+
| 6 | double | System time | seconds |
+-----------+-------------+-----------------+----------------------+
| 7 | uint8_t | Receiver number | |
+-----------+-------------+-----------------+----------------------+
| 8 | uint8_t | Antenna ID | |
+-----------+-------------+-----------------+----------------------+
| 9 | uint8_t | SV system | |
+-----------+-------------+-----------------+----------------------+
| 10 | uint8_t | N_SV | |
+-----------+-------------+-----------------+----------------------+
| 11 | uint8_t | SVID | SVID of 1st SV |
+-----------+-------------+-----------------+----------------------+
| 12 | uint8_t | Elevation | deg |
+-----------+-------------+-----------------+----------------------+
| 13 | uint16_t | Azimuth | deg |
+-----------+-------------+-----------------+----------------------+
| 14 | uint8_t | SNR | db-Hz |
+-----------+-------------+-----------------+----------------------+
| 15 | uint8_t | SVID | SVID of 2nd SV |
+-----------+-------------+-----------------+----------------------+
| 16 | uint8_t | Elevation | deg |
+-----------+-------------+-----------------+----------------------+
| 17 | uint16_t | Azimuth | deg |
+-----------+-------------+-----------------+----------------------+
| 18 | uint8_t | SNR | db-Hz |
+-----------+-------------+-----------------+----------------------+
| ... | | | |
+-----------+-------------+-----------------+----------------------+
| | uint8_t | Checksum A | |
+-----------+-------------+-----------------+----------------------+
| | uint8_t | Checksum B | |
+-----------+-------------+-----------------+----------------------+
5.11. Vehicle Dynamics Message
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+-------+-----------+--------------------------------------------------------+---------+
| Field | Type | Description | Content |
+=======+===========+========================================================+=========+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+-----------+--------------------------------------------------------+---------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+-----------+--------------------------------------------------------+---------+
| 3 | uint8_t | Message type | 0x05 |
+-------+-----------+--------------------------------------------------------+---------+
| 4 | uint8_t | Message sub-ID | 0x0B |
+-------+-----------+--------------------------------------------------------+---------+
| 5 | uint16_t | Payload length | 67 |
+-------+-----------+--------------------------------------------------------+---------+
| 6 | double | System time | seconds |
+-------+-----------+--------------------------------------------------------+---------+
| 7 | double | GPS time of week | seconds |
+-------+-----------+--------------------------------------------------------+---------+
| 8 | double[3] | Acceleration in body frame. See Note 2 in Section 5.13 | |
+-------+-----------+--------------------------------------------------------+---------+
| 9 | double[3] | Rotation rate in body frame. See Note 3 in Section 5.13| |
+-------+-----------+--------------------------------------------------------+---------+
| 10 | uint16_t | GPS week number | |
+-------+-----------+--------------------------------------------------------+---------+
| 11 | uint8_t | Alignment mode | |
+-------+-----------+--------------------------------------------------------+---------+
| 12 | uint8_t | Checksum A | |
+-------+-----------+--------------------------------------------------------+---------+
| 13 | uint8_t | Checksum B | |
+-------+-----------+--------------------------------------------------------+---------+
5.12. Distance Measurement Indicator Data12
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
+-------+----------+----------------+---------+
| Field | Type | Description | Content |
+=======+==========+================+=========+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+----------+----------------+---------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+----------+----------------+---------+
| 3 | uint8_t | Message type | 0x05 |
+-------+----------+----------------+---------+
| 4 | uint8_t | Message sub-ID | 0x0C |
+-------+----------+----------------+---------+
| 5 | uint16_t | Payload length | 13 |
+-------+----------+----------------+---------+
| 6 | double | System time | seconds |
+-------+----------+----------------+---------+
| 7 | int32_t | Pulse count | |
+-------+----------+----------------+---------+
| 8 | uint8_t | DMI ID | |
+-------+----------+----------------+---------+
| 9 | uint8_t | Checksum A | |
+-------+----------+----------------+---------+
| 10 | uint8_t | Checksum B | |
+-------+----------+----------------+---------+
5.13. Compact Navigation Message (High Rate)
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This message is a high-rate real-time navigation output at the position defined by the user.
+-------+----------+----------------------------------------------------+--------------------------------+
| Field | Type | Description | Content |
+=======+==========+====================================================+================================+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+----------+----------------------------------------------------+--------------------------------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+----------+----------------------------------------------------+--------------------------------+
| 3 | uint8_t | Message type | 0x05 |
+-------+----------+----------------------------------------------------+--------------------------------+
| 4 | uint8_t | Message sub-ID | 0x0D |
+-------+----------+----------------------------------------------------+--------------------------------+
| 5 | uint16_t | Payload length | 119 |
+-------+----------+----------------------------------------------------+--------------------------------+
| 6 | double | System time if week = 0, otherwise GPS timeof week | seconds |
+-------+----------+----------------------------------------------------+--------------------------------+
| 7 | double | Latitude | degrees |
+-------+----------+----------------------------------------------------+--------------------------------+
| 8 | double | Longitude | degrees |
+-------+----------+----------------------------------------------------+--------------------------------+
| 9 | float | Ellipsoidal height | m |
+-------+----------+----------------------------------------------------+--------------------------------+
| 10 | float[3] | Velocity in North, East, Down | m/s |
+-------+----------+----------------------------------------------------+--------------------------------+
| 11 | float[4] | Attitude quaternion; see Note 1 | Scalar, X, Y, Z |
+-------+----------+----------------------------------------------------+--------------------------------+
| 12 | float[3] | Acceleration in body frame; see Note 2 | m/s2 |
+-------+----------+----------------------------------------------------+--------------------------------+
| 13 | float[3] | Rotation rate in body frame; see Note 3 | degrees/s |
+-------+----------+----------------------------------------------------+--------------------------------+
| 14 | float[3] | Position RMS in NED | m |
+-------+----------+----------------------------------------------------+--------------------------------+
| 15 | float[3] | Velocity RMS in NED | m/s |
+-------+----------+----------------------------------------------------+--------------------------------+
| 16 | float[3] | Attitude RMS in NED | degrees |
+-------+----------+----------------------------------------------------+--------------------------------+
| 17 | uint16_t | GPS week number | If 0 time is not synced to GPS |
+-------+----------+----------------------------------------------------+--------------------------------+
| 18 | uint8_t | Alignment status | 0: Invalid, 1: Coarse, 2: Fine |
+-------+----------+----------------------------------------------------+--------------------------------+
| 19 | uint8_t | Checksum A | |
+-------+----------+----------------------------------------------------+--------------------------------+
| 20 | uint8_t | Checksum B | |
+-------+----------+----------------------------------------------------+--------------------------------+
.. note::
1. Attitude quaternion for the transformation from the body frame to the NED frame, :math:`q_{b}^{n}`. Note that the quaternion in ROS is defined as (X, Y, Z, scalar). The DCM corresponding to :math:`q_{b}^{n}` can be computed as follows:
.. math::
C_{b}^{n} = \begin{bmatrix}
q_{0}^{2}+ q_{1}^{2}- q_{2}^{2}- q_{3}^{2} & 2(q_{1}q_{2}-q_{0}q_{3}) & 2(q_{1}q_{3}+q_{0}q_{2}) \\
2(q_{1}q_{2}+q_{0}q_{3})& q_{0}^{2}- q_{1}^{2}+q_{2}^{2}- q_{3}^{2} & 2(q_{2}q_{3}-q_{0}q_{1})\\
2(q_{1}q_{3}-q_{0}q_{2}) & 2(q_{2}q_{3}+q_{0}q_{1}) & q_{0}^{2}-q_{1}^{2}- q_{2}^{2}+ q_{3}^{2}
\end{bmatrix}
where :math:`q_{i}` are elements of :math:`q_{b}^{n}`. Let :math:`C_{b}^{n} = \begin{Bmatrix}c_{ij}\end{Bmatrix}` then if :math:`\begin{vmatrix}c_{31}\end{vmatrix}< 0.9999` the Euler angles can be computed as follows:
.. math::
\phi =atan2(c_{32},c_{33})
.. math::
\Theta = atan\begin{pmatrix}-c_{31}/\sqrt{c_{32}^{2}+c_{33}^{2}}\end{pmatrix}
.. math::
\psi = atan2(c_{21},c_{11})
where :math:`\phi`, :math:`\Theta` and :math:`\psi` are the roll, pitch and heading, respectively.
2. Acceleration output is corrected for the gravity, Coriolis force and the estimated accelerometer biases: :math:`f^{b}-b_{a}+C_{e}^{b}(g^{e}-2w_{ie}^{e}\times v^{e} )` where :math:`f^{b}` is the specific force measurement from the IMU, :math:`b_{a}` estimated accelerometer bias, :math:`C_{e}^{b}` the DCM for the transformation from the ECEF to the body frame, :math:`g^{e}` the gravity vector computed from the model, :math:`w_{ie}^{e}` the earth's rotation rate vector, and :math:`v^{e}` the velocity vector.
3. Rotation rate output is corrected for the earth rotation rate and the estimated gyro biases, i.e., :math:`w_{ie}^{e}`.
5.14. NMEA PECNM Message
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This message is NMEA style text message corresponding to the message in Section 5.13.
5.15. NMEA GPRMC Message
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This is the NMEA GPRMC message generated by the primary GNSS receiver.
5.16. Time Sync Message
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This message contains the time sync message between the system time and GPS time. It gets generated at every PPS event. The GPS time corresponding to the system time can be obtained by
GPS time = System computer time - Bias
+-------+----------+-------------------------------+---------+
| Field | Type | Description | Content |
+=======+==========+===============================+=========+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+----------+-------------------------------+---------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+----------+-------------------------------+---------+
| 3 | uint8_t | Message type | 0x05 |
+-------+----------+-------------------------------+---------+
| 4 | uint8_t | Message sub-ID | 0x10 |
+-------+----------+-------------------------------+---------+
| 5 | uint16_t | Payload length | 16 |
+-------+----------+-------------------------------+---------+
| 6 | double | System computer time | seconds |
+-------+----------+-------------------------------+---------+
| 7 | double | Bias with respect to GPS time | seconds |
+-------+----------+-------------------------------+---------+
| 8 | uint8_t | Checksum A | |
+-------+----------+-------------------------------+---------+
| 9 | uint8_t | Checksum B | |
+-------+----------+-------------------------------+---------+
5.17. Raw GNSS Data Message
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This message contains raw data generated by the GNSS receivers.
+-------+------------+----------------------+---------+
| Field | Type | Description | Content |
+=======+============+======================+=========+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+------------+----------------------+---------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+------------+----------------------+---------+
| 3 | uint8_t | Message type | 0x05 |
+-------+------------+----------------------+---------+
| 4 | uint8_t | Message sub-ID | 0x11 |
+-------+------------+----------------------+---------+
| 5 | uint16_t | Payload length | 10+N |
+-------+------------+----------------------+---------+
| 6 | double | System computer time | seconds |
+-------+------------+----------------------+---------+
| 7 | uint8_t | Receiver number | |
+-------+------------+----------------------+---------+
| 8 | uint8_t | Receiver type | |
+-------+------------+----------------------+---------+
| 9 | uint8_t[N] | Raw GNSS data | |
+-------+------------+----------------------+---------+
| 10 | uint8_t | Checksum A | |
+-------+------------+----------------------+---------+
| 11 | uint8_t | Checksum B | |
+-------+------------+----------------------+---------+
5.18. Engine Version Message
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This message shows the engine version of the system. To receive this message the user needs to send an 8-byte binary message “0xAF 0x02 0x06 0x0B 0x01 0x02 0x02 0x02” to the system.
+-------+----------+-----------------------+---------+
| Field | Type | Description | Content |
+=======+==========+=======================+=========+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+----------+-----------------------+---------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+----------+-----------------------+---------+
| 3 | uint8_t | Message type | 0x05 |
+-------+----------+-----------------------+---------+
| 4 | uint8_t | Message sub-ID | 0x12 |
+-------+----------+-----------------------+---------+
| 5 | uint16_t | Payload length | N |
+-------+----------+-----------------------+---------+
| 6 | char[N] | Engine version string | |
+-------+----------+-----------------------+---------+
| 7 | uint8_t | Checksum A | |
+-------+----------+-----------------------+---------+
| 8 | uint8_t | Checksum B | |
+-------+----------+-----------------------+---------+
5.19. GNSS Receiver Acknowledge Message
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This message shows the acknowledge response from a GNSS receiver.
+-------+----------+-----------------+---------+
| Field | Type | Description | Content |
+=======+==========+=================+=========+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+----------+-----------------+---------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+----------+-----------------+---------+
| 3 | uint8_t | Message type | 0x05 |
+-------+----------+-----------------+---------+
| 4 | uint8_t | Message sub-ID | 0x13 |
+-------+----------+-----------------+---------+
| 5 | uint16_t | Payload length | 2 |
+-------+----------+-----------------+---------+
| 6 | uint8_t | Receiver number | |
+-------+----------+-----------------+---------+
| 7 | uint8_t | Receiver type | |
+-------+----------+-----------------+---------+
| 8 | uint8_t | Checksum A | |
+-------+----------+-----------------+---------+
| 9 | uint8_t | Checksum B | |
+-------+----------+-----------------+---------+
5.20. GNSS Antenna Lever-Arm Calibration Data
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
Although it is recommended to accurately measure the lever-arms, sometimes it is very difficult to measure them. In this case the user can let the system calibrate the lever-arm vector. The calibration, however, must be done in an open-sky area with RTK enabled. For the primary antenna, the trajectory must include frequent turns, up-hill or down-hill driving for a considerably long time (one hour or more). Thus it would be the best to measure precisely with other instruments. Also the dual-antenna solution cannot be used in the solution during the calibration mode. So the INS initialization must be done with GNSS velocity.
+-------+-----------+--------------------------------+--------------------+
| Field | Type | Description | Content |
+=======+===========+================================+====================+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+-----------+--------------------------------+--------------------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+-----------+--------------------------------+--------------------+
| 3 | uint8_t | Message type | 0x05 |
+-------+-----------+--------------------------------+--------------------+
| 4 | uint8_t | Message sub-ID | 0x14 |
+-------+-----------+--------------------------------+--------------------+
| 5 | uint16_t | Payload length | 57 |
+-------+-----------+--------------------------------+--------------------+
| 6 | double | Internal computer time | seconds |
+-------+-----------+--------------------------------+--------------------+
| 7 | double[3] | Lever arm vector in body frame | |
+-------+-----------+--------------------------------+--------------------+
| 8 | double[3] | Variance | m2 |
+-------+-----------+--------------------------------+--------------------+
| 9 | uint8_t | Antenna indicator; see Note 1 | 0: pri, 1: sec-pri |
+-------+-----------+--------------------------------+--------------------+
| 10 | uint8_t | Checksum A | |
+-------+-----------+--------------------------------+--------------------+
| 11 | uint8_t | Checksum B | |
+-------+-----------+--------------------------------+--------------------+
.. note::
1. When antenna indicator is '1' the message outputs the vector from the primary to the secondary antenna in the body frame. To get the lever-arm of the secondary antenna, the primary lever-arm vector must be added. Shown in Figure is a plot of this message for a lever-arm of the secondary antenna with respect to the primary antenna. It is recommended to take the mean values after the convergence.
.. figure:: media/ref/Example_of_a_lever-arm_calibration.png
:scale: 100 %
:align: center
Figure 4: The IMU frame and the body frame
5.21. DMI Lever-Arm Calibration Data
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
TBD.
5.22. Geoid Height
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This message outputs the Geoid height, which is the height of Geoid above the ellipsoid. The height above Geoid, treated normally as the height above mean sea level (MSL), can be computed as follows:
Height above MSL = Height above ellipsoid - Geoid height
+-------+----------+----------------+---------+
| Field | Type | Description | Content |
+=======+==========+================+=========+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+----------+----------------+---------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+----------+----------------+---------+
| 3 | uint8_t | Message type | 0x05 |
+-------+----------+----------------+---------+
| 4 | uint8_t | Message sub-ID | 0x16 |
+-------+----------+----------------+---------+
| 5 | uint16_t | Payload length | 12 |
+-------+----------+----------------+---------+
| 6 | double | GPS time | seconds |
+-------+----------+----------------+---------+
| 7 | float | Geoid height | m |
+-------+----------+----------------+---------+
| 8 | uint8_t | Checksum A | |
+-------+----------+----------------+---------+
| 9 | uint8_t | Checksum B | |
+-------+----------+----------------+---------+
5.23. Corrected IMU Data
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This message contains IMU data corrected for the sensor biases estimated by the fusion algorithm. Note that the effect of the gravity and the Earth’s rotation rate is still included in the sensor data. The reference frame of this data is the user body frame and thus the rotation from the IMU frame to the user body frame is applied.
+-------+-----------+------------------+-----------+
| Field | Type | Description | Content |
+=======+===========+==================+===========+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+-----------+------------------+-----------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+-----------+------------------+-----------+
| 3 | uint8_t | Message type | 0x05 |
+-------+-----------+------------------+-----------+
| 4 | uint8_t | Message sub-ID | 0x17 |
+-------+-----------+------------------+-----------+
| 5 | uint16_t | Payload length | 58 |
+-------+-----------+------------------+-----------+
| 6 | double | GPS time of week | seconds |
+-------+-----------+------------------+-----------+
| 7 | double[3] | Acceleration | m/s2 |
+-------+-----------+------------------+-----------+
| 8 | double[3] | Rotation rate | degrees/s |
+-------+-----------+------------------+-----------+
| 9 | uint16_t | GPS week number | |
+-------+-----------+------------------+-----------+
| 10 | uint8_t | Checksum A | |
+-------+-----------+------------------+-----------+
| 11 | uint8_t | Checksum B | |
+-------+-----------+------------------+-----------+
5.24. GPS-UTC Time Offset
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This message contains the offset between the GPS time and the UTC. Note that GPS time is ahead of the UTC, which is called the leap seconds.
+-------+----------+-----------------------+---------+
| Field | Type | Description | Content |
+=======+==========+=======================+=========+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+----------+-----------------------+---------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+----------+-----------------------+---------+
| 3 | uint8_t | Message type | 0x05 |
+-------+----------+-----------------------+---------+
| 4 | uint8_t | Message sub-ID | 0x18 |
+-------+----------+-----------------------+---------+
| 5 | uint16_t | Payload length | 1 |
+-------+----------+-----------------------+---------+
| 6 | uint8_t | GPS - UTC time offset | seconds |
+-------+----------+-----------------------+---------+
| 7 | uint8_t | Checksum A | |
+-------+----------+-----------------------+---------+
| 8 | uint8_t | Checksum B | |
+-------+----------+-----------------------+---------+
5.25. NMEA GGA Message
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
This is the NMEA GGA message generated by the primary GNSS receiver.
6. System Diagnostic Messages
------------------------
6.1. Text Message
~~~~~~~~~~~~~~~~~~~~~~~~
+-------+----------+----------------+---------+
| Field | Type | Description | Content |
+=======+==========+================+=========+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+----------+----------------+---------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+----------+----------------+---------+
| 3 | uint8_t | Message type | 0x07 |
+-------+----------+----------------+---------+
| 4 | uint8_t | Message sub-ID | 0x00 |
+-------+----------+----------------+---------+
| 5 | uint16_t | Payload length | N |
+-------+----------+----------------+---------+
| 6 | char[N] | Text | |
+-------+----------+----------------+---------+
| 7 | uint8_t | Checksum A | |
+-------+----------+----------------+---------+
| 8 | uint8_t | Checksum B | |
+-------+----------+----------------+---------+
6.2. Sensor Message Count
~~~~~~~~~~~~~~~~~~~~~~~~
This message indicates the activity of each sub-system thus it can be used to monitor the system.
+-------+-------------+--------------------+---------+
| Field | Type | Description | Content |
+=======+=============+====================+=========+
| 1 | uint8_t | Sync 1 | 0xAF |
+-------+-------------+--------------------+---------+
| 2 | uint8_t | Sync 2 | 0x20 |
+-------+-------------+--------------------+---------+
| 3 | uint8_t | Message type | 0x07 |
+-------+-------------+--------------------+---------+
| 4 | uint8_t | Message sub-ID | 0x01 |
+-------+-------------+--------------------+---------+
| 5 | uint16_t | Payload length | 16 |
+-------+-------------+--------------------+---------+
| 6 | uint16_t | IMU message count | |
+-------+-------------+--------------------+---------+
| 7 | uint16_t | GNSS message count | |
+-------+-------------+--------------------+---------+
| 8 | uint16_t | PPS count | |
+-------+-------------+--------------------+---------+
| 9 | uint16_t[5] | Reserved | |
+-------+-------------+--------------------+---------+
| 10 | uint8_t | Checksum A | |
+-------+-------------+--------------------+---------+
| 11 | uint8_t | Checksum B | |
+-------+-------------+--------------------+---------+
7. External Event Messages
------------------------