data_sets.h
Go to the documentation of this file.
1 /*
2 MIT LICENSE
3 
4 Copyright (c) 2014-2020 Inertial Sense, Inc. - http://inertialsense.com
5 
6 Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files(the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions :
7 
8 The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
9 
10 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
11 */
12 
13 #ifndef DATA_SETS_H
14 #define DATA_SETS_H
15 
16 #include <stdint.h>
17 #include <stdlib.h>
18 #include <time.h>
19 #include <string.h>
20 #include "ISConstants.h"
21 
22 #ifdef __cplusplus
23 extern "C" {
24 #endif
25 
26 // *****************************************************************************
27 // ****** InertialSense binary message Data Identification Numbers (DIDs) ******
28 // ****** ******
29 // ****** NEVER REORDER THESE VALUES! ******
30 // *****************************************************************************
32 typedef uint32_t eDataIDs;
33 
34 #define DID_NULL (eDataIDs)0
35 #define DID_DEV_INFO (eDataIDs)1
36 #define DID_SYS_FAULT (eDataIDs)2
37 #define DID_PREINTEGRATED_IMU (eDataIDs)3
38 #define DID_INS_1 (eDataIDs)4
39 #define DID_INS_2 (eDataIDs)5
40 #define DID_GPS1_UBX_POS (eDataIDs)6
41 #define DID_SYS_CMD (eDataIDs)7
42 #define DID_ASCII_BCAST_PERIOD (eDataIDs)8
43 #define DID_RMC (eDataIDs)9
44 #define DID_SYS_PARAMS (eDataIDs)10
45 #define DID_SYS_SENSORS (eDataIDs)11
46 #define DID_FLASH_CONFIG (eDataIDs)12
47 #define DID_GPS1_POS (eDataIDs)13
48 #define DID_GPS2_POS (eDataIDs)14
49 #define DID_GPS1_SAT (eDataIDs)15
50 #define DID_GPS2_SAT (eDataIDs)16
51 #define DID_GPS1_VERSION (eDataIDs)17
52 #define DID_GPS2_VERSION (eDataIDs)18
53 #define DID_MAG_CAL (eDataIDs)19
54 #define DID_INTERNAL_DIAGNOSTIC (eDataIDs)20
55 #define DID_GPS1_RTK_POS_REL (eDataIDs)21
56 #define DID_GPS1_RTK_POS_MISC (eDataIDs)22
57 #define DID_FEATURE_BITS (eDataIDs)23
58 #define DID_SENSORS_IS1 (eDataIDs)24
59 #define DID_SENSORS_IS2 (eDataIDs)25
60 #define DID_SENSORS_TC_BIAS (eDataIDs)26
61 #define DID_IO (eDataIDs)27
62 #define DID_SENSORS_ADC (eDataIDs)28
63 #define DID_SCOMP (eDataIDs)29
64 #define DID_GPS1_VEL (eDataIDs)30
65 #define DID_GPS2_VEL (eDataIDs)31
66 #define DID_HDW_PARAMS (eDataIDs)32
67 #define DID_NVR_MANAGE_USERPAGE (eDataIDs)33
68 #define DID_NVR_USERPAGE_SN (eDataIDs)34
69 #define DID_NVR_USERPAGE_G0 (eDataIDs)35
70 #define DID_NVR_USERPAGE_G1 (eDataIDs)36
71 #define DID_DEBUG_STRING (eDataIDs)37
72 #define DID_RTOS_INFO (eDataIDs)38
73 #define DID_DEBUG_ARRAY (eDataIDs)39
74 #define DID_SENSORS_CAL1 (eDataIDs)40
75 #define DID_SENSORS_CAL2 (eDataIDs)41
76 #define DID_CAL_SC (eDataIDs)42
77 #define DID_CAL_SC1 (eDataIDs)43
78 #define DID_CAL_SC2 (eDataIDs)44
79 #define DID_SYS_SENSORS_SIGMA (eDataIDs)45
80 #define DID_SENSORS_ADC_SIGMA (eDataIDs)46
81 #define DID_INS_DEV_1 (eDataIDs)47
82 #define DID_INL2_STATES (eDataIDs)48
83 #define DID_INL2_COVARIANCE_LD (eDataIDs)49
84 #define DID_INL2_STATUS (eDataIDs)50
85 #define DID_INL2_MISC (eDataIDs)51
86 #define DID_MAGNETOMETER_1 (eDataIDs)52
87 #define DID_BAROMETER (eDataIDs)53
88 #define DID_GPS1_RTK_POS (eDataIDs)54
89 #define DID_MAGNETOMETER_2 (eDataIDs)55
90 #define DID_COMMUNICATIONS_LOOPBACK (eDataIDs)56
91 #define DID_DUAL_IMU_RAW (eDataIDs)57
92 #define DID_DUAL_IMU (eDataIDs)58
93 #define DID_INL2_MAG_OBS_INFO (eDataIDs)59
94 #define DID_GPS_BASE_RAW (eDataIDs)60
95 #define DID_GPS_RTK_OPT (eDataIDs)61
96 #define DID_NVR_USERPAGE_INTERNAL (eDataIDs)62
97 #define DID_MANUFACTURING_INFO (eDataIDs)63
98 #define DID_BIT (eDataIDs)64
99 #define DID_INS_3 (eDataIDs)65
100 #define DID_INS_4 (eDataIDs)66
101 #define DID_INL2_NED_SIGMA (eDataIDs)67
102 #define DID_STROBE_IN_TIME (eDataIDs)68
103 #define DID_GPS1_RAW (eDataIDs)69
104 #define DID_GPS2_RAW (eDataIDs)70
105 #define DID_WHEEL_ENCODER (eDataIDs)71
106 #define DID_DIAGNOSTIC_MESSAGE (eDataIDs)72
107 #define DID_SURVEY_IN (eDataIDs)73
108 #define DID_CAL_SC_INFO (eDataIDs)74
109 #define DID_PORT_MONITOR (eDataIDs)75
110 #define DID_RTK_STATE (eDataIDs)76
111 #define DID_RTK_PHASE_RESIDUAL (eDataIDs)77
112 #define DID_RTK_CODE_RESIDUAL (eDataIDs)78
113 #define DID_RTK_DEBUG (eDataIDs)79
114 #define DID_EVB_STATUS (eDataIDs)80
115 #define DID_EVB_FLASH_CFG (eDataIDs)81
116 #define DID_EVB_DEBUG_ARRAY (eDataIDs)82
117 #define DID_EVB_RTOS_INFO (eDataIDs)83
118 #define DID_DUAL_IMU_RAW_MAG (eDataIDs)84
119 #define DID_DUAL_IMU_MAG (eDataIDs)85
120 #define DID_PREINTEGRATED_IMU_MAG (eDataIDs)86
121 #define DID_WHEEL_CONFIG (eDataIDs)87
122 #define DID_POSITION_MEASUREMENT (eDataIDs)88
123 #define DID_RTK_DEBUG_2 (eDataIDs)89
124 #define DID_CAN_CONFIG (eDataIDs)90
125 #define DID_GPS2_RTK_CMP_REL (eDataIDs)91
126 #define DID_GPS2_RTK_CMP_MISC (eDataIDs)92
127 #define DID_EVB_DEV_INFO (eDataIDs)93
129 // Adding a new data id?
130 // 1] Add it above and increment the previous number, include the matching data structure type in the comments
131 // 2] Add flip doubles and flip strings entries in data_sets.c
132 // 3] Add data id to ISDataMappings.cpp
133 // 4] Increment DID_COUNT
134 // 5) Update the DIDs in IS-src/python/src/ci_hdw/data_sets.py
135 // 6] Test!
136 
138 #define DID_COUNT (eDataIDs)96
139 
141 #define DID_MAX_COUNT 256
142 
143 // END DATA IDENTIFIERS --------------------------------------------------------------------------
144 
146 #define MAX_NUM_SAT_CHANNELS 50
147 
149 #define DEVINFO_MANUFACTURER_STRLEN 24
150 #define DEVINFO_ADDINFO_STRLEN 24
151 
152 
154 // #define PROTOCOL_VERSION_CHAR0 1 // Major (in com_manager.h)
155 // #define PROTOCOL_VERSION_CHAR1 0
156 #define PROTOCOL_VERSION_CHAR2 (0x000000FF&DID_COUNT)
157 #define PROTOCOL_VERSION_CHAR3 8 // Minor (in data_sets.h)
158 
160 #define RECEIVER_INDEX_GPS1 1 // DO NOT CHANGE
161 #define RECEIVER_INDEX_EXTERNAL_BASE 2 // DO NOT CHANGE
162 #define RECEIVER_INDEX_GPS2 3 // DO NOT CHANGE
163 
164 #define NUM_IMU_DEVICES 2
165 
168 {
170  INS_STATUS_ATT_ALIGN_COARSE = (int)0x00000001,
172  INS_STATUS_VEL_ALIGN_COARSE = (int)0x00000002,
174  INS_STATUS_POS_ALIGN_COARSE = (int)0x00000004,
176  INS_STATUS_ALIGN_COARSE_MASK = (int)0x00000007,
177 
178  INS_STATUS_UNUSED_1 = (int)0x00000008,
179 
181  INS_STATUS_ATT_ALIGN_FINE = (int)0x00000010,
183  INS_STATUS_VEL_ALIGN_FINE = (int)0x00000020,
185  INS_STATUS_POS_ALIGN_FINE = (int)0x00000040,
187  INS_STATUS_ALIGN_FINE_MASK = (int)0x00000070,
188 
190  INS_STATUS_GPS_AIDING_HEADING = (int)0x00000080,
191 
193  INS_STATUS_GPS_AIDING_POS_VEL = (int)0x00000100,
197  INS_STATUS_RESERVED_1 = (int)0x00000400,
199  INS_STATUS_MAG_AIDING_HEADING = (int)0x00000800,
200 
202  INS_STATUS_NAV_MODE = (int)0x00001000,
203 
205  INS_STATUS_DO_NOT_MOVE = (int)0x00002000,
206 
207  INS_STATUS_UNUSED_3 = (int)0x00004000,
208  INS_STATUS_UNUSED_4 = (int)0x00008000,
209 
211  INS_STATUS_SOLUTION_MASK = (int)0x000F0000,
214 
215  INS_STATUS_SOLUTION_OFF = 0, // System is off
216  INS_STATUS_SOLUTION_ALIGNING = 1, // System is in alignment mode
217  INS_STATUS_SOLUTION_ALIGNMENT_COMPLETE = 2, // System is aligned but not enough dynamics have been experienced to be with specifications.
218  INS_STATUS_SOLUTION_NAV = 3, // System is in navigation mode and solution is good.
219  INS_STATUS_SOLUTION_NAV_HIGH_VARIANCE = 4, // System is in navigation mode but the attitude uncertainty has exceeded the threshold.
220  INS_STATUS_SOLUTION_AHRS = 5, // System is in AHRS mode and solution is good.
221  INS_STATUS_SOLUTION_AHRS_HIGH_VARIANCE = 6, // System is in AHRS mode but the attitude uncertainty has exceeded the threshold.
222 
228 
230  INS_STATUS_MAG_RECALIBRATING = (int)0x00400000,
233 
235  INS_STATUS_GPS_NAV_FIX_MASK = (int)0x03000000,
237 #define INS_STATUS_NAV_FIX_STATUS(insStatus) ((insStatus&INS_STATUS_GPS_NAV_FIX_MASK)>>INS_STATUS_GPS_NAV_FIX_OFFSET)
238 
241 
242  /* NOTE: If you add or modify these INS_STATUS_RTK_ values, please update eInsStatusRtkBase in IS-src/python/src/ci_hdw/data_sets.py */
252  INS_STATUS_RTK_ERR_BASE_MASK = (int)0x30000000,
255 
259  INS_STATUS_GENERAL_FAULT = (int)0x80000000,
260 
263 };
264 
266 /* NOTE: If you modify this enum, please also modify the eGpsNavFixStatus enum
267  * in IS-src/python/src/ci_hdw/data_sets.py */
269 {
270  GPS_NAV_FIX_NONE = (int)0x00000000,
271  GPS_NAV_FIX_POSITIONING_3D = (int)0x00000001,
273  GPS_NAV_FIX_POSITIONING_RTK_FIX = (int)0x00000003, // Includes fix & hold
274 };
275 
278 {
280  HDW_STATUS_MOTION_GYR_SIG = (int)0x00000001,
282  HDW_STATUS_MOTION_ACC_SIG = (int)0x00000002,
284  HDW_STATUS_MOTION_SIG_MASK = (int)0x00000003,
286  HDW_STATUS_MOTION_GYR_DEV = (int)0x00000004,
288  HDW_STATUS_MOTION_ACC_DEV = (int)0x00000008,
290  HDW_STATUS_MOTION_MASK = (int)0x0000000F,
291 
293  HDW_STATUS_GPS_SATELLITE_RX = (int)0x00000010,
295  HDW_STATUS_STROBE_IN_EVENT = (int)0x00000020,
298 
299  HDW_STATUS_UNUSED_1 = (int)0x00000080,
300 
302  HDW_STATUS_SATURATION_GYR = (int)0x00000100,
304  HDW_STATUS_SATURATION_ACC = (int)0x00000200,
306  HDW_STATUS_SATURATION_MAG = (int)0x00000400,
308  HDW_STATUS_SATURATION_BARO = (int)0x00000800,
309 
311  HDW_STATUS_SATURATION_MASK = (int)0x00000F00,
314 
317 
318  HDW_STATUS_UNUSED_3 = (int)0x00002000,
319  HDW_STATUS_UNUSED_4 = (int)0x00004000,
320  HDW_STATUS_UNUSED_5 = (int)0x00008000,
321 
323  HDW_STATUS_ERR_COM_TX_LIMITED = (int)0x00010000,
325  HDW_STATUS_ERR_COM_RX_OVERRUN = (int)0x00020000,
326 
330 #define HDW_STATUS_COM_PARSE_ERROR_COUNT(hdwStatus) ((hdwStatus&HDW_STATUS_COM_PARSE_ERR_COUNT_MASK)>>HDW_STATUS_COM_PARSE_ERR_COUNT_OFFSET)
331 
333  HDW_STATUS_BIT_FAULT = (int)0x01000000,
335  HDW_STATUS_ERR_TEMPERATURE = (int)0x02000000,
337 // HDW_STATUS_ERR_VIBRATION = (int)0x04000000,
338 
339  HDW_STATUS_UNUSED_6 = (int)0x08000000,
340 
342  HDW_STATUS_FAULT_RESET_MASK = (int)0x70000000,
348  HDW_STATUS_FAULT_RESET_SOFT = (int)0x30000000,
350  HDW_STATUS_FAULT_RESET_HDW = (int)0x40000000,
351 
353  HDW_STATUS_FAULT_SYS_CRITICAL = (int)0x80000000,
354 
357 };
358 
361 {
362  GPS_STATUS_NUM_SATS_USED_MASK = (int)0x000000FF,
363 
365  GPS_STATUS_FIX_NONE = (int)0x00000000,
367  GPS_STATUS_FIX_2D = (int)0x00000200,
368  GPS_STATUS_FIX_3D = (int)0x00000300,
370  GPS_STATUS_FIX_TIME_ONLY = (int)0x00000500,
371  GPS_STATUS_FIX_UNUSED1 = (int)0x00000600,
372  GPS_STATUS_FIX_UNUSED2 = (int)0x00000700,
373  GPS_STATUS_FIX_DGPS = (int)0x00000800,
374  GPS_STATUS_FIX_SBAS = (int)0x00000900,
375  GPS_STATUS_FIX_RTK_SINGLE = (int)0x00000A00,
376  GPS_STATUS_FIX_RTK_FLOAT = (int)0x00000B00,
377  GPS_STATUS_FIX_RTK_FIX = (int)0x00000C00,
378  GPS_STATUS_FIX_MASK = (int)0x00001F00,
380 
382  GPS_STATUS_FLAGS_FIX_OK = (int)0x00010000, // within limits (e.g. DOP & accuracy)
383  GPS_STATUS_FLAGS_DGPS_USED = (int)0x00020000, // Differential GPS (DGPS) used.
384  GPS_STATUS_FLAGS_RTK_FIX_AND_HOLD = (int)0x00040000, // RTK feedback on the integer solutions to drive the float biases towards the resolved integers
385 // GPS_STATUS_FLAGS_WEEK_VALID = (int)0x00040000,
386 // GPS_STATUS_FLAGS_TOW_VALID = (int)0x00080000,
387  GPS_STATUS_FLAGS_RTK_POSITION_ENABLED = (int)0x00100000, // RTK precision positioning mode enabled
388  GPS_STATUS_FLAGS_STATIC_MODE = (int)0x00200000, // Static mode
389  GPS_STATUS_FLAGS_RTK_COMPASSING_ENABLED = (int)0x00400000, // RTK moving base mode enabled
390  GPS_STATUS_FLAGS_RTK_RAW_GPS_DATA_ERROR = (int)0x00800000, // RTK error: observations or ephemeris are invalid or not received (i.e. RTK differential corrections)
391  GPS_STATUS_FLAGS_RTK_BASE_DATA_MISSING = (int)0x01000000, // RTK error: Either base observations or antenna position have not been received.
392  GPS_STATUS_FLAGS_RTK_BASE_POSITION_MOVING = (int)0x02000000, // RTK error: base position moved when it should be stationary
393  GPS_STATUS_FLAGS_RTK_BASE_POSITION_INVALID = (int)0x03000000, // RTK error: base position is invalid or not surveyed well
394  GPS_STATUS_FLAGS_RTK_BASE_POSITION_MASK = (int)0x03000000, // RTK error: base position error bitmask
397  GPS_STATUS_FLAGS_RTK_POSITION_VALID = (int)0x04000000, // RTK precision position is valid on GPS1 (i.e. < 20cm accuracy)
398  GPS_STATUS_FLAGS_RTK_COMPASSING_VALID = (int)0x08000000, // RTK moving base heading is valid on GPS2
405  GPS_STATUS_FLAGS_GPS_NMEA_DATA = (int)0x00008000, // 1 = Data from NMEA message
406  GPS_STATUS_FLAGS_MASK = (int)0x0FFFE000,
408 
409 };
410 
412 
414 typedef struct PACKED
415 {
417  double timeOfWeek;
418 
420  double ecef[3];
421 
423  float psi;
424 
426  float accuracyCovUD[6]; // Matrix accuracyCovUD Described below
427  // 0 1 2
428  // _ 3 4
429  // _ _ 5
430 
431 
433 
434 
436 typedef struct PACKED
437 {
439  uint32_t reserved;
440 
442  uint32_t serialNumber;
443 
445  uint8_t hardwareVer[4];
446 
448  uint8_t firmwareVer[4];
449 
451  uint32_t buildNumber;
452 
454  uint8_t protocolVer[4];
455 
457  uint32_t repoRevision;
458 
461 
463  uint8_t buildDate[4];
464 
466  uint8_t buildTime[4];
467 
470 } dev_info_t;
471 
473 typedef struct PACKED
474 {
476  uint32_t serialNumber;
477 
479  uint32_t lotNumber;
480 
482  char date[16];
483 
485  uint32_t key;
487 
488 
490 typedef struct PACKED
491 {
493  uint32_t week;
494 
496  double timeOfWeek;
497 
499  uint32_t insStatus;
500 
502  uint32_t hdwStatus;
503 
505  float theta[3];
506 
508  float uvw[3];
509 
511  double lla[3];
512 
514  float ned[3];
515 } ins_1_t;
516 
517 
519 typedef struct PACKED
520 {
522  uint32_t week;
523 
525  double timeOfWeek;
526 
528  uint32_t insStatus;
529 
531  uint32_t hdwStatus;
532 
534  float qn2b[4];
535 
537  float uvw[3];
538 
540  double lla[3];
541 } ins_2_t;
542 
543 
545 typedef struct PACKED
546 {
548  uint32_t week;
549 
551  double timeOfWeek;
552 
554  uint32_t insStatus;
555 
557  uint32_t hdwStatus;
558 
560  float qn2b[4];
561 
563  float uvw[3];
564 
566  double lla[3];
567 
569  float msl;
570 } ins_3_t;
571 
572 
574 typedef struct PACKED
575 {
577  uint32_t week;
578 
580  double timeOfWeek;
581 
583  uint32_t insStatus;
584 
586  uint32_t hdwStatus;
587 
589  float qe2b[4];
590 
592  float ve[3];
593 
595  double ecef[3];
596 } ins_4_t;
597 
598 
600 typedef struct PACKED
601 {
603  float pqr[3];
604 
606  float acc[3];
607 } imus_t;
608 
609 
611 typedef struct PACKED
612 {
614  double time;
615 
618 } imu_t;
619 
620 
622 typedef struct PACKED
623 {
625  double time;
626 
628  imus_t I[2];
629 
631  uint32_t status;
632 } dual_imu_t;
633 
634 
636 typedef struct PACKED
637 {
639  double time;
640 
642  float mag[3];
644 
645 
647 typedef struct PACKED
648 {
650  double time;
651 
653  float bar;
654 
656  float mslBar;
657 
659  float barTemp;
660 
662  float humidity;
663 } barometer_t;
664 
665 
667 typedef struct PACKED
668 {
670  double time;
671 
673  float theta1[3];
674 
676  float theta2[3];
677 
679  float vel1[3];
680 
682  float vel2[3];
683 
685  float dt;
686 
688  uint32_t status;
690 
691 
693 typedef struct PACKED
694 {
697 
701 } imu_mag_t;
702 
703 
705 typedef struct PACKED
706 {
709 
713 } pimu_mag_t;
714 
715 
718 {
727 
729  IMU_STATUS_RESERVED1 = (int)0x00000020,
730 
732  IMU_STATUS_RESERVED2 = (int)0x00000040,
733 
734 // /** Sensor saturation happened within past 10 seconds */
735 // IMU_STATUS_SATURATION_HISTORY = (int)0x00000100,
736 // /** Sample rate fault happened within past 10 seconds */
737 // IMU_STATUS_SAMPLE_RATE_FAULT_HISTORY = (int)0x00000200,
738 };
739 
741 typedef struct PACKED
742 {
744  uint32_t week;
745 
747  uint32_t timeOfWeekMs;
748 
750  uint32_t status;
751 
753  double ecef[3];
754 
756  double lla[3];
757 
759  float hMSL;
760 
762  float hAcc;
763 
765  float vAcc;
766 
768  float pDop;
769 
771  float cnoMean;
772 
774  double towOffset;
775 
777  uint8_t leapS;
778 
780  uint8_t reserved[3];
781 
782 } gps_pos_t;
783 
784 
786 typedef struct PACKED
787 {
789  uint32_t timeOfWeekMs;
790 
793  float vel[3];
794 
796  float sAcc;
797 
799  uint32_t status;
800 } gps_vel_t;
801 
802 
804 typedef struct PACKED
805 {
807  uint8_t gnssId;
808 
810  uint8_t svId;
811 
813  uint8_t cno;
814 
816  int8_t elev;
817 
819  int16_t azim;
820 
822  int16_t prRes;
823 
825  uint32_t flags;
826 } gps_sat_sv_t;
827 
828 
831 {
833  SAT_SV_FLAGS_SV_USED = 0x00000008,
836  SAT_SV_FLAGS_DIFFCORR = 0x00000040,
837  SAT_SV_FLAGS_SMOOTHED = 0x00000080,
840  SAT_SV_FLAGS_EPHAVAIL = 0x00000800,
841  SAT_SV_FLAGS_ALMAVAIL = 0x00001000,
842  SAT_SV_FLAGS_ANOAVAIL = 0x00002000,
843  SAT_SV_FLAGS_AOPAVAIL = 0x00004000,
844 
845  SAT_SV_FLAGS_RTK_SOL_FIX_STATUS_MASK = 0x03000000, // 1=float, 2=fix, 3=hold
850 };
851 
853 typedef struct PACKED
854 {
856  uint32_t timeOfWeekMs;
858  uint32_t numSats;
861 } gps_sat_t;
862 
863 
865 typedef struct PACKED
866 {
868  uint8_t swVersion[30];
870  uint8_t hwVersion[10];
872  uint8_t extension[30];
874  uint8_t reserved[2];
875 } gps_version_t;
876 
877 // (DID_INL2_STATES) INL2 - INS Extended Kalman Filter (EKF) states
878 typedef struct PACKED
879 {
881  double timeOfWeek;
882 
884  float qe2b[4];
885 
887  float ve[3];
888 
890  double ecef[3];
891 
893  float biasPqr[3];
894 
896  float biasAcc[3];
897 
899  float biasBaro;
900 
902  float magDec;
903 
905  float magInc;
906 } inl2_states_t;
907 
908 typedef struct PACKED
909 {
910  int ahrs;
915  int zero_vel;
916  int ahrs_gps_cnt; // Counter of sequential valid GPS data (for switching from AHRS to navigation)
917  float att_err;
918  int att_coarse; // Flag whether initial attitude error converged
919  int att_aligned; // Flag whether initial attitude error converged
921  int start_proc_done; // Cold/hot start procedure completed
925 } inl2_status_t;
926 
928 typedef struct PACKED
929 {
931  double time;
932 
934  float val;
936 
938 typedef struct PACKED
939 {
941  double time;
942 
944  float val[3];
946 
948 typedef struct PACKED
949 {
951  double time;
952 
954  float val1[3];
955 
957  float val2[3];
959 
961 typedef struct PACKED
962 {
964  double time;
965 
967  double val[3];
969 
971 typedef struct PACKED
972 {
974  double time;
975 
977  float temp;
978 
980  float pqr[3];
981 
983  float acc[3];
984 
986  float mag[3];
987 
989  float bar;
990 
992  float barTemp;
993 
995  float mslBar;
996 
998  float humidity;
999 
1001  float vin;
1002 
1004  float ana1;
1005 
1007  float ana3;
1008 
1010  float ana4;
1011 } sys_sensors_t;
1012 
1014 typedef struct PACKED
1015 {
1017  uint32_t timeOfWeekMs;
1018 
1020  double lla[3];
1021 
1023  float uvw[3];
1024 
1026  float qn2b[4];
1027 } ins_output_t;
1028 
1030 typedef struct PACKED
1031 {
1033  uint32_t timeOfWeekMs;
1034 
1036  uint32_t insStatus;
1037 
1039  uint32_t hdwStatus;
1040 
1042  float imuTemp;
1043 
1045  float baroTemp;
1046 
1048  float mcuTemp;
1049 
1051  float reserved1;
1052 
1054  uint32_t imuPeriodMs;
1055 
1057  uint32_t navPeriodMs;
1058 
1061 
1063  float reserved2[2];
1064 
1066  uint32_t genFaultCode;
1067 } sys_params_t;
1068 
1071 {
1081  GFC_INIT_SENSORS = 0x00000100,
1083  GFC_INIT_SPI = 0x00000200,
1085  GFC_CONFIG_SPI = 0x00000400,
1087  GFC_INIT_GPS1 = 0x00000800,
1089  GFC_INIT_GPS2 = 0x00001000,
1102 };
1103 
1104 
1106 typedef struct PACKED
1107 {
1109  uint32_t command;
1110 
1112  uint32_t invCommand;
1113 
1115 
1117 {
1123 
1128  SYS_CMD_MANF_UNLOCK = 1122334455,
1129  SYS_CMD_MANF_FACTORY_RESET = 1357924680, // SYS_CMD_MANF_RESET_UNLOCK must be sent prior to this command.
1130  SYS_CMD_MANF_CHIP_ERASE = 1357924681, // SYS_CMD_MANF_RESET_UNLOCK must be sent prior to this command.
1131 };
1132 
1133 
1134 
1136 typedef struct PACKED
1137 {
1139  uint32_t options;
1140 
1142  uint32_t pimu;
1143 
1145  uint32_t ppimu;
1146 
1148  uint32_t pins1;
1149 
1151  uint32_t pins2;
1152 
1154  uint32_t pgpsp;
1155 
1157  uint32_t reserved;
1158 
1160  uint32_t gpgga;
1161 
1163  uint32_t gpgll;
1164 
1166  uint32_t gpgsa;
1167 
1169  uint32_t gprmc;
1170 
1172  uint32_t gpzda;
1173 
1175  uint32_t pashr;
1176 
1177 } ascii_msgs_t;
1178 
1179 /* (DID_SENSORS_CAL1, DID_SENSORS_CAL2) */
1180 typedef struct PACKED
1181 { // Units only apply for calibrated data
1182  f_t pqr[3]; // (rad/s) Angular rate
1183  f_t acc[3]; // (m/s^2) Linear acceleration
1184  f_t mag[3]; // (uT) Magnetometers
1185  f_t temp; // (°C) Temperature of MPU
1187 
1188 #define NUM_ANA_CHANNELS 4
1189 typedef struct PACKED
1190 { // LSB units for all except temperature, which is Celsius.
1191  double time;
1193  f_t bar; // Barometric pressure
1194  f_t barTemp; // Temperature of barometric pressure sensor
1195  f_t humidity; // Relative humidity as a percent (%rH). Range is 0% - 100%
1196  f_t ana[NUM_ANA_CHANNELS]; // ADC analog input
1198 
1199 #define NUM_COM_PORTS 3 // Number of communication ports. (Ser0, Ser1, and USB).
1200 #ifndef NUM_SERIAL_PORTS
1201 #define NUM_SERIAL_PORTS 5
1202 #endif
1203 
1211 #define RMC_OPTIONS_PORT_MASK 0x000000FF
1212 #define RMC_OPTIONS_PORT_ALL (RMC_OPTIONS_PORT_MASK)
1213 #define RMC_OPTIONS_PORT_CURRENT 0x00000000
1214 #define RMC_OPTIONS_PORT_SER0 0x00000001
1215 #define RMC_OPTIONS_PORT_SER1 0x00000002 // also SPI
1216 #define RMC_OPTIONS_PORT_USB 0x00000004
1217 #define RMC_OPTIONS_PRESERVE_CTRL 0x00000100 // Prevent any messages from getting turned off by bitwise OR'ing new message bits with current message bits.
1218 #define RMC_OPTIONS_PERSISTENT 0x00000200 // Save current port RMC to flash memory for use following reboot, eliminating need to re-enable RMC to start data streaming.
1219 
1220 // RMC message data rates:
1221 #define RMC_BITS_INS1 0x0000000000000001 // rmc.insPeriodMs (4ms default)
1222 #define RMC_BITS_INS2 0x0000000000000002 // "
1223 #define RMC_BITS_INS3 0x0000000000000004 // "
1224 #define RMC_BITS_INS4 0x0000000000000008 // "
1225 #define RMC_BITS_DUAL_IMU 0x0000000000000010 // DID_FLASH_CONFIG.startupNavDtMs (4ms default)
1226 #define RMC_BITS_PREINTEGRATED_IMU 0x0000000000000020 // "
1227 #define RMC_BITS_BAROMETER 0x0000000000000040 // ~8ms
1228 #define RMC_BITS_MAGNETOMETER1 0x0000000000000080 // ~10ms
1229 #define RMC_BITS_MAGNETOMETER2 0x0000000000000100 // "
1230 
1231 #define RMC_BITS_GPS1_POS 0x0000000000000400 // DID_FLASH_CONFIG.startupGpsDtMs (200ms default)
1232 #define RMC_BITS_GPS2_POS 0x0000000000000800 // "
1233 #define RMC_BITS_GPS1_RAW 0x0000000000001000 // "
1234 #define RMC_BITS_GPS2_RAW 0x0000000000002000 // "
1235 #define RMC_BITS_GPS1_SAT 0x0000000000004000 // 1s
1236 #define RMC_BITS_GPS2_SAT 0x0000000000008000 // "
1237 #define RMC_BITS_GPS_BASE_RAW 0x0000000000010000 //
1238 #define RMC_BITS_STROBE_IN_TIME 0x0000000000020000 // On strobe input event
1239 #define RMC_BITS_DIAGNOSTIC_MESSAGE 0x0000000000040000
1240 #define RMC_BITS_DUAL_IMU_RAW 0x0000000000080000 // DID_FLASH_CONFIG.startupImuDtMs (1ms default)
1241 #define RMC_BITS_GPS1_VEL 0x0000000000100000 // DID_FLASH_CONFIG.startupGpsDtMs (200ms default)
1242 #define RMC_BITS_GPS2_VEL 0x0000000000200000 // "
1243 #define RMC_BITS_GPS1_UBX_POS 0x0000000000400000 // "
1244 #define RMC_BITS_GPS1_RTK_POS 0x0000000000800000 // "
1245 #define RMC_BITS_GPS1_RTK_POS_REL 0x0000000001000000 // "
1246 #define RMC_BITS_GPS1_RTK_POS_MISC 0x0000000004000000 // "
1247 #define RMC_BITS_INL2_NED_SIGMA 0x0000000008000000
1248 #define RMC_BITS_RTK_STATE 0x0000000010000000
1249 #define RMC_BITS_RTK_CODE_RESIDUAL 0x0000000020000000
1250 #define RMC_BITS_RTK_PHASE_RESIDUAL 0x0000000040000000
1251 #define RMC_BITS_WHEEL_ENCODER 0x0000000080000000
1252 #define RMC_BITS_WHEEL_CONFIG 0x0000000100000000
1253 #define RMC_BITS_DUAL_IMU_MAG_RAW 0x0000000200000000
1254 #define RMC_BITS_DUAL_IMU_MAG 0x0000000400000000
1255 #define RMC_BITS_PREINTEGRATED_IMU_MAG 0x0000000800000000
1256 #define RMC_BITS_GPS1_RTK_HDG_REL 0x0000001000000000 // DID_FLASH_CONFIG.startupGpsDtMs (200ms default)
1257 #define RMC_BITS_GPS1_RTK_HDG_MISC 0x0000002000000000 // "
1258 #define RMC_BITS_MASK 0x0FFFFFFFFFFFFFFF
1259 #define RMC_BITS_INTERNAL_PPD 0x4000000000000000 //
1260 #define RMC_BITS_PRESET 0x8000000000000000 // Indicate BITS is a preset
1261 
1262 #define RMC_PRESET_PPD_NAV_PERIOD_MULT 25
1263 #define RMC_PRESET_INS_NAV_PERIOD_MULT 1 // fastest rate (nav filter update rate)
1264 
1265 // Preset: Post Processing Data
1266 #define RMC_PRESET_PPD_BITS_NO_IMU (RMC_BITS_PRESET \
1267  | RMC_BITS_INS2 \
1268  | RMC_BITS_BAROMETER \
1269  | RMC_BITS_MAGNETOMETER1 \
1270  | RMC_BITS_MAGNETOMETER2 \
1271  | RMC_BITS_GPS1_POS \
1272  | RMC_BITS_GPS2_POS \
1273  | RMC_BITS_GPS1_VEL \
1274  | RMC_BITS_GPS2_VEL \
1275  | RMC_BITS_GPS1_RAW \
1276  | RMC_BITS_GPS2_RAW \
1277  | RMC_BITS_GPS_BASE_RAW \
1278  | RMC_BITS_GPS1_RTK_POS_REL \
1279  | RMC_BITS_GPS1_RTK_HDG_REL \
1280  | RMC_BITS_INTERNAL_PPD \
1281  | RMC_BITS_DIAGNOSTIC_MESSAGE)
1282 #define RMC_PRESET_PPD_BITS (RMC_PRESET_PPD_BITS_NO_IMU \
1283  | RMC_BITS_PREINTEGRATED_IMU)
1284 #define RMC_PRESET_INS_BITS (RMC_BITS_INS2 \
1285  | RMC_BITS_GPS1_POS \
1286  | RMC_BITS_PRESET)
1287 #define RMC_PRESET_PPD_BITS_RAW_IMU (RMC_PRESET_PPD_BITS_NO_IMU \
1288  | RMC_BITS_DUAL_IMU_RAW)
1289 #define RMC_PRESET_PPD_BITS_RTK_DBG (RMC_PRESET_PPD_BITS \
1290  | RMC_BITS_RTK_STATE \
1291  | RMC_BITS_RTK_CODE_RESIDUAL \
1292  | RMC_BITS_RTK_PHASE_RESIDUAL)
1293 #define RMC_PRESET_PPD_ROBOT (RMC_PRESET_PPD_BITS\
1294  | RMC_BITS_WHEEL_ENCODER \
1295  | RMC_BITS_WHEEL_CONFIG)
1296 
1298 typedef struct PACKED
1299 {
1301  uint64_t bits;
1302 
1304  uint32_t options;
1305 
1307 } rmc_t;
1308 
1309 
1311 typedef struct PACKED
1312 {
1314  uint32_t timeOfWeekMs;
1315 
1317  uint32_t gpioStatus;
1318 } io_t;
1319 
1321 {
1323  MAG_RECAL_CMD_MULTI_AXIS = (int)1, // Recalibrate magnetometers using multiple axis
1324  MAG_RECAL_CMD_SINGLE_AXIS = (int)2, // Recalibrate magnetometers using only one axis
1325  MAG_RECAL_CMD_ABORT = (int)101, // Stop mag recalibration
1326 };
1327 
1329 typedef struct PACKED
1330 {
1332  uint32_t recalCmd;
1333 
1335  float progress;
1336 
1339 } mag_cal_t;
1340 
1341 typedef struct PACKED
1342 { // INL2 - Magnetometer observer info
1343  uint32_t timeOfWeekMs; // Timestamp in milliseconds
1344  uint32_t Ncal_samples;
1345  uint32_t ready; // Data ready to be processed
1346  uint32_t calibrated; // Calibration data present. Set to -1 to force mag recalibration.
1347  uint32_t auto_recal; // Allow mag to auto-recalibrate
1348  uint32_t outlier; // Bad sample data
1349  float magHdg; // Heading from magnetometer
1350  float insHdg; // Heading from INS
1351  float magInsHdgDelta; // Difference between mag heading and (INS heading plus mag declination)
1352  float nis; // Normalized innovation squared (likelihood metric)
1353  float nis_threshold; // Threshold for maximum NIS
1354  float Wcal[9]; // Magnetometer calibration matrix. Must be initialized with a unit matrix, not zeros!
1355  uint32_t activeCalSet; // active calibration set (0 or 1)
1356  float magHdgOffset; // Offset between magnetometer heading and estimate heading
1357  float Tcal; // Scaled computed variance between calibrated magnetometer samples.
1359 
1362 {
1363  BIT_STATE_OFF = (int)0,
1364  BIT_STATE_DONE = (int)1,
1365  BIT_STATE_CMD_FULL_STATIONARY = (int)2, // (FULL) More comprehensive test. Requires system be completely stationary without vibrations.
1366  BIT_STATE_CMD_BASIC_MOVING = (int)3, // (BASIC) Ignores sensor output. Can be run while moving. This mode is automatically run after bootup.
1372 };
1373 
1376 {
1377  HDW_BIT_PASSED_MASK = (int)0x0000000F,
1378  HDW_BIT_PASSED_ALL = (int)0x00000001,
1379  HDW_BIT_PASSED_NO_GPS = (int)0x00000002, // Passed w/o valid GPS signal
1380  HDW_BIT_MODE_MASK = (int)0x000000F0, // BIT mode run
1383  HDW_BIT_FAILED_MASK = (int)0xFFFFFF00,
1384  HDW_BIT_FAILED_AHRS_MASK = (int)0xFFFF0F00,
1385  HDW_BIT_FAULT_NOISE_PQR = (int)0x00000100,
1386  HDW_BIT_FAULT_NOISE_ACC = (int)0x00000200,
1387  HDW_BIT_FAULT_MAGNETOMETER = (int)0x00000400,
1388  HDW_BIT_FAULT_BAROMETER = (int)0x00000800,
1389  HDW_BIT_FAULT_GPS_NO_COM = (int)0x00001000, // No GPS serial communications
1390  HDW_BIT_FAULT_GPS_POOR_CNO = (int)0x00002000, // Poor GPS signal strength. Check antenna
1391  HDW_BIT_FAULT_GPS_POOR_ACCURACY = (int)0x00002000, // Low number of satellites, or bad accuracy
1392  HDW_BIT_FAULT_GPS_NOISE = (int)0x00004000, // (Not implemented)
1393 };
1394 
1397 {
1398  CAL_BIT_PASSED_MASK = (int)0x0000000F,
1399  CAL_BIT_PASSED_ALL = (int)0x00000001,
1400  CAL_BIT_MODE_MASK = (int)0x000000F0, // BIT mode run
1402 #define CAL_BIT_MODE(calBitStatus) ((calBitStatus&CAL_BIT_MODE_MASK)>>CAL_BIT_MODE_OFFSET)
1403  CAL_BIT_FAILED_MASK = (int)0xFFFFFF00,
1404  CAL_BIT_FAULT_TCAL_EMPTY = (int)0x00000100, // Temperature calibration not present
1405  CAL_BIT_FAULT_TCAL_TSPAN = (int)0x00000200, // Temperature calibration temperature range is inadequate
1406  CAL_BIT_FAULT_TCAL_INCONSISTENT = (int)0x00000400, // Temperature calibration number of points or slopes are not consistent
1407  CAL_BIT_FAULT_TCAL_CORRUPT = (int)0x00000800, // Temperature calibration memory corruption
1408  CAL_BIT_FAULT_TCAL_PQR_BIAS = (int)0x00001000, // Temperature calibration gyro bias
1409  CAL_BIT_FAULT_TCAL_PQR_SLOPE = (int)0x00002000, // Temperature calibration gyro slope
1410  CAL_BIT_FAULT_TCAL_PQR_LIN = (int)0x00004000, // Temperature calibration gyro linearity
1411  CAL_BIT_FAULT_TCAL_ACC_BIAS = (int)0x00008000, // Temperature calibration accelerometer bias
1412  CAL_BIT_FAULT_TCAL_ACC_SLOPE = (int)0x00010000, // Temperature calibration accelerometer slope
1413  CAL_BIT_FAULT_TCAL_ACC_LIN = (int)0x00020000, // Temperature calibration accelerometer linearity
1414  CAL_BIT_FAULT_CAL_SERIAL_NUM = (int)0x00040000, // Calibration info: wrong device serial number
1415  CAL_BIT_FAULT_ORTO_EMPTY = (int)0x00100000, // Cross-axis alignment is not calibrated
1416  CAL_BIT_FAULT_ORTO_INVALID = (int)0x00200000, // Cross-axis alignment is poorly formed
1417  CAL_BIT_FAULT_MOTION_PQR = (int)0x00400000, // Motion on gyros
1418  CAL_BIT_FAULT_MOTION_ACC = (int)0x00800000, // Motion on accelerometers
1419 };
1420 
1421 
1423 typedef struct PACKED
1424 {
1426  uint32_t state;
1427 
1429  uint32_t hdwBitStatus;
1430 
1432  uint32_t calBitStatus;
1433 
1435  float tcPqrBias;
1436  float tcAccBias;
1437 
1439  float tcPqrSlope;
1440  float tcAccSlope;
1441 
1445 
1447  float pqr;
1448 
1450  float acc;
1451 
1453  float pqrSigma;
1454 
1456  float accSigma;
1457 
1458 } bit_t;
1459 
1460 
1463 {
1468  SYS_CFG_BITS_AUTO_MAG_RECAL = (int)0x00000004,
1471 
1473  SYS_CFG_BITS_DISABLE_LEDS = (int)0x00000010,
1474 
1478 #define SYS_CFG_BITS_MAG_RECAL_MODE(sysCfgBits) ((sysCfgBits&SYS_CFG_BITS_MAG_RECAL_MODE_MASK)>>SYS_CFG_BITS_MAG_RECAL_MODE_OFFSET)
1479 
1488 
1494  SYS_CFG_BITS_DISABLE_INS_EKF = (int)0x00040000,
1497 
1502 };
1503 
1506 {
1508  GNSS_SAT_SIG_CONST_GPS = (uint16_t)0x0003,
1510  GNSS_SAT_SIG_CONST_QZSS = (uint16_t)0x000C,
1512  GNSS_SAT_SIG_CONST_GAL = (uint16_t)0x0030,
1514  GNSS_SAT_SIG_CONST_BDS = (uint16_t)0x00C0,
1516  GNSS_SAT_SIG_CONST_GLO = (uint16_t)0x0300,
1518  GNSS_SAT_SIG_CONST_SBAS = (uint16_t)0x1000,
1519 
1522  GNSS_SAT_SIG_CONST_GPS | \
1523  GNSS_SAT_SIG_CONST_SBAS | \
1524  GNSS_SAT_SIG_CONST_QZSS | \
1525  GNSS_SAT_SIG_CONST_GAL | \
1526  GNSS_SAT_SIG_CONST_GLO
1527 };
1528 
1531 {
1534 
1537 
1540 
1543 
1546 
1549 
1551  RTK_CFG_BITS_ROVER_MODE_MASK = (int)0x0000000F,
1552 
1555 
1558 
1561 
1564 
1567 
1570 
1573 
1576 
1579 
1582 
1585 
1588 
1590  RTK_CFG_BITS_BASE_POS_MOVING = (int)0x00010000,
1591 
1593  RTK_CFG_BITS_RESERVED1 = (int)0x00020000,
1594 
1597 
1600 
1609 
1614 
1619 
1625 
1631 
1637 
1643 
1646 
1649 };
1650 
1651 
1654 {
1656  SENSOR_CFG_GYR_FS_250 = (int)0x00000000,
1657  SENSOR_CFG_GYR_FS_500 = (int)0x00000001,
1658  SENSOR_CFG_GYR_FS_1000 = (int)0x00000002,
1659  SENSOR_CFG_GYR_FS_2000 = (int)0x00000003,
1660  SENSOR_CFG_GYR_FS_MASK = (int)0x00000003,
1662 
1664  SENSOR_CFG_ACC_FS_2G = (int)0x00000000,
1665  SENSOR_CFG_ACC_FS_4G = (int)0x00000001,
1666  SENSOR_CFG_ACC_FS_8G = (int)0x00000002,
1667  SENSOR_CFG_ACC_FS_16G = (int)0x00000003,
1668  SENSOR_CFG_ACC_FS_MASK = (int)0x00000003,
1670 
1673  SENSOR_CFG_GYR_DLPF_250HZ = (int)0x00000000,
1674  SENSOR_CFG_GYR_DLPF_184HZ = (int)0x00000001,
1675  SENSOR_CFG_GYR_DLPF_92HZ = (int)0x00000002,
1676  SENSOR_CFG_GYR_DLPF_41HZ = (int)0x00000003,
1677  SENSOR_CFG_GYR_DLPF_20HZ = (int)0x00000004,
1678  SENSOR_CFG_GYR_DLPF_10HZ = (int)0x00000005,
1679  SENSOR_CFG_GYR_DLPF_5HZ = (int)0x00000006,
1680  SENSOR_CFG_GYR_DLPF_MASK = (int)0x0000000F,
1682 
1685  SENSOR_CFG_ACC_DLPF_218HZ = (int)0x00000000,
1686  SENSOR_CFG_ACC_DLPF_218HZb = (int)0x00000001,
1687  SENSOR_CFG_ACC_DLPF_99HZ = (int)0x00000002,
1688  SENSOR_CFG_ACC_DLPF_45HZ = (int)0x00000003,
1689  SENSOR_CFG_ACC_DLPF_21HZ = (int)0x00000004,
1690  SENSOR_CFG_ACC_DLPF_10HZ = (int)0x00000005,
1691  SENSOR_CFG_ACC_DLPF_5HZ = (int)0x00000006,
1692  SENSOR_CFG_ACC_DLPF_MASK = (int)0x0000000F,
1694 };
1695 
1696 
1699 {
1710 
1713 
1724 #define SET_STATUS_OFFSET_MASK(result,val,offset,mask) { (result) &= ~((mask)<<(offset)); (result) |= ((val)<<(offset)); }
1725 
1726 #define IO_CFG_GPS_TIMEPUSE_SOURCE(ioConfig) ((ioConfig>>IO_CFG_GPS_TIMEPUSE_SOURCE_OFFSET)&IO_CFG_GPS_TIMEPUSE_SOURCE_MASK)
1727 
1736 
1738  IO_CONFIG_GPS_SOURCE_MASK = (int)0x00000007,
1749 
1751  IO_CONFIG_GPS_TYPE_MASK = (int)0x00000003,
1758 
1759 #define IO_CONFIG_GPS1_SOURCE(ioConfig) ((ioConfig>>IO_CONFIG_GPS1_SOURCE_OFFSET)&IO_CONFIG_GPS_SOURCE_MASK)
1760 #define IO_CONFIG_GPS2_SOURCE(ioConfig) ((ioConfig>>IO_CONFIG_GPS2_SOURCE_OFFSET)&IO_CONFIG_GPS_SOURCE_MASK)
1761 #define IO_CONFIG_GPS1_TYPE(ioConfig) ((ioConfig>>IO_CONFIG_GPS1_TYPE_OFFSET)&IO_CONFIG_GPS_TYPE_MASK)
1762 #define IO_CONFIG_GPS2_TYPE(ioConfig) ((ioConfig>>IO_CONFIG_GPS2_TYPE_OFFSET)&IO_CONFIG_GPS_TYPE_MASK)
1763 
1765  IO_CFG_IMU_1_DISABLE = (int)0x00100000,
1767  IO_CFG_IMU_2_DISABLE = (int)0x00200000,
1768 };
1769 
1770 
1772 typedef struct PACKED
1773 {
1775  double timeOfWeek;
1776 
1778  uint32_t status;
1779 
1781  float theta_l;
1782 
1784  float theta_r;
1785 
1787  float omega_l;
1788 
1790  float omega_r;
1791 
1793  uint32_t wrap_count_l;
1794 
1796  uint32_t wrap_count_r;
1797 
1798 } wheel_encoder_t;
1799 
1801 {
1804  WHEEL_CFG_BITS_ENABLE_MASK = (int)0x0000000F,
1805 };
1806 
1808 typedef struct PACKED
1809 {
1811  uint32_t bits;
1812 
1814  float e_i2l[3];
1815 
1817  float t_i2l[3];
1818 
1820  float distance;
1821 
1823  float diameter;
1824 
1825 } wheel_config_t;
1826 
1827 typedef enum
1828 {
1838 } eInsDynModel;
1839 
1844 typedef struct PACKED
1845 {
1847  uint32_t size;
1848 
1850  uint32_t checksum;
1851 
1853  uint32_t key;
1854 
1856  uint32_t startupImuDtMs;
1857 
1859  uint32_t startupNavDtMs;
1860 
1862  uint32_t ser0BaudRate;
1863 
1865  uint32_t ser1BaudRate;
1866 
1868  float insRotation[3];
1869 
1871  float insOffset[3];
1872 
1874  float gps1AntOffset[3];
1875 
1877  uint8_t insDynModel;
1878 
1880  uint8_t reserved;
1881 
1884 
1886  uint32_t sysCfgBits;
1887 
1889  double refLla[3];
1890 
1892  double lastLla[3];
1893 
1896 
1898  uint32_t lastLlaWeek;
1899 
1902 
1904  uint32_t ioConfig;
1905 
1907  uint32_t cBrdConfig;
1908 
1910  float gps2AntOffset[3];
1911 
1914 
1916  float zeroVelOffset[3];
1917 
1920 
1923 
1926 
1928  uint32_t startupGPSDtMs;
1929 
1931  uint32_t RTKCfgBits;
1932 
1934  uint32_t sensorConfig;
1935 
1938 
1941 
1942 } nvm_flash_cfg_t;
1943 
1945 typedef struct PACKED
1946 {
1948  unsigned int timeOfWeekMs;
1950  float PxyzNED[3];
1952  float PvelNED[3];
1954  float PattNED[3];
1956  float PABias[3];
1958  float PWBias[3];
1960  float PBaroBias;
1964 
1966 typedef struct PACKED
1967 {
1969  uint32_t week;
1970 
1972  uint32_t timeOfWeekMs;
1973 
1975  uint32_t pin;
1976 
1978  uint32_t count;
1980 
1981 #define DEBUG_I_ARRAY_SIZE 9
1982 #define DEBUG_F_ARRAY_SIZE 9
1983 #define DEBUG_LF_ARRAY_SIZE 3
1984 
1985 /* (DID_DEBUG_ARRAY) */
1986 typedef struct PACKED
1987 {
1991 } debug_array_t;
1992 
1993 #define DEBUG_STRING_SIZE 80
1994 
1995 /* (DID_DEBUG_STRING) */
1996 typedef struct PACKED
1997 {
1999 } debug_string_t;
2000 
2001 POP_PACK
2002 
2004 
2006 typedef struct
2007 {
2009  int64_t time;
2010 
2012  double sec;
2013 } gtime_t;
2014 
2015 typedef struct PACKED
2016 {
2018  double rp_ecef[3]; // Rover position
2019  double rv_ecef[3]; // Rover velocity
2020  double ra_ecef[3]; // Rover acceleration
2021  double bp_ecef[3]; // Base position
2022  double bv_ecef[3]; // Base velocity
2023  double qr[6]; // rover position and velocity covariance main diagonal
2024  double b[24]; // satellite bias
2025  double qb[24]; // main diagonal of sat bias covariances
2026  uint8_t sat_id[24]; // satellite id of b[]
2027 } rtk_state_t;
2028 
2029 typedef struct PACKED
2030 {
2031  gtime_t time;
2032  int32_t nv; // number of measurements
2033  uint8_t sat_id_i[24]; // sat id of measurements (reference sat)
2034  uint8_t sat_id_j[24]; // sat id of measurements
2035  uint8_t type[24]; // type (0 = dd-range, 1 = dd-phase, 2 = baseline)
2036  double v[24]; // residual
2037 } rtk_residual_t;
2038 
2039 typedef struct PACKED
2040 {
2041  gtime_t time;
2042 
2043  uint8_t rej_ovfl;
2044  uint8_t code_outlier;
2045  uint8_t phase_outlier;
2047 
2052 
2053  uint8_t outc_ovfl;
2054  uint8_t reset_timer;
2056  uint8_t large_v2b;
2057 
2060  uint8_t reset_bias;
2061  uint8_t start_relpos;
2062 
2063  uint8_t end_relpos;
2064  uint8_t start_rtkpos;
2065  uint8_t pnt_pos_error;
2067 
2072 
2073  uint8_t lsq_error;
2077 
2078  uint32_t cycle_slips;
2079 
2080  float ubx_error;
2081 
2082  uint8_t solStatus;
2084  uint8_t error_count;
2085  uint8_t error_code;
2086 
2087  float dist2base;
2088 
2089  uint8_t reserved1;
2090  uint8_t gdop_error;
2091  uint8_t warning_count;
2092  uint8_t warning_code;
2093 
2094  double double_debug[4];
2095 
2096  uint8_t debug[2];
2097  uint8_t obs_count_bas;
2098  uint8_t obs_count_rov;
2099 
2104 } rtk_debug_t;
2105 
2106 POP_PACK
2107 
2109 
2111 typedef struct
2112 {
2114  int32_t mode;
2115 
2117  int32_t soltype;
2118 
2120  int32_t nf;
2121 
2123  int32_t navsys;
2124 
2126  double elmin;
2127 
2129  int32_t snrmin;
2130 
2132  int32_t modear;
2133 
2135  int32_t glomodear;
2136 
2138  int32_t gpsmodear;
2139 
2141  int32_t sbsmodear;
2142 
2144  int32_t bdsmodear;
2145 
2147  int32_t arfilter;
2148 
2150  int32_t maxout;
2151 
2153  int32_t maxrej;
2154 
2156  int32_t minlock;
2157 
2159  int32_t minfixsats;
2160 
2162  int32_t minholdsats;
2163 
2165  int32_t mindropsats;
2166 
2168  int32_t rcvstds;
2169 
2171  int32_t minfix;
2172 
2174  int32_t armaxiter;
2175 
2177  int32_t dynamics;
2178 
2180  int32_t niter;
2181 
2183  int32_t intpref;
2184 
2186  int32_t rovpos;
2187 
2189  int32_t refpos;
2190 
2192  double eratio[1];
2193 
2195  double err[5];
2196 
2198  double std[3];
2199 
2201  double prn[6];
2202 
2204  double sclkstab;
2205 
2207  double thresar[8];
2208 
2210  double elmaskar;
2211 
2213  double elmaskhold;
2214 
2216  double thresslip;
2217 
2219  double varholdamb;
2220 
2222  double gainholdamb;
2223 
2225  double maxtdiff;
2226 
2229 
2231  double maxinnocode;
2233  double maxnis;
2234 
2236  double maxgdop;
2237 
2239  double baseline[3];
2242 
2245 
2247  double ru[3];
2248 
2250  double rb[3];
2251 
2253  int32_t maxaveep;
2254 
2256  int32_t outsingle;
2257 } prcopt_t;
2259 
2261 typedef struct PACKED
2262 {
2264  gtime_t time;
2265 
2267  uint8_t sat;
2268 
2270  uint8_t rcv;
2271 
2273  uint8_t SNR[1];
2274 
2276  uint8_t LLI[1];
2277 
2279  uint8_t code[1];
2280 
2282  uint8_t qualL[1];
2283 
2285  uint8_t qualP[1];
2286 
2288  uint8_t reserved;
2289 
2291  double L[1];
2292 
2294  double P[1];
2295 
2297  float D[1];
2298 } obsd_t;
2299 
2300 #define GPS_RAW_MESSAGE_BUF_SIZE 1000
2301 #define MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE (GPS_RAW_MESSAGE_BUF_SIZE / sizeof(obsd_t))
2302 
2304 typedef struct
2305 {
2307  uint32_t n;
2308 
2310  uint32_t nmax;
2311 
2314 } obs_t;
2315 
2317 typedef struct
2318 {
2320  int32_t sat;
2321 
2323  int32_t iode;
2324 
2326  int32_t iodc;
2327 
2329  int32_t sva;
2330 
2332  int32_t svh;
2333 
2335  int32_t week;
2336 
2338  int32_t code;
2339 
2341  int32_t flag;
2342 
2345 
2348 
2351 
2353  double A;
2354 
2356  double e;
2357 
2359  double i0;
2360 
2362  double OMG0;
2363 
2365  double omg;
2366 
2368  double M0;
2369 
2371  double deln;
2372 
2374  double OMGd;
2375 
2377  double idot;
2378 
2380  double crc;
2381 
2383  double crs;
2384 
2386  double cuc;
2387 
2389  double cus;
2390 
2392  double cic;
2393 
2395  double cis;
2396 
2398  double toes;
2399 
2401  double fit;
2402 
2404  double f0;
2405 
2407  double f1;
2408 
2410  double f2;
2411 
2413  double tgd[4];
2414 
2416  double Adot;
2417 
2419  double ndot;
2420 } eph_t;
2421 
2423 typedef struct
2424 {
2426  int32_t sat;
2427 
2429  int32_t iode;
2430 
2432  int32_t frq;
2433 
2435  int32_t svh;
2436 
2438  int32_t sva;
2439 
2441  int32_t age;
2442 
2445 
2448 
2450  double pos[3];
2451 
2453  double vel[3];
2454 
2456  double acc[3];
2457 
2459  double taun;
2460 
2462  double gamn;
2463 
2465  double dtaun;
2466 } geph_t;
2467 
2469 typedef struct
2470 {
2472  int32_t week;
2473 
2475  int32_t tow;
2476 
2478  int32_t prn;
2479 
2481  uint8_t msg[29];
2482 
2484  uint8_t reserved[3];
2485 } sbsmsg_t;
2486 
2488 typedef struct
2489 {
2491  int32_t deltype;
2492 
2494  double pos[3];
2495 
2497  double del[3];
2498 
2500  double hgt;
2501 
2503  int32_t stationId;
2504 } sta_t;
2505 
2507 typedef struct
2508 {
2510  int32_t sat;
2511 
2513  int32_t svh;
2514 
2516  int32_t svconf;
2517 
2518  /* GPS/QZS: gps week, GAL: galileo week */
2519  int32_t week;
2520 
2521  /* Toa */
2523 
2525  double A;
2526 
2528  double e;
2529 
2531  double i0;
2532 
2534  double OMG0;
2535 
2537  double omg;
2538 
2540  double M0;
2541 
2543  double OMGd;
2544 
2546  double toas;
2547 
2549  double f0;
2550 
2552  double f1;
2553 } alm_t;
2554 
2556 typedef struct
2557 {
2558  double ion_gps[8]; /* GPS iono model parameters {a0,a1,a2,a3,b0,b1,b2,b3} */
2559  double ion_gal[4]; /* Galileo iono model parameters {ai0,ai1,ai2,0} */
2560  double ion_qzs[8]; /* QZSS iono model parameters {a0,a1,a2,a3,b0,b1,b2,b3} */
2561  double ion_cmp[8]; /* BeiDou iono model parameters {a0,a1,a2,a3,b0,b1,b2,b3} */
2562  double ion_irn[8]; /* IRNSS iono model parameters {a0,a1,a2,a3,b0,b1,b2,b3} */
2563 
2564  double utc_gps[4]; /* GPS delta-UTC parameters {A0,A1,T,W} */
2565  double utc_glo[4]; /* GLONASS UTC GPS time parameters */
2566  double utc_gal[4]; /* Galileo UTC GPS time parameters */
2567  double utc_qzs[4]; /* QZS UTC GPS time parameters */
2568  double utc_cmp[4]; /* BeiDou UTC parameters */
2569  double utc_irn[4]; /* IRNSS UTC parameters */
2570  double utc_sbs[4]; /* SBAS UTC parameters */
2571 
2572  int32_t leaps; /* leap seconds (s) */
2573 
2574  alm_t alm; /* almanac */
2576 
2578 typedef enum
2579 {
2582 
2585 
2588 
2591 
2594 
2597 } eRtkSolStatus;
2598 
2600 typedef struct PACKED
2601 {
2603  uint32_t timeOfWeekMs;
2604 
2607 
2609  float arRatio;
2610 
2613 
2616 
2619 
2622 
2624  uint32_t status;
2625 
2626 } gps_rtk_rel_t;
2627 
2629 typedef struct PACKED
2630 {
2632  uint32_t timeOfWeekMs;
2633 
2635  float accuracyPos[3];
2636 
2638  float accuracyCov[3];
2639 
2642 
2644  float gDop;
2645 
2647  float hDop;
2648 
2650  float vDop;
2651 
2653  double baseLla[3];
2654 
2656  uint32_t cycleSlipCount;
2657 
2660 
2663 
2666 
2669 
2672 
2675 
2678 
2681 
2684 
2687 
2690 
2693 
2696 
2699 
2702 
2705 
2708 
2711 
2714 
2717 
2719  uint32_t roverSbasCount;
2720 
2722  uint32_t baseSbasCount;
2723 
2726 
2728  uint32_t ionUtcAlmCount;
2729 
2732 
2735 
2736 } gps_rtk_misc_t;
2737 
2739 typedef enum
2740 {
2743 
2746 
2749 
2752 
2755 
2758 
2761 } eRawDataType;
2762 
2763 typedef union PACKED
2764 {
2767 
2770 
2773 
2776 
2779 
2782 
2785 } uGpsRawData;
2786 
2788 typedef struct PACKED
2789 {
2791  uint8_t receiverIndex;
2792 
2794  uint8_t dataType;
2795 
2797  uint8_t obsCount;
2798 
2800  uint8_t reserved;
2801 
2804 } gps_raw_t;
2805 
2809 typedef struct
2810 {
2812  uint32_t timeOfWeekMs;
2813 
2815  uint32_t messageLength;
2816 
2818  char message[256];
2819 } diag_msg_t;
2820 
2821 typedef enum
2822 {
2823  // default state
2825 
2826  // commands
2831 
2832  // status
2838 } eSurveyInStatus;
2839 
2843 typedef struct
2844 {
2846  uint32_t state;
2847 
2849  uint32_t maxDurationSec;
2850 
2853 
2855  uint32_t elapsedTimeSec;
2856 
2858  float hAccuracy;
2859 
2861  double lla[3];
2862 } survey_in_t;
2863 
2864 
2865 typedef enum
2866 {
2869 
2872 
2875 
2878 
2881 
2884 
2887 
2890 
2893 
2896 
2899 
2900 } eEvbStatus;
2901 
2904 {
2908  EVB2_PORT_XRADIO = 3, // H4-8 (orange) Tx, H4-7 (brown) Rx
2910  EVB2_PORT_SP330 = 5, // H3-2 (brown) Tx, H3-5 (green) Rx
2911  EVB2_PORT_GPIO_H8 = 6, // H8-5 (brown) Tx, H8-6 (orange) Rx
2914  EVB2_PORT_CAN = 9, // H2-3 CANL (brown), H2-4 CANH (orange)
2916 };
2917 
2920 {
2929 };
2930 
2932 {
2933  EVB2_PORT_OPTIONS_RADIO_RTK_FILTER = 0x00000001, // Allow RTCM3, NMEA, and RTCM3. Reject IS binary.
2935 };
2936 
2940 typedef struct
2941 {
2943  uint32_t week;
2944 
2946  uint32_t timeOfWeekMs;
2947 
2949  uint8_t firmwareVer[4];
2950 
2952  uint32_t evbStatus;
2953 
2955  uint32_t loggerMode;
2956 
2959 
2961  uint32_t wifiIpAddr;
2962 
2964  uint32_t sysCommand;
2965 
2966 } evb_status_t;
2967 
2968 #define WIFI_SSID_PSK_SIZE 40
2969 
2970 typedef struct
2971 {
2973  uint8_t ssid[WIFI_SSID_PSK_SIZE];
2974 
2976  uint8_t psk[WIFI_SSID_PSK_SIZE];
2977 
2978 } evb_wifi_t;
2979 
2980 typedef struct
2981 {
2983  uint32_t ipAddr;
2984 
2986  uint32_t port;
2987 
2988 } evb_server_t;
2989 
2990 typedef enum
2991 {
2998 
2999 #define NUM_WIFI_PRESETS 3
3000 #define EVB_CFG_BITS_SET_IDX_WIFI(bits,idx) {bits&=EVB_CFG_BITS_WIFI_SELECT_MASK; bits|=((idx<<EVB_CFG_BITS_WIFI_SELECT_OFFSET)&EVB_CFG_BITS_WIFI_SELECT_MASK);}
3001 #define EVB_CFG_BITS_SET_IDX_SERVER(bits,idx) {bits&=EVB_CFG_BITS_SERVER_SELECT_MASK; bits|=((idx<<EVB_CFG_BITS_SERVER_SELECT_OFFSET)&EVB_CFG_BITS_SERVER_SELECT_MASK);}
3002 #define EVB_CFG_BITS_IDX_WIFI(bits) ((bits&EVB_CFG_BITS_WIFI_SELECT_MASK)>>EVB_CFG_BITS_WIFI_SELECT_OFFSET)
3003 #define EVB_CFG_BITS_IDX_SERVER(bits) ((bits&EVB_CFG_BITS_SERVER_SELECT_MASK)>>EVB_CFG_BITS_SERVER_SELECT_OFFSET)
3004 
3008 typedef struct
3009 {
3011  uint32_t size;
3012 
3014  uint32_t checksum;
3015 
3017  uint32_t key;
3018 
3020  uint8_t cbPreset;
3021 
3022  // 32-bit alignment
3023  uint8_t reserved1[3];
3024 
3026  uint32_t cbf[EVB2_PORT_COUNT];
3027 
3029  uint32_t cbOptions;
3030 
3032  uint32_t bits;
3033 
3035  uint32_t radioPID;
3036 
3038  uint32_t radioNID;
3039 
3042 
3045 
3048 
3051 
3053  uint32_t CANbaud_kbps;
3054 
3057 
3059  uint8_t uinsComPort;
3060 
3062  uint8_t uinsAuxPort;
3063 
3064  // Ensure 32-bit alignment
3065  uint8_t reserved2[2];
3066 
3068  uint32_t portOptions;
3069 
3072 
3075 
3077  uint32_t h8gpioBaudRate;
3078 
3079 } evb_flash_cfg_t;
3080 
3081 
3084 {
3087 
3090 
3093 
3096 
3099 
3102 
3105 
3108 
3111 
3112 };
3113 
3114 #define EVB2_CB_PRESET_DEFAULT EVB2_CB_PRESET_RS232
3115 
3118 {
3121 
3124 
3127 
3130 
3131 };
3132 
3133 
3137 typedef struct
3138 {
3140  uint32_t txBytesPerS;
3141 
3143  uint32_t rxBytesPerS;
3144 
3146  uint32_t status;
3147 
3149 
3150 typedef struct
3151 {
3154 
3155 } port_monitor_t;
3156 
3157 
3161 #define SYS_FAULT_STATUS_HARDWARE_RESET 0x00000000
3162 #define SYS_FAULT_STATUS_USER_RESET 0x00000001
3163 #define SYS_FAULT_STATUS_ENABLE_BOOTLOADER 0x00000002
3164 // General:
3165 #define SYS_FAULT_STATUS_SOFT_RESET 0x00000010
3166 #define SYS_FAULT_STATUS_FLASH_MIGRATION_EVENT 0x00000020
3167 #define SYS_FAULT_STATUS_FLASH_MIGRATION_COMPLETED 0x00000040
3168 #define SYS_FAULT_STATUS_RTK_MISC_ERROR 0x00000080
3169 #define SYS_FAULT_STATUS_MASK_GENERAL_ERROR 0xFFFFFFF0
3170 // Critical: (usually associated with system reset)
3171 #define SYS_FAULT_STATUS_HARD_FAULT 0x00010000
3172 #define SYS_FAULT_STATUS_USAGE_FAULT 0x00020000
3173 #define SYS_FAULT_STATUS_MEM_MANGE 0x00040000
3174 #define SYS_FAULT_STATUS_BUS_FAULT 0x00080000
3175 #define SYS_FAULT_STATUS_MALLOC_FAILED 0x00100000
3176 #define SYS_FAULT_STATUS_STACK_OVERFLOW 0x00200000
3177 #define SYS_FAULT_STATUS_INVALID_CODE_OPERATION 0x00400000
3178 #define SYS_FAULT_STATUS_FLASH_MIGRATION_MARKER_UPDATED 0x00800000
3179 #define SYS_FAULT_STATUS_WATCHDOG_RESET 0x01000000
3180 #define SYS_FAULT_STATUS_RTK_BUFFER_LIMIT 0x02000000
3181 #define SYS_FAULT_STATUS_SENSOR_CALIBRATION 0x04000000
3182 #define SYS_FAULT_STATUS_HARDWARE_DETECTION 0x08000000
3183 #define SYS_FAULT_STATUS_MASK_CRITICAL_ERROR 0xFFFF0000
3184 
3185 typedef struct
3186 {
3188  uint32_t status;
3189 
3191  uint32_t g1Task;
3192 
3194  uint32_t g2FileNum;
3195 
3197  uint32_t g3LineNum;
3198 
3200  uint32_t g4;
3201 
3203  uint32_t g5Lr;
3204 
3206  uint32_t pc;
3207 
3209  uint32_t psr;
3210 
3211 } system_fault_t;
3212 
3214 typedef struct
3215 {
3217  uint32_t gapCountSerialDriver[NUM_SERIAL_PORTS];
3218 
3220  uint32_t gapCountSerialParser[NUM_SERIAL_PORTS];
3221 
3223  uint32_t rxOverflowCount[NUM_SERIAL_PORTS];
3224 
3226  uint32_t txOverflowCount[NUM_SERIAL_PORTS];
3227 
3229  uint32_t checksumFailCount[NUM_SERIAL_PORTS];
3231 
3233 typedef enum
3234 {
3237 
3240 
3243 
3246 
3249 
3252 
3254  UINS_RTOS_NUM_TASKS // Keep last
3255 } eRtosTask;
3256 
3258 typedef enum
3259 {
3262 
3265 
3268 
3271 
3274 
3277 
3280 
3282  EVB_RTOS_NUM_TASKS // Keep last
3283 } eEvbRtosTask;
3284 
3286 #define MAX_TASK_NAME_LEN 12
3287 
3289 typedef struct PACKED
3290 {
3293 
3295  uint32_t priority;
3296 
3298  uint32_t stackUnused;
3299 
3301  uint32_t periodMs;
3302 
3304  uint32_t runTimeUs;
3305 
3307  uint32_t maxRunTimeUs;
3308 
3311 
3313  uint32_t gapCount;
3314 
3316  float cpuUsage;
3317 
3319  uint32_t handle;
3320 } rtos_task_t;
3321 
3323 typedef struct PACKED
3324 {
3326  uint32_t freeHeapSize;
3327 
3329  uint32_t mallocSize;
3330 
3332  uint32_t freeSize;
3333 
3336 
3337 } rtos_info_t;
3338 
3340 typedef struct PACKED
3341 {
3343  uint32_t freeHeapSize;
3344 
3346  uint32_t mallocSize;
3347 
3349  uint32_t freeSize;
3350 
3353 
3354 } evb_rtos_info_t;
3355 enum
3356 {
3383 };
3384 
3386 typedef struct PACKED
3387 {
3390 
3393 
3396 
3399 
3400 } can_config_t;
3401 
3403 typedef union PACKED
3404 {
3433 } uDatasets;
3434 
3436 typedef union PACKED
3437 {
3438  ins_1_t ins1;
3439  ins_2_t ins2;
3440  ins_3_t ins3;
3441  ins_4_t ins4;
3442 } uInsOutDatasets;
3443 
3444 POP_PACK
3445 
3454 uint32_t checksum32(const void* data, int count);
3455 uint32_t serialNumChecksum32(const void* data, int size);
3456 uint32_t flashChecksum32(const void* data, int size);
3457 
3464 void flipEndianess32(uint8_t* data, int dataLength);
3465 
3471 void flipFloat(uint8_t* ptr);
3472 
3479 float flipFloatCopy(float val);
3480 
3487 void flipDouble(void* ptr);
3488 
3496 double flipDoubleCopy(double val);
3497 
3507 void flipDoubles(uint8_t* data, int dataLength, int offset, uint16_t* offsets, uint16_t offsetsLength);
3508 
3518 void flipStrings(uint8_t* data, int dataLength, int offset, uint16_t* offsets, uint16_t offsetsLength);
3519 
3520 // BE_SWAP: if big endian then swap, else no-op
3521 // LE_SWAP: if little endian then swap, else no-op
3522 #if CPU_IS_BIG_ENDIAN
3523 #define BE_SWAP64F(_i) flipDoubleCopy(_i)
3524 #define BE_SWAP32F(_i) flipFloatCopy(_i)
3525 #define BE_SWAP32(_i) (SWAP32(_i))
3526 #define BE_SWAP16(_i) (SWAP16(_i))
3527 #define LE_SWAP64F(_i) (_i)
3528 #define LE_SWAP32F(_i) (_i)
3529 #define LE_SWAP32(_i) (_i)
3530 #define LE_SWAP16(_i) (_i)
3531 #else // little endian
3532 #define BE_SWAP64F(_i) (_i)
3533 #define BE_SWAP32F(_i) (_i)
3534 #define BE_SWAP32(_i) (_i)
3535 #define BE_SWAP16(_i) (_i)
3536 #define LE_SWAP64F(_i) flipDoubleCopy(_i)
3537 #define LE_SWAP32F(_i) flipFloatCopy(_i)
3538 #define LE_SWAP32(_i) (SWAP32(_i))
3539 #define LE_SWAP16(_i) (SWAP16(_i))
3540 #endif
3541 
3550 uint16_t* getDoubleOffsets(eDataIDs dataId, uint16_t* offsetsLength);
3551 
3560 uint16_t* getStringOffsetsLengths(eDataIDs dataId, uint16_t* offsetsLength);
3561 
3563 uint64_t didToRmcBit(uint32_t dataId, uint64_t defaultRmcBits);
3564 
3565 //Time conversion constants
3566 #define SECONDS_PER_WEEK 604800
3567 #define SECONDS_PER_DAY 86400
3568 #define GPS_TO_UNIX_OFFSET 315964800
3569 
3570 double gpsToUnix(uint32_t gpsWeek, uint32_t gpsTimeofWeekMS, uint8_t leapSeconds);
3571 
3573 void julianToDate(double julian, int32_t* year, int32_t* month, int32_t* day, int32_t* hour, int32_t* minute, int32_t* second, int32_t* millisecond);
3574 
3576 double gpsToJulian(int32_t gpsWeek, int32_t gpsMilliseconds, int32_t leapSeconds);
3577 
3578 /*
3579 Convert gps pos to nmea gga
3580 
3581 @param gps gps position
3582 @param buffer buffer to fill with nmea gga
3583 @param bufferLength number of chars available in buffer, should be at least 128
3584 @return number of chars written to buffer, not including the null terminator
3585 */
3586 int gpsToNmeaGGA(const gps_pos_t* gps, char* buffer, int bufferLength);
3587 
3588 #ifndef RTKLIB_H
3589 #define SYS_NONE 0x00 /* navigation system: none */
3590 #define SYS_GPS 0x01 /* navigation system: GPS */
3591 #define SYS_SBS 0x02 /* navigation system: SBAS */
3592 #define SYS_GLO 0x04 /* navigation system: GLONASS */
3593 #define SYS_GAL 0x08 /* navigation system: Galileo */
3594 #define SYS_QZS 0x10 /* navigation system: QZSS */
3595 #define SYS_CMP 0x20 /* navigation system: BeiDou */
3596 #define SYS_IRN 0x40 /* navigation system: IRNS */
3597 #define SYS_LEO 0x80 /* navigation system: LEO */
3598 #define SYS_ALL 0xFF /* navigation system: all */
3599 #endif
3600 
3601 /*
3602 Convert gnssID to ubx gnss indicator (ref [2] 25)
3603 
3604 @param gnssID gnssID of satellite
3605 @return ubx gnss indicator
3606 */
3607 int ubxSys(int gnssID);
3608 
3609 #ifndef __RTKLIB_EMBEDDED_DEFINES_H_
3610 
3611 #undef ENAGLO
3612 #define ENAGLO
3613 
3614 #undef ENAGAL
3615 #define ENAGAL
3616 
3617 #undef ENAQZS
3618 //#define ENAQZS
3619 
3620 #undef ENASBS
3621 #define ENASBS
3622 
3623 #undef MAXSUBFRMLEN
3624 #define MAXSUBFRMLEN 152
3625 
3626 #undef MAXRAWLEN
3627 #define MAXRAWLEN 2048
3628 
3629 #undef NFREQ
3630 #define NFREQ 1
3631 
3632 #undef NFREQGLO
3633 #ifdef ENAGLO
3634 #define NFREQGLO 1
3635 #else
3636 #define NFREQGLO 0
3637 #endif
3638 
3639 #undef NFREQGAL
3640 #ifdef ENAGAL
3641 #define NFREQGAL 1
3642 #else
3643 #define NFREQGAL 0
3644 #endif
3645 
3646 #undef NEXOBS
3647 #define NEXOBS 0
3648 
3649 #undef MAXOBS
3650 #define MAXOBS 56 // Also defined inside rtklib_defines.h
3651 #define HALF_MAXOBS (MAXOBS/2)
3652 
3653 #undef NUMSATSOL
3654 #define NUMSATSOL 22
3655 
3656 #undef MAXERRMSG
3657 #define MAXERRMSG 0
3658 
3659 #ifdef ENASBS
3660 
3661 // sbas waas only satellites
3662 #undef MINPRNSBS
3663 #define MINPRNSBS 133 /* min satellite PRN number of SBAS */
3664 
3665 #undef MAXPRNSBS
3666 #define MAXPRNSBS 138 /* max satellite PRN number of SBAS */
3667 
3668 #undef NSATSBS
3669 #define NSATSBS (MAXPRNSBS - MINPRNSBS + 1) /* number of SBAS satellites */
3670 
3671 #define SBAS_EPHEMERIS_ARRAY_SIZE NSATSBS
3672 
3673 #else
3674 
3675 #define SBAS_EPHEMERIS_ARRAY_SIZE 0
3676 
3677 #endif
3678 
3679 
3680 #endif
3681 
3682 #ifndef RTKLIB_H
3683 
3684 #define MINPRNGPS 1 /* min satellite PRN number of GPS */
3685 #define MAXPRNGPS 32 /* max satellite PRN number of GPS */
3686 #define NSATGPS (MAXPRNGPS-MINPRNGPS+1) /* number of GPS satellites */
3687 #define NSYSGPS 1
3688 
3689 #ifdef ENAGLO
3690 #define MINPRNGLO 1 /* min satellite slot number of GLONASS */
3691 #define MAXPRNGLO 27 /* max satellite slot number of GLONASS */
3692 #define NSATGLO (MAXPRNGLO-MINPRNGLO+1) /* number of GLONASS satellites */
3693 #define NSYSGLO 1
3694 #else
3695 #define MINPRNGLO 0
3696 #define MAXPRNGLO 0
3697 #define NSATGLO 0
3698 #define NSYSGLO 0
3699 #endif
3700 #ifdef ENAGAL
3701 #define MINPRNGAL 1 /* min satellite PRN number of Galileo */
3702 #define MAXPRNGAL 30 /* max satellite PRN number of Galileo */
3703 #define NSATGAL (MAXPRNGAL-MINPRNGAL+1) /* number of Galileo satellites */
3704 #define NSYSGAL 1
3705 #else
3706 #define MINPRNGAL 0
3707 #define MAXPRNGAL 0
3708 #define NSATGAL 0
3709 #define NSYSGAL 0
3710 #endif
3711 #ifdef ENAQZS
3712 #define MINPRNQZS 193 /* min satellite PRN number of QZSS */
3713 #define MAXPRNQZS 199 /* max satellite PRN number of QZSS */
3714 #define MINPRNQZS_S 183 /* min satellite PRN number of QZSS SAIF */
3715 #define MAXPRNQZS_S 189 /* max satellite PRN number of QZSS SAIF */
3716 #define NSATQZS (MAXPRNQZS-MINPRNQZS+1) /* number of QZSS satellites */
3717 #define NSYSQZS 1
3718 #else
3719 #define MINPRNQZS 0
3720 #define MAXPRNQZS 0
3721 #define MINPRNQZS_S 0
3722 #define MAXPRNQZS_S 0
3723 #define NSATQZS 0
3724 #define NSYSQZS 0
3725 #endif
3726 #ifdef ENACMP
3727 #define MINPRNCMP 1 /* min satellite sat number of BeiDou */
3728 #define MAXPRNCMP 35 /* max satellite sat number of BeiDou */
3729 #define NSATCMP (MAXPRNCMP-MINPRNCMP+1) /* number of BeiDou satellites */
3730 #define NSYSCMP 1
3731 #else
3732 #define MINPRNCMP 0
3733 #define MAXPRNCMP 0
3734 #define NSATCMP 0
3735 #define NSYSCMP 0
3736 #endif
3737 #ifdef ENAIRN
3738 #define MINPRNIRN 1 /* min satellite sat number of IRNSS */
3739 #define MAXPRNIRN 7 /* max satellite sat number of IRNSS */
3740 #define NSATIRN (MAXPRNIRN-MINPRNIRN+1) /* number of IRNSS satellites */
3741 #define NSYSIRN 1
3742 #else
3743 #define MINPRNIRN 0
3744 #define MAXPRNIRN 0
3745 #define NSATIRN 0
3746 #define NSYSIRN 0
3747 #endif
3748 #ifdef ENALEO
3749 #define MINPRNLEO 1 /* min satellite sat number of LEO */
3750 #define MAXPRNLEO 10 /* max satellite sat number of LEO */
3751 #define NSATLEO (MAXPRNLEO-MINPRNLEO+1) /* number of LEO satellites */
3752 #define NSYSLEO 1
3753 #else
3754 #define MINPRNLEO 0
3755 #define MAXPRNLEO 0
3756 #define NSATLEO 0
3757 #define NSYSLEO 0
3758 #endif
3759 #define NSYS (NSYSGPS+NSYSGLO+NSYSGAL+NSYSQZS+NSYSCMP+NSYSIRN+NSYSLEO) /* number of systems */
3760 #ifndef NSATSBS
3761 #ifdef ENASBS
3762 #define MINPRNSBS 120 /* min satellite PRN number of SBAS */
3763 #define MAXPRNSBS 142 /* max satellite PRN number of SBAS */
3764 #define NSATSBS (MAXPRNSBS-MINPRNSBS+1) /* number of SBAS satellites */
3765 #else
3766 #define MINPRNSBS 0
3767 #define MAXPRNSBS 0
3768 #define NSATSBS 0
3769 #endif
3770 #endif
3771 
3772 #endif
3773 /*
3774 Convert satellite constelation and prn/slot number to satellite number
3775 
3776 @param sys satellite system (SYS_GPS,SYS_GLO,...)
3777 @param prn satellite prn/slot number
3778 @return satellite number (0:error)
3779 */
3780 int satNo(int sys, int prn);
3781 
3782 /*
3783 convert satellite gnssID + svID to satellite number
3784 
3785 @param gnssID satellite system
3786 @param svID satellite prn/slot number
3787 @return satellite number (0:error)
3788 */
3789 int satNumCalc(int gnssID, int svID);
3790 
3791 
3792 #ifdef __cplusplus
3793 }
3794 #endif
3795 
3796 #endif // DATA_SETS_H
uint8_t type[24]
Definition: data_sets.h:2035
float max_ubx_error
Definition: data_sets.h:2244
uint32_t bits
Definition: data_sets.h:3032
void flipFloat(uint8_t *ptr)
Definition: data_sets.c:19
double refLla[3]
Definition: data_sets.h:1889
double lastLla[3]
Definition: data_sets.h:1892
double hgt
Definition: data_sets.h:2500
int stat_magfield
Definition: data_sets.h:924
gps_pos_t gpsPos
Definition: data_sets.h:3418
uint8_t start_rtkpos
Definition: data_sets.h:2064
uint32_t g1Task
Definition: data_sets.h:3191
unsigned int timeOfWeekMs
Definition: data_sets.h:1948
eInsStatusFlags
Definition: data_sets.h:167
double f0
Definition: data_sets.h:2404
struct PACKED can_config_t
uint8_t qualP[1]
Definition: data_sets.h:2285
uint8_t base_position_update
Definition: data_sets.h:2058
imus_t I
Definition: data_sets.h:617
float bar
Definition: data_sets.h:653
float baseToRoverVector[3]
Definition: data_sets.h:2612
uint32_t options
Definition: data_sets.h:1139
uint32_t bufferLength
Definition: USBD.h:91
uint8_t sat_id_j[24]
Definition: data_sets.h:2034
void flipStrings(uint8_t *data, int dataLength, int offset, uint16_t *offsets, uint16_t offsetsLength)
Definition: data_sets.c:117
int32_t week
Definition: data_sets.h:2335
uint32_t h3sp330BaudRate
Definition: data_sets.h:3071
double P[1]
Definition: data_sets.h:2294
uint8_t rej_ovfl
Definition: data_sets.h:2043
float humidity
Definition: data_sets.h:662
double taun
Definition: data_sets.h:2459
uint32_t recalCmd
Definition: data_sets.h:1332
int16_t azim
Definition: data_sets.h:819
ins_2_t ins2
Definition: data_sets.h:3407
float PxyzNED[3]
Definition: data_sets.h:1950
struct PACKED rtk_residual_t
int32_t i[DEBUG_I_ARRAY_SIZE]
Definition: data_sets.h:1988
uint8_t LLI[1]
Definition: data_sets.h:2276
double i0
Definition: data_sets.h:2531
uint8_t gnssId
Definition: data_sets.h:807
gps_raw_t gpsRaw
Definition: data_sets.h:3430
gps_vel_t gpsVel
Definition: data_sets.h:3419
float val
Definition: data_sets.h:934
uint32_t lastLlaTimeOfWeekMs
Definition: data_sets.h:1895
struct PACKED debug_array_t
double rv_ecef[3]
Definition: data_sets.h:2019
float vDop
Definition: data_sets.h:2650
int32_t iode
Definition: data_sets.h:2323
int32_t navsys
Definition: data_sets.h:2123
uint32_t correctionChecksumFailures
Definition: data_sets.h:2731
inl2_states_t inl2States
Definition: data_sets.h:3423
double elmaskar
Definition: data_sets.h:2210
#define DEBUG_LF_ARRAY_SIZE
Definition: data_sets.h:1983
uint32_t messageLength
Definition: data_sets.h:2815
double sclkstab
Definition: data_sets.h:2204
float nis
Definition: data_sets.h:1352
double towOffset
Definition: data_sets.h:774
uint32_t repoRevision
Definition: data_sets.h:457
eBitState
Definition: data_sets.h:1361
double sec
Definition: data_sets.h:2012
struct PACKED gps_pos_t
uint8_t reset_timer
Definition: data_sets.h:2054
f_t f[DEBUG_F_ARRAY_SIZE]
Definition: data_sets.h:1989
double lf[DEBUG_LF_ARRAY_SIZE]
Definition: data_sets.h:1990
float pqrSigma
Definition: data_sets.h:1453
int start_proc_done
Definition: data_sets.h:921
is_can_ve ve
Definition: CAN_comm.h:258
float insHdg
Definition: data_sets.h:1350
uint32_t g3LineNum
Definition: data_sets.h:3197
int32_t rcvstds
Definition: data_sets.h:2168
uint32_t baseGpsEphemerisCount
Definition: data_sets.h:2692
uint32_t startupImuDtMs
Definition: data_sets.h:1856
struct PACKED gps_sat_t
uint8_t sat
Definition: data_sets.h:2267
uint32_t wrap_count_l
Definition: data_sets.h:1793
int32_t armaxiter
Definition: data_sets.h:2174
double maxinnocode
Definition: data_sets.h:2231
struct PACKED imu_t
uint32_t pashr
Definition: data_sets.h:1175
uint8_t hwVersion[10]
Definition: data_sets.h:870
double toes
Definition: data_sets.h:2398
double b[24]
Definition: data_sets.h:2024
uint8_t leapS
Definition: data_sets.h:777
uint32_t gpgga
Definition: data_sets.h:1160
eEvb2CommPorts
Definition: data_sets.h:2903
uint32_t gprmc
Definition: data_sets.h:1169
float hAccuracy
Definition: data_sets.h:2858
float qn2b[4]
Definition: data_sets.h:534
int satNo(int sys, int prn)
Definition: data_sets.c:868
uint8_t no_base_obs_data
Definition: data_sets.h:2066
float f_t
Definition: ISConstants.h:786
uint8_t warning_count
Definition: data_sets.h:2091
double gamn
Definition: data_sets.h:2462
float accuracyCov[3]
Definition: data_sets.h:2638
int32_t deltype
Definition: data_sets.h:2491
uint8_t sat_id[24]
Definition: data_sets.h:2026
int32_t rovpos
Definition: data_sets.h:2186
float progress
Definition: data_sets.h:1335
gtime_t toc
Definition: data_sets.h:2347
float lastLlaUpdateDistance
Definition: data_sets.h:1901
float gDop
Definition: data_sets.h:2644
union PACKED uDatasets
#define DEVINFO_MANUFACTURER_STRLEN
Definition: data_sets.h:149
uint32_t sysCommand
Definition: data_sets.h:2964
uint32_t evbStatus
Definition: data_sets.h:2952
float val2[3]
Definition: data_sets.h:957
float PABias[3]
Definition: data_sets.h:1956
ins_1_t ins1
Definition: data_sets.h:3406
eRtosTask
Definition: data_sets.h:3233
float insOffset[3]
Definition: data_sets.h:1871
eImuStatus
Definition: data_sets.h:717
uint8_t error_code
Definition: data_sets.h:2085
struct PACKED imus_t
uint32_t elapsedTimeSec
Definition: data_sets.h:2855
uint32_t can_period_mult[NUM_CIDS]
Definition: data_sets.h:3389
float arThreshold
Definition: data_sets.h:2641
int32_t niter
Definition: data_sets.h:2180
uint32_t outlier
Definition: data_sets.h:1348
uint32_t calBitStatus
Definition: data_sets.h:1432
int32_t mode
Definition: data_sets.h:2114
is_can_uvw uvw
Definition: CAN_comm.h:257
uint32_t radioNID
Definition: data_sets.h:3038
struct PACKED inl2_status_t
double v[24]
Definition: data_sets.h:2036
double bv_ecef[3]
Definition: data_sets.h:2022
eGpsNavFixStatus
Definition: data_sets.h:268
uint8_t chi_square_error
Definition: data_sets.h:2076
float vel[3]
Definition: data_sets.h:793
uint32_t checksum
Definition: data_sets.h:1850
struct PACKED rmc_t
uint32_t maxDurationSec
Definition: data_sets.h:2849
float baseToRoverHeadingAcc
Definition: data_sets.h:2621
uint8_t large_v2b
Definition: data_sets.h:2056
#define DEVINFO_ADDINFO_STRLEN
Definition: data_sets.h:150
uint8_t svId
Definition: data_sets.h:810
float dt
Definition: data_sets.h:685
float msl
Definition: CAN_comm.h:165
double cis
Definition: data_sets.h:2395
int32_t stationId
Definition: data_sets.h:2503
float Tcal
Definition: data_sets.h:1357
uint8_t lack_of_valid_sats
Definition: data_sets.h:2074
uint32_t state
Definition: data_sets.h:2846
int32_t flag
Definition: data_sets.h:2341
magnetometer_t mag2
Definition: data_sets.h:700
float tcPqrLinearity
Definition: data_sets.h:1443
int32_t age
Definition: data_sets.h:2441
float distance
Definition: data_sets.h:1820
float omega_r
Definition: data_sets.h:1790
uint32_t loggerElapsedTimeMs
Definition: data_sets.h:2958
double maxtdiff
Definition: data_sets.h:2225
uint64_t bits
Definition: data_sets.h:1301
int32_t arfilter
Definition: data_sets.h:2147
obsd_t obs[MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE]
Definition: data_sets.h:2766
uGpsRawData data
Definition: data_sets.h:2803
int32_t sat
Definition: data_sets.h:2510
float baroTemp
Definition: data_sets.h:1045
eSurveyInStatus
Definition: data_sets.h:2821
#define SET_STATUS_OFFSET_MASK(result, val, offset, mask)
Definition: data_sets.h:1724
double e
Definition: data_sets.h:2528
uint32_t baseGpsObservationCount
Definition: data_sets.h:2662
#define MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE
Definition: data_sets.h:2301
sys_params_t sysParams
Definition: data_sets.h:3427
int mag_cal_done
Definition: data_sets.h:923
float mag[3]
Definition: data_sets.h:642
uint32_t psr
Definition: data_sets.h:3209
#define GPS_RAW_MESSAGE_BUF_SIZE
Definition: data_sets.h:2300
uint32_t wrap_count_r
Definition: data_sets.h:1796
double dtaun
Definition: data_sets.h:2465
float theta_l
Definition: data_sets.h:1781
float biasPqr[3]
Definition: data_sets.h:893
float averageRunTimeUs
Definition: data_sets.h:3310
uint32_t timeOfWeekMs
Definition: data_sets.h:747
struct PACKED wheel_encoder_t
struct PACKED ins_1_t
#define NUM_WIFI_PRESETS
Definition: data_sets.h:2999
struct PACKED sys_params_t
dual_imu_t imu
Definition: data_sets.h:696
uint16_t gnssSatSigConst
Definition: data_sets.h:1883
eSatSvFlags
Definition: data_sets.h:830
uint32_t gpzda
Definition: data_sets.h:1172
float barTemp
Definition: data_sets.h:659
struct PACKED inl2_ned_sigma_t
int32_t svh
Definition: data_sets.h:2332
#define PUSH_PACK_1
Definition: ISConstants.h:231
rtos_task_t task[UINS_RTOS_NUM_TASKS]
Definition: data_sets.h:3335
double OMGd
Definition: data_sets.h:2374
uint32_t eDataIDs
Definition: data_sets.h:32
double M0
Definition: data_sets.h:2368
imu_t imu
Definition: data_sets.h:3410
uint8_t code_outlier
Definition: data_sets.h:2044
struct PACKED rtos_info_t
uint32_t txBytesPerS
Definition: data_sets.h:3140
struct PACKED sys_sensors_adc_t
uint32_t h4xRadioBaudRate
Definition: data_sets.h:3074
double max_baseline_error
Definition: data_sets.h:2240
uint32_t gpioStatus
Definition: data_sets.h:1317
int32_t svconf
Definition: data_sets.h:2516
int satNumCalc(int gnssID, int svID)
Definition: data_sets.c:908
uint8_t divergent_pnt_pos_iteration
Definition: data_sets.h:2075
uint32_t roverSbasCount
Definition: data_sets.h:2719
double gainholdamb
Definition: data_sets.h:2222
#define WIFI_SSID_PSK_SIZE
Definition: data_sets.h:2968
uint32_t pins1
Definition: data_sets.h:1148
float diameter
Definition: data_sets.h:1823
float ana4
Definition: data_sets.h:1010
double f2
Definition: data_sets.h:2410
uint32_t port
Definition: data_sets.h:2986
double omg
Definition: data_sets.h:2365
struct PACKED ascii_msgs_t
double baseLla[3]
Definition: data_sets.h:2653
float pqr[3]
Definition: data_sets.h:603
#define NUM_IMU_DEVICES
Definition: data_sets.h:164
double bp_ecef[3]
Definition: data_sets.h:2021
#define HDW_BIT_MODE(hdwBitStatus)
Definition: data_sets.h:1382
struct PACKED dual_imu_t
uint8_t phase_outlier
Definition: data_sets.h:2045
int32_t gpsmodear
Definition: data_sets.h:2138
float tcAccLinearity
Definition: data_sets.h:1444
uint32_t timeOfWeekMs
Definition: data_sets.h:2946
uint8_t end_relpos
Definition: data_sets.h:2063
uint32_t key
Definition: data_sets.h:485
uint8_t receiverIndex
Definition: data_sets.h:2791
uint32_t week
Definition: data_sets.h:2943
eGpsStatus
Definition: data_sets.h:360
uint32_t checksum
Definition: data_sets.h:3014
uint32_t bits
Definition: data_sets.h:1811
uint32_t week
Definition: CAN_comm.h:26
float tcAccBias
Definition: data_sets.h:1436
uint32_t ser0BaudRate
Definition: data_sets.h:1862
eEvb2ComBridgePreset
Definition: data_sets.h:3083
void julianToDate(double julian, int32_t *year, int32_t *month, int32_t *day, int32_t *hour, int32_t *minute, int32_t *second, int32_t *millisecond)
Definition: data_sets.c:607
magnetometer_t mag
Definition: data_sets.h:3412
uint8_t cno
Definition: data_sets.h:813
struct PACKED gps_rtk_misc_t
gps_rtk_misc_t gpsRtkMisc
Definition: data_sets.h:3422
uint32_t handle
Definition: data_sets.h:3319
double OMG0
Definition: data_sets.h:2534
int att_aligned
Definition: data_sets.h:919
double L[1]
Definition: data_sets.h:2291
int32_t prn
Definition: data_sets.h:2478
int16_t theta1
Definition: CAN_comm.h:48
gtime_t toe
Definition: data_sets.h:2444
#define DEBUG_I_ARRAY_SIZE
Definition: data_sets.h:1981
double A
Definition: data_sets.h:2525
uint32_t timeOfWeekMs
Definition: data_sets.h:2812
float Wcal[9]
Definition: data_sets.h:1354
mag_cal_t magCal
Definition: data_sets.h:3413
int16_t vel2
Definition: CAN_comm.h:191
uint32_t radioPowerLevel
Definition: data_sets.h:3041
float magHdgOffset
Definition: data_sets.h:1356
float magInc
Definition: data_sets.h:905
int32_t iode
Definition: data_sets.h:2429
int zero_vel
Definition: data_sets.h:915
int32_t outsingle
Definition: data_sets.h:2256
int att_aligning
Definition: data_sets.h:920
double M0
Definition: data_sets.h:2540
uint32_t status
Definition: data_sets.h:3188
int ahrs
Definition: data_sets.h:910
float zeroVelRotation[3]
Definition: data_sets.h:1913
uint32_t g5Lr
Definition: data_sets.h:3203
ins_3_t ins3
Definition: data_sets.h:3408
int32_t minholdsats
Definition: data_sets.h:2162
float encoderTickToWheelRad
Definition: data_sets.h:3050
uint8_t warning_code
Definition: data_sets.h:2092
double timeOfWeek
Definition: data_sets.h:417
double ndot
Definition: data_sets.h:2419
double idot
Definition: data_sets.h:2377
uint32_t n
Definition: data_sets.h:2307
struct PACKED strobe_in_time_t
int32_t code
Definition: data_sets.h:2338
int gpsToNmeaGGA(const gps_pos_t *gps, char *buffer, int bufferLength)
Definition: data_sets.c:745
int zero_accel
Definition: data_sets.h:911
gtime_t tof
Definition: data_sets.h:2447
int32_t svh
Definition: data_sets.h:2435
uint32_t timeToFirstFixMs
Definition: data_sets.h:2734
uint32_t ppimu
Definition: data_sets.h:1145
#define NUM_ANA_CHANNELS
Definition: data_sets.h:1188
float hMSL
Definition: data_sets.h:759
wheel_encoder_t wheelEncoder
Definition: data_sets.h:3415
float baseToRoverDistance
Definition: data_sets.h:2615
uint32_t roverGlonassObservationCount
Definition: data_sets.h:2665
int32_t iodc
Definition: data_sets.h:2326
gtime_t toa
Definition: data_sets.h:2522
int accel_motion
Definition: data_sets.h:913
struct PACKED inl2_mag_obs_info_t
float reserved1
Definition: data_sets.h:1051
uint32_t roverGpsObservationCount
Definition: data_sets.h:2659
uint32_t roverBeidouEphemerisCount
Definition: data_sets.h:2707
eIoConfig
Definition: data_sets.h:1698
double double_debug[4]
Definition: data_sets.h:2094
uint32_t invCommand
Definition: data_sets.h:1112
f_t barTemp
Definition: data_sets.h:1194
struct PACKED gen_1axis_sensor_t
uint8_t obs_pairs_used
Definition: data_sets.h:2101
wheel_config_t wheelConfig
Definition: data_sets.h:1937
int32_t week
Definition: data_sets.h:2519
double gpsToUnix(uint32_t gpsWeek, uint32_t gpsTimeofWeekMS, uint8_t leapSeconds)
Definition: data_sets.c:699
uint32_t ser1BaudRate
Definition: data_sets.h:1865
uint32_t auto_recal
Definition: data_sets.h:1347
double cus
Definition: data_sets.h:2389
uint8_t waiting_for_base_packet
Definition: data_sets.h:2071
int ahrs_gps_cnt
Definition: data_sets.h:916
double crs
Definition: data_sets.h:2383
int32_t nv
Definition: data_sets.h:2032
float theta_r
Definition: data_sets.h:1784
double f1
Definition: data_sets.h:2407
uint32_t pins2
Definition: data_sets.h:1151
uint32_t serialNumChecksum32(const void *data, int size)
Definition: data_sets.c:551
uint32_t gapCount
Definition: data_sets.h:3313
uint32_t baseQzsObservationCount
Definition: data_sets.h:2686
float pDop
Definition: data_sets.h:768
double maxgdop
Definition: data_sets.h:2236
preintegrated_imu_t pImu
Definition: data_sets.h:3417
struct PACKED inl2_states_t
uint32_t baseAntennaCount
Definition: data_sets.h:2725
uint32_t ionUtcAlmCount
Definition: data_sets.h:2728
uint32_t lotNumber
Definition: data_sets.h:479
uint8_t bad_baseline_holdamb
Definition: data_sets.h:2050
uint32_t gpgsa
Definition: data_sets.h:1166
uint32_t buildNumber
Definition: data_sets.h:451
uint32_t numSats
Definition: data_sets.h:858
uint32_t startupGPSDtMs
Definition: data_sets.h:1928
double cuc
Definition: data_sets.h:2386
float vin
Definition: data_sets.h:1001
float minAccuracy
Definition: data_sets.h:2852
uint32_t command
Definition: data_sets.h:1109
PUSH_PACK_1 struct PACKED pos_measurement_t
float D[1]
Definition: data_sets.h:2297
float arRatio
Definition: data_sets.h:2609
uint32_t hdwStatus
Definition: CAN_comm.h:40
prcopt_t gps_rtk_opt_t
Definition: data_sets.h:2258
struct PACKED manufacturing_info_t
f_t humidity
Definition: data_sets.h:1195
uint32_t cbOptions
Definition: data_sets.h:3029
uint8_t hardwareVer[4]
Definition: data_sets.h:445
double i0
Definition: data_sets.h:2359
uint32_t ipAddr
Definition: data_sets.h:2983
uint32_t runTimeUs
Definition: data_sets.h:3304
uint32_t reserved
Definition: data_sets.h:439
struct PACKED ins_3_t
double rp_ecef[3]
Definition: data_sets.h:2018
uint8_t cbPreset
Definition: data_sets.h:3020
float cpuUsage
Definition: data_sets.h:3316
float magInclination
Definition: data_sets.h:1919
pos_measurement_t posMeasurement
Definition: data_sets.h:3416
float accuracyCovUD[6]
Definition: data_sets.h:426
float hDop
Definition: data_sets.h:2647
uint8_t waiting_for_rover_packet
Definition: data_sets.h:2070
int32_t maxout
Definition: data_sets.h:2150
int32_t glomodear
Definition: data_sets.h:2135
float mslBar
Definition: data_sets.h:656
uint8_t code[1]
Definition: data_sets.h:2279
uint8_t raw_ptr_queue_overrun
Definition: data_sets.h:2102
struct PACKED io_t
struct PACKED gps_version_t
uint8_t reserved1
Definition: data_sets.h:2089
float declination
Definition: data_sets.h:1338
uint32_t roverGpsEphemerisCount
Definition: data_sets.h:2689
eRTKConfigBits
Definition: data_sets.h:1530
uint8_t swVersion[30]
Definition: data_sets.h:868
double elmin
Definition: data_sets.h:2126
double A
Definition: data_sets.h:2353
float nis_threshold
Definition: data_sets.h:1353
float PvelNED[3]
Definition: data_sets.h:1952
uint32_t genFaultCode
Definition: data_sets.h:1066
uint8_t start_relpos
Definition: data_sets.h:2061
struct PACKED preintegrated_imu_t
sta_t sta
Definition: data_sets.h:2778
struct PACKED wheel_config_t
uint8_t buf[GPS_RAW_MESSAGE_BUF_SIZE]
Definition: data_sets.h:2784
ins_4_t ins4
Definition: data_sets.h:3409
eph_t eph
Definition: data_sets.h:2769
char addInfo[DEVINFO_ADDINFO_STRLEN]
Definition: data_sets.h:469
float tcPqrSlope
Definition: data_sets.h:1439
float baseToRoverHeading
Definition: data_sets.h:2618
float sAcc
Definition: data_sets.h:796
int32_t minfix
Definition: data_sets.h:2171
double OMGd
Definition: data_sets.h:2543
int zero_angrate
Definition: data_sets.h:912
int32_t sva
Definition: data_sets.h:2438
uint8_t buildDate[4]
Definition: data_sets.h:463
int64_t time
Definition: data_sets.h:2009
double lla[3]
Definition: data_sets.h:511
int16_t theta2
Definition: CAN_comm.h:49
float magInsHdgDelta
Definition: data_sets.h:1351
uint32_t roverGlonassEphemerisCount
Definition: data_sets.h:2695
eMagRecalMode
Definition: data_sets.h:1320
void flipDoubles(uint8_t *data, int dataLength, int offset, uint16_t *offsets, uint16_t offsetsLength)
Definition: data_sets.c:91
uint16_t * getDoubleOffsets(eDataIDs dataId, uint16_t *offsetsLength)
Definition: data_sets.c:141
double flipDoubleCopy(double val)
Definition: data_sets.c:60
float PattNED[3]
Definition: data_sets.h:1954
double thresslip
Definition: data_sets.h:2216
float magDeclination
Definition: data_sets.h:1922
double cic
Definition: data_sets.h:2392
eRtkSolStatus
Definition: data_sets.h:2578
eEvbFlashCfgBits
Definition: data_sets.h:2990
uint8_t gdop_error
Definition: data_sets.h:2090
double omg
Definition: data_sets.h:2537
int32_t svh
Definition: data_sets.h:2513
uint32_t status
Definition: CAN_comm.h:114
struct PACKED ins_output_t
union PACKED uGpsRawData
uint32_t gpgll
Definition: data_sets.h:1163
uint32_t baseSbasCount
Definition: data_sets.h:2722
f_t ana[NUM_ANA_CHANNELS]
Definition: data_sets.h:1196
char manufacturer[DEVINFO_MANUFACTURER_STRLEN]
Definition: data_sets.h:460
uint8_t rescode_err_marker
Definition: data_sets.h:2083
uint32_t sensorConfig
Definition: data_sets.h:1934
double qr[6]
Definition: data_sets.h:2023
uint8_t pnt_pos_error
Definition: data_sets.h:2065
int32_t maxaveep
Definition: data_sets.h:2253
sys_sensors_t sysSensors
Definition: data_sets.h:3428
int32_t bdsmodear
Definition: data_sets.h:2144
float PBaroBias
Definition: data_sets.h:1960
uint32_t count
Definition: data_sets.h:1978
uint32_t RTKCfgBits
Definition: data_sets.h:1931
float gps1AntOffset[3]
Definition: data_sets.h:1874
int32_t modear
Definition: data_sets.h:2132
int32_t refpos
Definition: data_sets.h:2189
struct PACKED barometer_t
float magHdg
Definition: data_sets.h:1349
uint32_t ioConfig
Definition: data_sets.h:1904
uint32_t key
Definition: data_sets.h:3017
eCalBitStatusFlags
Definition: data_sets.h:1396
#define INS_STATUS_SOLUTION(insStatus)
Definition: data_sets.h:213
float insRotation[3]
Definition: data_sets.h:1868
dev_info_t devInfo
Definition: data_sets.h:3405
uint8_t code_large_residual
Definition: data_sets.h:2046
gtime_t toe
Definition: data_sets.h:2344
int ubxSys(int gnssID)
Definition: data_sets.c:849
float tcPqrBias
Definition: data_sets.h:1435
float gpsMinimumElevation
Definition: data_sets.h:1940
int32_t sbsmodear
Definition: data_sets.h:2141
def insStatus(istatus)
INS Status #####.
uint8_t insDynModel
Definition: data_sets.h:1877
uint32_t baseGalileoEphemerisCount
Definition: data_sets.h:2704
uint8_t obs_pairs_filtered
Definition: data_sets.h:2100
int16_t vel1
Definition: CAN_comm.h:181
uint32_t wifiIpAddr
Definition: data_sets.h:2961
int32_t tow
Definition: data_sets.h:2475
gtime_t ttr
Definition: data_sets.h:2350
uint8_t rcv
Definition: data_sets.h:2270
uint8_t use_ubx_position
Definition: data_sets.h:2055
rmc_t rmc
Definition: data_sets.h:3432
double varholdamb
Definition: data_sets.h:2219
double deln
Definition: data_sets.h:2371
int32_t mindropsats
Definition: data_sets.h:2165
uint32_t freeHeapSize
Definition: data_sets.h:3326
f_t bar
Definition: data_sets.h:1193
uint32_t activeCalSet
Definition: data_sets.h:1355
struct PACKED gps_rtk_rel_t
struct PACKED gen_3axis_sensord_t
int32_t sat
Definition: data_sets.h:2426
eWheelCfgBits
Definition: data_sets.h:1800
float acc[3]
Definition: data_sets.h:606
uint8_t debug[2]
Definition: data_sets.h:2096
uint32_t insStatus
Definition: CAN_comm.h:37
uint32_t roverGalileoEphemerisCount
Definition: data_sets.h:2701
sensors_mpu_w_temp_t mpu[NUM_IMU_DEVICES]
Definition: data_sets.h:1192
double time
Definition: data_sets.h:614
obsd_t * data
Definition: data_sets.h:2313
float tcAccSlope
Definition: data_sets.h:1440
struct PACKED nvm_flash_cfg_t
int fix_reset_base_msgs
Definition: data_sets.h:2228
uint32_t maxRunTimeUs
Definition: data_sets.h:3307
uint8_t reset_bias
Definition: data_sets.h:2060
#define MAX_TASK_NAME_LEN
Definition: data_sets.h:3286
ROSCPP_DECL bool del(const std::string &key)
uint8_t rover_position_error
Definition: data_sets.h:2059
double Adot
Definition: data_sets.h:2416
float differentialAge
Definition: data_sets.h:2606
#define MAX_NUM_SAT_CHANNELS
Definition: data_sets.h:146
uint32_t baseGalileoObservationCount
Definition: data_sets.h:2674
uint8_t base_position_error
Definition: data_sets.h:2051
uint32_t periodMs
Definition: data_sets.h:3301
int32_t snrmin
Definition: data_sets.h:2129
float theta[3]
Definition: data_sets.h:505
struct PACKED sys_sensors_t
uint32_t baseGlonassEphemerisCount
Definition: data_sets.h:2698
struct PACKED sensors_mpu_w_temp_t
uint32_t pgpsp
Definition: data_sets.h:1154
eEvbStatus
Definition: data_sets.h:2865
uint32_t gpsTimeSyncPeriodMs
Definition: data_sets.h:1925
int32_t minfixsats
Definition: data_sets.h:2159
int32_t week
Definition: data_sets.h:2472
uint32_t serialNumber
Definition: data_sets.h:442
uint32_t lastLlaWeek
Definition: data_sets.h:1898
uint8_t lsq_error
Definition: data_sets.h:2073
struct PACKED debug_string_t
uint32_t sysCfgBits
Definition: data_sets.h:1886
uint32_t baseQzsEphemerisCount
Definition: data_sets.h:2716
int32_t maxrej
Definition: data_sets.h:2153
magnetometer_t mag1
Definition: data_sets.h:699
uint32_t mallocSize
Definition: data_sets.h:3329
eEvb2PortOptions
Definition: data_sets.h:2931
uint32_t size
Definition: data_sets.h:3011
struct PACKED obsd_t
float ned[3]
Definition: data_sets.h:514
float biasAcc[3]
Definition: data_sets.h:896
double reset_baseline_error
Definition: data_sets.h:2241
barometer_t baro
Definition: data_sets.h:3414
float e_i2l[3]
Definition: data_sets.h:1814
#define POP_PACK
Definition: ISConstants.h:234
uint8_t invalid_base_position
Definition: data_sets.h:2049
gps_rtk_rel_t gpsRtkRel
Definition: data_sets.h:3421
uint32_t cycle_slips
Definition: data_sets.h:2078
double f0
Definition: data_sets.h:2549
double ecef[3]
Definition: data_sets.h:420
union PACKED uInsOutDatasets
struct PACKED pimu_mag_t
uint32_t g4
Definition: data_sets.h:3200
struct PACKED gen_dual_3axis_sensor_t
uint8_t obs_count_bas
Definition: data_sets.h:2097
float dist2base
Definition: data_sets.h:2087
double maxnis
Definition: data_sets.h:2233
float psi
Definition: data_sets.h:423
struct PACKED bit_t
float imuTemp
Definition: data_sets.h:1042
uint8_t raw_dat_queue_overrun
Definition: data_sets.h:2103
gps_sat_sv_t sat[MAX_NUM_SAT_CHANNELS]
Definition: data_sets.h:860
float ana1
Definition: data_sets.h:1004
uint16_t * getStringOffsetsLengths(eDataIDs dataId, uint16_t *offsetsLength)
Definition: data_sets.c:382
eEvb2ComBridgeOptions
Definition: data_sets.h:2919
int32_t sat
Definition: data_sets.h:2320
nvm_flash_cfg_t flashCfg
Definition: data_sets.h:3425
struct PACKED magnetometer_t
uint32_t ready
Definition: data_sets.h:1345
struct PACKED system_command_t
float zeroVelOffset[3]
Definition: data_sets.h:1916
survey_in_t surveyIn
Definition: data_sets.h:3426
uint32_t rxBytesPerS
Definition: data_sets.h:3143
struct PACKED gps_raw_t
rtos_info_t rtosInfo
Definition: data_sets.h:3429
uint64_t didToRmcBit(uint32_t dataId, uint64_t defaultRmcBits)
Definition: data_sets.c:563
uint8_t obs_count_rov
Definition: data_sets.h:2098
float ana3
Definition: data_sets.h:1007
void flipEndianess32(uint8_t *data, int dataLength)
Definition: data_sets.c:73
double maxinnophase
Definition: data_sets.h:2232
uint8_t buildTime[4]
Definition: data_sets.h:466
ion_model_utc_alm_t ion
Definition: data_sets.h:2781
uint8_t protocolVer[4]
Definition: data_sets.h:454
struct PACKED ins_4_t
uint32_t flashChecksum32(const void *data, int size)
Definition: data_sets.c:557
float ubx_error
Definition: data_sets.h:2080
struct PACKED rtos_task_t
inl2_ned_sigma_t inl2NedSigma
Definition: data_sets.h:3424
int8_t elev
Definition: data_sets.h:816
double f1
Definition: data_sets.h:2552
uint32_t roverGalileoObservationCount
Definition: data_sets.h:2671
uint8_t firmwareVer[4]
Definition: data_sets.h:448
int32_t nf
Definition: data_sets.h:2120
double sensorTruePeriod
Definition: data_sets.h:1060
float hAcc
Definition: data_sets.h:762
struct PACKED ins_2_t
uint32_t can_transmit_address[NUM_CIDS]
Definition: data_sets.h:3392
uint32_t g2FileNum
Definition: data_sets.h:3194
eSystemCommand
Definition: data_sets.h:1116
uint32_t baseBeidouObservationCount
Definition: data_sets.h:2680
uint32_t hdwBitStatus
Definition: data_sets.h:1429
uint32_t roverBeidouObservationCount
Definition: data_sets.h:2677
uint32_t pin
Definition: data_sets.h:1975
float vAcc
Definition: data_sets.h:765
float qe2b[4]
Definition: data_sets.h:589
int32_t soltype
Definition: data_sets.h:2117
float PDeclination
Definition: data_sets.h:1962
int32_t sva
Definition: data_sets.h:2329
uint32_t loggerMode
Definition: data_sets.h:2955
float mcuTemp
Definition: data_sets.h:1048
float accuracyPos[3]
Definition: data_sets.h:2635
int32_t dynamics
Definition: data_sets.h:2177
uint32_t portOptions
Definition: data_sets.h:3068
uint32_t roverQzsEphemerisCount
Definition: data_sets.h:2713
geph_t gloEph
Definition: data_sets.h:2772
struct PACKED gps_vel_t
uint32_t can_receive_address
Definition: data_sets.h:3398
uint8_t solStatus
Definition: data_sets.h:2082
int16_t prRes
Definition: data_sets.h:822
POP_PACK uint32_t checksum32(const void *data, int count)
Definition: data_sets.c:531
#define DEBUG_STRING_SIZE
Definition: data_sets.h:1993
int32_t intpref
Definition: data_sets.h:2183
uint8_t obsCount
Definition: data_sets.h:2797
eEvb2LoggerMode
Definition: data_sets.h:3117
sys_sensors_adc_t sensorsAdc
Definition: data_sets.h:3431
float gps2AntOffset[3]
Definition: data_sets.h:1910
uint32_t baseBeidouEphemerisCount
Definition: data_sets.h:2710
int rot_motion
Definition: data_sets.h:914
uint8_t outc_ovfl
Definition: data_sets.h:2053
is_can_time time
Definition: CAN_comm.h:252
struct PACKED rtk_debug_t
uint32_t pimu
Definition: data_sets.h:1142
double elmaskhold
Definition: data_sets.h:2213
uint8_t moveb_time_sync_error
Definition: data_sets.h:2069
struct PACKED gen_3axis_sensor_t
struct PACKED dev_info_t
uint8_t dataType
Definition: data_sets.h:2794
#define NUM_SERIAL_PORTS
Definition: data_sets.h:1201
uint8_t s[DEBUG_STRING_SIZE]
Definition: data_sets.h:1998
float t_i2l[3]
Definition: data_sets.h:1817
int32_t frq
Definition: data_sets.h:2432
float flipFloatCopy(float val)
Definition: data_sets.c:31
eHdwBitStatusFlags
Definition: data_sets.h:1375
eEvbRtosTask
Definition: data_sets.h:3258
uint32_t can_baudrate_kbps
Definition: data_sets.h:3395
float biasBaro
Definition: data_sets.h:899
float att_err
Definition: data_sets.h:917
double gpsToJulian(int32_t gpsWeek, int32_t gpsMilliseconds, int32_t leapSeconds)
Definition: data_sets.c:708
uint32_t radioPID
Definition: data_sets.h:3035
uint8_t phase_large_residual
Definition: data_sets.h:2048
uint32_t Ncal_samples
Definition: data_sets.h:1344
uint32_t calibrated
Definition: data_sets.h:1346
float val1[3]
Definition: data_sets.h:954
uint32_t stackUnused
Definition: data_sets.h:3298
uint32_t startupNavDtMs
Definition: data_sets.h:1859
double fit
Definition: data_sets.h:2401
uint8_t extension[30]
Definition: data_sets.h:872
uint32_t nmax
Definition: data_sets.h:2310
uint8_t uinsComPort
Definition: data_sets.h:3059
float omega_l
Definition: data_sets.h:1787
float accSigma
Definition: data_sets.h:1456
eHdwStatusFlags
Definition: data_sets.h:277
eSysConfigBits
Definition: data_sets.h:1462
uint32_t imuPeriodMs
Definition: data_sets.h:1054
uint8_t sat_id_i[24]
Definition: data_sets.h:2033
uint32_t freeSize
Definition: data_sets.h:3332
preintegrated_imu_t pimu
Definition: data_sets.h:708
float temp
Definition: data_sets.h:977
uint8_t SNR[1]
Definition: data_sets.h:2273
struct PACKED imu_mag_t
float PWBias[3]
Definition: data_sets.h:1958
char name[MAX_TASK_NAME_LEN]
Definition: data_sets.h:3292
uint32_t navPeriodMs
Definition: data_sets.h:1057
eGnssSatSigConst
Definition: data_sets.h:1505
uint8_t diff_age_error
Definition: data_sets.h:2068
struct PACKED rtk_state_t
uint32_t can_receive_address
Definition: data_sets.h:3056
f_t temp
Definition: data_sets.h:1185
int32_t minlock
Definition: data_sets.h:2156
float cnoMean
Definition: data_sets.h:771
uint32_t cycleSlipCount
Definition: data_sets.h:2656
uint32_t size
uint32_t state
Definition: data_sets.h:1426
double ra_ecef[3]
Definition: data_sets.h:2020
float magDec
Definition: data_sets.h:902
uint8_t qualL[1]
Definition: data_sets.h:2282
double qb[24]
Definition: data_sets.h:2025
gps_sat_t gpsSat
Definition: data_sets.h:3420
eSensorConfig
Definition: data_sets.h:1653
#define PUSH_PACK_8
Definition: ISConstants.h:233
uint32_t roverQzsObservationCount
Definition: data_sets.h:2683
struct PACKED gps_sat_sv_t
float reserved2[2]
Definition: data_sets.h:1063
uint32_t pc
Definition: data_sets.h:3206
uint32_t cBrdConfig
Definition: data_sets.h:1907
uint32_t baseGlonassObservationCount
Definition: data_sets.h:2668
#define DEBUG_F_ARRAY_SIZE
Definition: data_sets.h:1982
double OMG0
Definition: data_sets.h:2362
struct PACKED evb_rtos_info_t
double crc
Definition: data_sets.h:2380
struct PACKED mag_cal_t
uint32_t priority
Definition: data_sets.h:3295
uint32_t h8gpioBaudRate
Definition: data_sets.h:3077
uint8_t error_count
Definition: data_sets.h:2084
uint8_t uinsAuxPort
Definition: data_sets.h:3062
uint32_t CANbaud_kbps
Definition: data_sets.h:3053
eInsDynModel
Definition: data_sets.h:1827
char date[16]
Definition: data_sets.h:482
eRawDataType
Definition: data_sets.h:2739
double e
Definition: data_sets.h:2356
dual_imu_t dualImu
Definition: data_sets.h:3411
int mag_cal_good
Definition: data_sets.h:922
sbsmsg_t sbas
Definition: data_sets.h:2775
eGenFaultCodes
Definition: data_sets.h:1070
double toas
Definition: data_sets.h:2546
void flipDouble(void *ptr)
Definition: data_sets.c:47
int att_coarse
Definition: data_sets.h:918
uint32_t flags
Definition: data_sets.h:825


inertial_sense_ros
Author(s):
autogenerated on Sat Sep 19 2020 03:19:04