data_sets.h
Go to the documentation of this file.
1 /*
2 MIT LICENSE
3 
4 Copyright (c) 2014-2021 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 
641  uint8_t imu1ok;
642  uint8_t imu2ok;
643  uint8_t reserved1;
644  uint8_t reserved2;
645 } dual_imu_ok_t;
646 
647 
649 typedef struct PACKED
650 {
652  double time;
653 
655  float mag[3];
657 
658 
660 typedef struct PACKED
661 {
663  double time;
664 
666  float bar;
667 
669  float mslBar;
670 
672  float barTemp;
673 
675  float humidity;
676 } barometer_t;
677 
678 
680 typedef struct PACKED
681 {
683  double time;
684 
686  float theta1[3];
687 
689  float theta2[3];
690 
692  float vel1[3];
693 
695  float vel2[3];
696 
698  float dt;
699 
701  uint32_t status;
703 
704 
706 typedef struct PACKED
707 {
709  dual_imu_t imu;
710 
714 } imu_mag_t;
715 
716 
718 typedef struct PACKED
719 {
722 
726 } pimu_mag_t;
727 
728 
731 {
740 
742  IMU_STATUS_RESERVED1 = (int)0x00000020,
743 
745  IMU_STATUS_RESERVED2 = (int)0x00000040,
746 
747 // /** Sensor saturation happened within past 10 seconds */
748 // IMU_STATUS_SATURATION_HISTORY = (int)0x00000100,
749 // /** Sample rate fault happened within past 10 seconds */
750 // IMU_STATUS_SAMPLE_RATE_FAULT_HISTORY = (int)0x00000200,
751 };
752 
754 typedef struct PACKED
755 {
757  uint32_t week;
758 
760  uint32_t timeOfWeekMs;
761 
763  uint32_t status;
764 
766  double ecef[3];
767 
769  double lla[3];
770 
772  float hMSL;
773 
775  float hAcc;
776 
778  float vAcc;
779 
781  float pDop;
782 
784  float cnoMean;
785 
787  double towOffset;
788 
790  uint8_t leapS;
791 
793  uint8_t reserved[3];
794 
795 } gps_pos_t;
796 
797 
799 typedef struct PACKED
800 {
802  uint32_t timeOfWeekMs;
803 
806  float vel[3];
807 
809  float sAcc;
810 
812  uint32_t status;
813 } gps_vel_t;
814 
815 
817 typedef struct PACKED
818 {
820  uint8_t gnssId;
821 
823  uint8_t svId;
824 
826  uint8_t cno;
827 
829  int8_t elev;
830 
832  int16_t azim;
833 
835  int16_t prRes;
836 
838  uint32_t flags;
839 } gps_sat_sv_t;
840 
841 
844 {
846  SAT_SV_FLAGS_SV_USED = 0x00000008,
849  SAT_SV_FLAGS_DIFFCORR = 0x00000040,
850  SAT_SV_FLAGS_SMOOTHED = 0x00000080,
853  SAT_SV_FLAGS_EPHAVAIL = 0x00000800,
854  SAT_SV_FLAGS_ALMAVAIL = 0x00001000,
855  SAT_SV_FLAGS_ANOAVAIL = 0x00002000,
856  SAT_SV_FLAGS_AOPAVAIL = 0x00004000,
857 
858  SAT_SV_FLAGS_RTK_SOL_FIX_STATUS_MASK = 0x03000000, // 1=float, 2=fix, 3=hold
863 };
864 
866 typedef struct PACKED
867 {
869  uint32_t timeOfWeekMs;
871  uint32_t numSats;
874 } gps_sat_t;
875 
876 
878 typedef struct PACKED
879 {
881  uint8_t swVersion[30];
883  uint8_t hwVersion[10];
885  uint8_t extension[30];
887  uint8_t reserved[2];
888 } gps_version_t;
889 
890 // (DID_INL2_STATES) INL2 - INS Extended Kalman Filter (EKF) states
891 typedef struct PACKED
892 {
894  double timeOfWeek;
895 
897  float qe2b[4];
898 
900  float ve[3];
901 
903  double ecef[3];
904 
906  float biasPqr[3];
907 
909  float biasAcc[3];
910 
912  float biasBaro;
913 
915  float magDec;
916 
918  float magInc;
919 } inl2_states_t;
920 
921 typedef struct PACKED
922 {
923  int ahrs;
928  int zero_vel;
929  int ahrs_gps_cnt; // Counter of sequential valid GPS data (for switching from AHRS to navigation)
930  float att_err;
931  int att_coarse; // Flag whether initial attitude error converged
932  int att_aligned; // Flag whether initial attitude error converged
934  int start_proc_done; // Cold/hot start procedure completed
938 } inl2_status_t;
939 
941 typedef struct PACKED
942 {
944  double time;
945 
947  float val;
949 
951 typedef struct PACKED
952 {
954  double time;
955 
957  float val[3];
959 
961 typedef struct PACKED
962 {
964  double time;
965 
967  float val1[3];
968 
970  float val2[3];
972 
974 typedef struct PACKED
975 {
977  double time;
978 
980  double val[3];
982 
984 typedef struct PACKED
985 {
987  double time;
988 
990  float temp;
991 
993  float pqr[3];
994 
996  float acc[3];
997 
999  float mag[3];
1000 
1002  float bar;
1003 
1005  float barTemp;
1006 
1008  float mslBar;
1009 
1011  float humidity;
1012 
1014  float vin;
1015 
1017  float ana1;
1018 
1020  float ana3;
1021 
1023  float ana4;
1024 } sys_sensors_t;
1025 
1027 typedef struct PACKED
1028 {
1030  uint32_t timeOfWeekMs;
1031 
1033  double lla[3];
1034 
1036  float uvw[3];
1037 
1039  float qn2b[4];
1040 } ins_output_t;
1041 
1043 typedef struct PACKED
1044 {
1046  uint32_t timeOfWeekMs;
1047 
1049  uint32_t insStatus;
1050 
1052  uint32_t hdwStatus;
1053 
1055  float imuTemp;
1056 
1058  float baroTemp;
1059 
1061  float mcuTemp;
1062 
1064  float reserved1;
1065 
1067  uint32_t imuPeriodMs;
1068 
1070  uint32_t navPeriodMs;
1071 
1074 
1076  float reserved2[2];
1077 
1079  uint32_t genFaultCode;
1080 } sys_params_t;
1081 
1084 {
1094  GFC_INIT_SENSORS = 0x00000100,
1096  GFC_INIT_SPI = 0x00000200,
1098  GFC_CONFIG_SPI = 0x00000400,
1100  GFC_INIT_GPS1 = 0x00000800,
1102  GFC_INIT_GPS2 = 0x00001000,
1115 };
1116 
1117 
1119 typedef struct PACKED
1120 {
1122  uint32_t command;
1123 
1125  uint32_t invCommand;
1126 
1128 
1130 {
1136 
1141  SYS_CMD_MANF_UNLOCK = 1122334455,
1142  SYS_CMD_MANF_FACTORY_RESET = 1357924680, // SYS_CMD_MANF_RESET_UNLOCK must be sent prior to this command.
1143  SYS_CMD_MANF_CHIP_ERASE = 1357924681, // SYS_CMD_MANF_RESET_UNLOCK must be sent prior to this command.
1144 };
1145 
1146 
1147 
1149 typedef struct PACKED
1150 {
1152  uint32_t options;
1153 
1155  uint16_t pimu;
1156 
1158  uint16_t ppimu;
1159 
1161  uint16_t pins1;
1162 
1164  uint16_t pins2;
1165 
1167  uint16_t pgpsp;
1168 
1170  uint16_t reserved;
1171 
1173  uint16_t gpgga;
1174 
1176  uint16_t gpgll;
1177 
1179  uint16_t gpgsa;
1180 
1182  uint16_t gprmc;
1183 
1185  uint16_t gpzda;
1186 
1188  uint16_t pashr;
1189 
1190 } ascii_msgs_t;
1191 
1193 typedef struct PACKED
1194 {
1196  uint32_t options;
1197 
1199  uint32_t pimu;
1200 
1202  uint32_t ppimu;
1203 
1205  uint32_t pins1;
1206 
1208  uint32_t pins2;
1209 
1211  uint32_t pgpsp;
1212 
1214  uint32_t reserved;
1215 
1217  uint32_t gpgga;
1218 
1220  uint32_t gpgll;
1221 
1223  uint32_t gpgsa;
1224 
1226  uint32_t gprmc;
1227 
1229  uint32_t gpzda;
1230 
1232  uint32_t pashr;
1233 
1235 
1236 /* (DID_SENSORS_CAL1, DID_SENSORS_CAL2) */
1237 typedef struct PACKED
1238 { // Units only apply for calibrated data
1239  f_t pqr[3]; // (rad/s) Angular rate
1240  f_t acc[3]; // (m/s^2) Linear acceleration
1241  f_t mag[3]; // (uT) Magnetometers
1242  f_t temp; // (°C) Temperature of MPU
1244 
1245 #define NUM_ANA_CHANNELS 4
1246 typedef struct PACKED
1247 { // LSB units for all except temperature, which is Celsius.
1248  double time;
1250  f_t bar; // Barometric pressure
1251  f_t barTemp; // Temperature of barometric pressure sensor
1252  f_t humidity; // Relative humidity as a percent (%rH). Range is 0% - 100%
1253  f_t ana[NUM_ANA_CHANNELS]; // ADC analog input
1255 
1256 #define NUM_COM_PORTS 4 // Number of communication ports. (Ser0, Ser1, Ser2, and USB).
1257 #ifndef NUM_SERIAL_PORTS
1258 #define NUM_SERIAL_PORTS 6
1259 #endif
1260 
1268 #define RMC_OPTIONS_PORT_MASK 0x000000FF
1269 #define RMC_OPTIONS_PORT_ALL (RMC_OPTIONS_PORT_MASK)
1270 #define RMC_OPTIONS_PORT_CURRENT 0x00000000
1271 #define RMC_OPTIONS_PORT_SER0 0x00000001
1272 #define RMC_OPTIONS_PORT_SER1 0x00000002 // also SPI
1273 #define RMC_OPTIONS_PORT_SER2 0x00000004
1274 #define RMC_OPTIONS_PORT_USB 0x00000008
1275 #define RMC_OPTIONS_PRESERVE_CTRL 0x00000100 // Prevent any messages from getting turned off by bitwise OR'ing new message bits with current message bits.
1276 #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.
1277 
1278 // RMC message data rates:
1279 #define RMC_BITS_INS1 0x0000000000000001 // rmc.insPeriodMs (4ms default)
1280 #define RMC_BITS_INS2 0x0000000000000002 // "
1281 #define RMC_BITS_INS3 0x0000000000000004 // "
1282 #define RMC_BITS_INS4 0x0000000000000008 // "
1283 #define RMC_BITS_DUAL_IMU 0x0000000000000010 // DID_FLASH_CONFIG.startupNavDtMs (4ms default)
1284 #define RMC_BITS_PREINTEGRATED_IMU 0x0000000000000020 // "
1285 #define RMC_BITS_BAROMETER 0x0000000000000040 // ~8ms
1286 #define RMC_BITS_MAGNETOMETER1 0x0000000000000080 // ~10ms
1287 #define RMC_BITS_MAGNETOMETER2 0x0000000000000100 // "
1288 
1289 #define RMC_BITS_GPS1_POS 0x0000000000000400 // DID_FLASH_CONFIG.startupGpsDtMs (200ms default)
1290 #define RMC_BITS_GPS2_POS 0x0000000000000800 // "
1291 #define RMC_BITS_GPS1_RAW 0x0000000000001000 // "
1292 #define RMC_BITS_GPS2_RAW 0x0000000000002000 // "
1293 #define RMC_BITS_GPS1_SAT 0x0000000000004000 // 1s
1294 #define RMC_BITS_GPS2_SAT 0x0000000000008000 // "
1295 #define RMC_BITS_GPS_BASE_RAW 0x0000000000010000 //
1296 #define RMC_BITS_STROBE_IN_TIME 0x0000000000020000 // On strobe input event
1297 #define RMC_BITS_DIAGNOSTIC_MESSAGE 0x0000000000040000
1298 #define RMC_BITS_DUAL_IMU_RAW 0x0000000000080000 // DID_FLASH_CONFIG.startupImuDtMs (1ms default)
1299 #define RMC_BITS_GPS1_VEL 0x0000000000100000 // DID_FLASH_CONFIG.startupGpsDtMs (200ms default)
1300 #define RMC_BITS_GPS2_VEL 0x0000000000200000 // "
1301 #define RMC_BITS_GPS1_UBX_POS 0x0000000000400000 // "
1302 #define RMC_BITS_GPS1_RTK_POS 0x0000000000800000 // "
1303 #define RMC_BITS_GPS1_RTK_POS_REL 0x0000000001000000 // "
1304 #define RMC_BITS_GPS1_RTK_POS_MISC 0x0000000004000000 // "
1305 #define RMC_BITS_INL2_NED_SIGMA 0x0000000008000000
1306 #define RMC_BITS_RTK_STATE 0x0000000010000000
1307 #define RMC_BITS_RTK_CODE_RESIDUAL 0x0000000020000000
1308 #define RMC_BITS_RTK_PHASE_RESIDUAL 0x0000000040000000
1309 #define RMC_BITS_WHEEL_ENCODER 0x0000000080000000
1310 #define RMC_BITS_WHEEL_CONFIG 0x0000000100000000
1311 #define RMC_BITS_DUAL_IMU_MAG_RAW 0x0000000200000000
1312 #define RMC_BITS_DUAL_IMU_MAG 0x0000000400000000
1313 #define RMC_BITS_PREINTEGRATED_IMU_MAG 0x0000000800000000
1314 #define RMC_BITS_GPS1_RTK_HDG_REL 0x0000001000000000 // DID_FLASH_CONFIG.startupGpsDtMs (200ms default)
1315 #define RMC_BITS_GPS1_RTK_HDG_MISC 0x0000002000000000 // "
1316 #define RMC_BITS_MASK 0x0FFFFFFFFFFFFFFF
1317 #define RMC_BITS_INTERNAL_PPD 0x4000000000000000 //
1318 #define RMC_BITS_PRESET 0x8000000000000000 // Indicate BITS is a preset
1319 
1320 #define RMC_PRESET_PPD_NAV_PERIOD_MULT 25
1321 #define RMC_PRESET_INS_NAV_PERIOD_MULT 1 // fastest rate (nav filter update rate)
1322 
1323 // Preset: Post Processing Data
1324 #define RMC_PRESET_PPD_BITS_NO_IMU (RMC_BITS_PRESET \
1325  | RMC_BITS_INS2 \
1326  | RMC_BITS_BAROMETER \
1327  | RMC_BITS_MAGNETOMETER1 \
1328  | RMC_BITS_MAGNETOMETER2 \
1329  | RMC_BITS_GPS1_POS \
1330  | RMC_BITS_GPS2_POS \
1331  | RMC_BITS_GPS1_VEL \
1332  | RMC_BITS_GPS2_VEL \
1333  | RMC_BITS_GPS1_RAW \
1334  | RMC_BITS_GPS2_RAW \
1335  | RMC_BITS_GPS_BASE_RAW \
1336  | RMC_BITS_GPS1_RTK_POS_REL \
1337  | RMC_BITS_GPS1_RTK_HDG_REL \
1338  | RMC_BITS_INTERNAL_PPD \
1339  | RMC_BITS_DIAGNOSTIC_MESSAGE)
1340 #define RMC_PRESET_PPD_BITS (RMC_PRESET_PPD_BITS_NO_IMU \
1341  | RMC_BITS_PREINTEGRATED_IMU)
1342 #define RMC_PRESET_INS_BITS (RMC_BITS_INS2 \
1343  | RMC_BITS_GPS1_POS \
1344  | RMC_BITS_PRESET)
1345 #define RMC_PRESET_PPD_BITS_RAW_IMU (RMC_PRESET_PPD_BITS_NO_IMU \
1346  | RMC_BITS_DUAL_IMU_RAW)
1347 #define RMC_PRESET_PPD_BITS_RTK_DBG (RMC_PRESET_PPD_BITS \
1348  | RMC_BITS_RTK_STATE \
1349  | RMC_BITS_RTK_CODE_RESIDUAL \
1350  | RMC_BITS_RTK_PHASE_RESIDUAL)
1351 #define RMC_PRESET_PPD_ROBOT (RMC_PRESET_PPD_BITS\
1352  | RMC_BITS_WHEEL_ENCODER \
1353  | RMC_BITS_WHEEL_CONFIG)
1354 
1356 typedef struct PACKED
1357 {
1359  uint64_t bits;
1360 
1362  uint32_t options;
1363 
1365 } rmc_t;
1366 
1367 
1369 typedef struct PACKED
1370 {
1372  uint32_t timeOfWeekMs;
1373 
1375  uint32_t gpioStatus;
1376 } io_t;
1377 
1379 {
1381  MAG_RECAL_CMD_MULTI_AXIS = (int)1, // Recalibrate magnetometers using multiple axis
1382  MAG_RECAL_CMD_SINGLE_AXIS = (int)2, // Recalibrate magnetometers using only one axis
1383  MAG_RECAL_CMD_ABORT = (int)101, // Stop mag recalibration
1384 };
1385 
1387 typedef struct PACKED
1388 {
1390  uint32_t recalCmd;
1391 
1393  float progress;
1394 
1397 } mag_cal_t;
1398 
1399 typedef struct PACKED
1400 { // INL2 - Magnetometer observer info
1401  uint32_t timeOfWeekMs; // Timestamp in milliseconds
1402  uint32_t Ncal_samples;
1403  uint32_t ready; // Data ready to be processed
1404  uint32_t calibrated; // Calibration data present. Set to -1 to force mag recalibration.
1405  uint32_t auto_recal; // Allow mag to auto-recalibrate
1406  uint32_t outlier; // Bad sample data
1407  float magHdg; // Heading from magnetometer
1408  float insHdg; // Heading from INS
1409  float magInsHdgDelta; // Difference between mag heading and (INS heading plus mag declination)
1410  float nis; // Normalized innovation squared (likelihood metric)
1411  float nis_threshold; // Threshold for maximum NIS
1412  float Wcal[9]; // Magnetometer calibration matrix. Must be initialized with a unit matrix, not zeros!
1413  uint32_t activeCalSet; // active calibration set (0 or 1)
1414  float magHdgOffset; // Offset between magnetometer heading and estimate heading
1415  float Tcal; // Scaled computed variance between calibrated magnetometer samples.
1416  float bias_cal[3]; // Calibrated magnetometer output can be produced using: Bcal = Wcal * (Braw - bias_cal)
1418 
1421 {
1422  BIT_STATE_OFF = (int)0,
1423  BIT_STATE_DONE = (int)1,
1424  BIT_STATE_CMD_FULL_STATIONARY = (int)2, // (FULL) More comprehensive test. Requires system be completely stationary without vibrations.
1425  BIT_STATE_CMD_BASIC_MOVING = (int)3, // (BASIC) Ignores sensor output. Can be run while moving. This mode is automatically run after bootup.
1431 };
1432 
1435 {
1436  HDW_BIT_PASSED_MASK = (int)0x0000000F,
1437  HDW_BIT_PASSED_ALL = (int)0x00000001,
1438  HDW_BIT_PASSED_NO_GPS = (int)0x00000002, // Passed w/o valid GPS signal
1439  HDW_BIT_MODE_MASK = (int)0x000000F0, // BIT mode run
1442  HDW_BIT_FAILED_MASK = (int)0xFFFFFF00,
1443  HDW_BIT_FAILED_AHRS_MASK = (int)0xFFFF0F00,
1444  HDW_BIT_FAULT_NOISE_PQR = (int)0x00000100,
1445  HDW_BIT_FAULT_NOISE_ACC = (int)0x00000200,
1446  HDW_BIT_FAULT_MAGNETOMETER = (int)0x00000400,
1447  HDW_BIT_FAULT_BAROMETER = (int)0x00000800,
1448  HDW_BIT_FAULT_GPS_NO_COM = (int)0x00001000, // No GPS serial communications
1449  HDW_BIT_FAULT_GPS_POOR_CNO = (int)0x00002000, // Poor GPS signal strength. Check antenna
1450  HDW_BIT_FAULT_GPS_POOR_ACCURACY = (int)0x00002000, // Low number of satellites, or bad accuracy
1451  HDW_BIT_FAULT_GPS_NOISE = (int)0x00004000, // (Not implemented)
1452 };
1453 
1456 {
1457  CAL_BIT_PASSED_MASK = (int)0x0000000F,
1458  CAL_BIT_PASSED_ALL = (int)0x00000001,
1459  CAL_BIT_MODE_MASK = (int)0x000000F0, // BIT mode run
1461 #define CAL_BIT_MODE(calBitStatus) ((calBitStatus&CAL_BIT_MODE_MASK)>>CAL_BIT_MODE_OFFSET)
1462  CAL_BIT_FAILED_MASK = (int)0xFFFFFF00,
1463  CAL_BIT_FAULT_TCAL_EMPTY = (int)0x00000100, // Temperature calibration not present
1464  CAL_BIT_FAULT_TCAL_TSPAN = (int)0x00000200, // Temperature calibration temperature range is inadequate
1465  CAL_BIT_FAULT_TCAL_INCONSISTENT = (int)0x00000400, // Temperature calibration number of points or slopes are not consistent
1466  CAL_BIT_FAULT_TCAL_CORRUPT = (int)0x00000800, // Temperature calibration memory corruption
1467  CAL_BIT_FAULT_TCAL_PQR_BIAS = (int)0x00001000, // Temperature calibration gyro bias
1468  CAL_BIT_FAULT_TCAL_PQR_SLOPE = (int)0x00002000, // Temperature calibration gyro slope
1469  CAL_BIT_FAULT_TCAL_PQR_LIN = (int)0x00004000, // Temperature calibration gyro linearity
1470  CAL_BIT_FAULT_TCAL_ACC_BIAS = (int)0x00008000, // Temperature calibration accelerometer bias
1471  CAL_BIT_FAULT_TCAL_ACC_SLOPE = (int)0x00010000, // Temperature calibration accelerometer slope
1472  CAL_BIT_FAULT_TCAL_ACC_LIN = (int)0x00020000, // Temperature calibration accelerometer linearity
1473  CAL_BIT_FAULT_CAL_SERIAL_NUM = (int)0x00040000, // Calibration info: wrong device serial number
1474  CAL_BIT_FAULT_ORTO_EMPTY = (int)0x00100000, // Cross-axis alignment is not calibrated
1475  CAL_BIT_FAULT_ORTO_INVALID = (int)0x00200000, // Cross-axis alignment is poorly formed
1476  CAL_BIT_FAULT_MOTION_PQR = (int)0x00400000, // Motion on gyros
1477  CAL_BIT_FAULT_MOTION_ACC = (int)0x00800000, // Motion on accelerometers
1478 };
1479 
1480 
1482 typedef struct PACKED
1483 {
1485  uint32_t state;
1486 
1488  uint32_t hdwBitStatus;
1489 
1491  uint32_t calBitStatus;
1492 
1494  float tcPqrBias;
1495  float tcAccBias;
1496 
1498  float tcPqrSlope;
1499  float tcAccSlope;
1500 
1504 
1506  float pqr;
1507 
1509  float acc;
1510 
1512  float pqrSigma;
1513 
1515  float accSigma;
1516 
1517 } bit_t;
1518 
1519 
1522 {
1523  UNUSED1 = (int)0x00000001,
1524  UNUSED2 = (int)0x00000002,
1526  SYS_CFG_BITS_AUTO_MAG_RECAL = (int)0x00000004,
1529 
1531  SYS_CFG_BITS_DISABLE_LEDS = (int)0x00000010,
1532 
1536 #define SYS_CFG_BITS_MAG_RECAL_MODE(sysCfgBits) ((sysCfgBits&SYS_CFG_BITS_MAG_RECAL_MODE_MASK)>>SYS_CFG_BITS_MAG_RECAL_MODE_OFFSET)
1537 
1546 
1552  SYS_CFG_BITS_DISABLE_INS_EKF = (int)0x00040000,
1555 
1558 };
1559 
1562 {
1564  GNSS_SAT_SIG_CONST_GPS = (uint16_t)0x0003,
1566  GNSS_SAT_SIG_CONST_QZSS = (uint16_t)0x000C,
1568  GNSS_SAT_SIG_CONST_GAL = (uint16_t)0x0030,
1570  GNSS_SAT_SIG_CONST_BDS = (uint16_t)0x00C0,
1572  GNSS_SAT_SIG_CONST_GLO = (uint16_t)0x0300,
1574  GNSS_SAT_SIG_CONST_SBAS = (uint16_t)0x1000,
1575 
1578  GNSS_SAT_SIG_CONST_GPS | \
1579  GNSS_SAT_SIG_CONST_SBAS | \
1580  GNSS_SAT_SIG_CONST_QZSS | \
1581  GNSS_SAT_SIG_CONST_GAL | \
1582  GNSS_SAT_SIG_CONST_GLO
1583 };
1584 
1587 {
1590 
1593 
1596 
1599 
1602 
1605 
1607  RTK_CFG_BITS_ROVER_MODE_MASK = (int)0x0000000F,
1608 
1611 
1614 
1617 
1620 
1623 
1626 
1629 
1632 
1635 
1638 
1641 
1644 
1647 
1650 
1653 
1656 
1658  RTK_CFG_BITS_BASE_POS_MOVING = (int)0x00100000,
1659 
1661  RTK_CFG_BITS_RESERVED1 = (int)0x00200000,
1662 
1665 
1668 
1679 
1684 
1689 
1694 
1701 
1708 
1715 
1722 
1725 
1728 };
1729 
1730 
1733 {
1735  SENSOR_CFG_GYR_FS_250 = (int)0x00000000,
1736  SENSOR_CFG_GYR_FS_500 = (int)0x00000001,
1737  SENSOR_CFG_GYR_FS_1000 = (int)0x00000002,
1738  SENSOR_CFG_GYR_FS_2000 = (int)0x00000003,
1739  SENSOR_CFG_GYR_FS_MASK = (int)0x00000003,
1741 
1743  SENSOR_CFG_ACC_FS_2G = (int)0x00000000,
1744  SENSOR_CFG_ACC_FS_4G = (int)0x00000001,
1745  SENSOR_CFG_ACC_FS_8G = (int)0x00000002,
1746  SENSOR_CFG_ACC_FS_16G = (int)0x00000003,
1747  SENSOR_CFG_ACC_FS_MASK = (int)0x00000003,
1749 
1752  SENSOR_CFG_GYR_DLPF_250HZ = (int)0x00000000,
1753  SENSOR_CFG_GYR_DLPF_184HZ = (int)0x00000001,
1754  SENSOR_CFG_GYR_DLPF_92HZ = (int)0x00000002,
1755  SENSOR_CFG_GYR_DLPF_41HZ = (int)0x00000003,
1756  SENSOR_CFG_GYR_DLPF_20HZ = (int)0x00000004,
1757  SENSOR_CFG_GYR_DLPF_10HZ = (int)0x00000005,
1758  SENSOR_CFG_GYR_DLPF_5HZ = (int)0x00000006,
1759  SENSOR_CFG_GYR_DLPF_MASK = (int)0x0000000F,
1761 
1764  SENSOR_CFG_ACC_DLPF_218HZ = (int)0x00000000,
1765  SENSOR_CFG_ACC_DLPF_218HZb = (int)0x00000001,
1766  SENSOR_CFG_ACC_DLPF_99HZ = (int)0x00000002,
1767  SENSOR_CFG_ACC_DLPF_45HZ = (int)0x00000003,
1768  SENSOR_CFG_ACC_DLPF_21HZ = (int)0x00000004,
1769  SENSOR_CFG_ACC_DLPF_10HZ = (int)0x00000005,
1770  SENSOR_CFG_ACC_DLPF_5HZ = (int)0x00000006,
1771  SENSOR_CFG_ACC_DLPF_MASK = (int)0x0000000F,
1773 
1777  SENSOR_CFG_SENSOR_ROTATION_0_0_0 = (int)0, // roll, pitch, yaw rotation (deg).
1801 };
1802 
1803 
1806 {
1819 
1822 
1833 #define SET_STATUS_OFFSET_MASK(result,val,offset,mask) { (result) &= ~((mask)<<(offset)); (result) |= ((val)<<(offset)); }
1834 
1835 #define IO_CFG_GPS_TIMEPUSE_SOURCE(ioConfig) ((ioConfig>>IO_CFG_GPS_TIMEPUSE_SOURCE_OFFSET)&IO_CFG_GPS_TIMEPUSE_SOURCE_MASK)
1836 
1845 
1847  IO_CONFIG_GPS_SOURCE_MASK = (int)0x00000007,
1860 
1862  IO_CONFIG_GPS_TYPE_MASK = (int)0x00000003,
1869 
1871 #define IO_CONFIG_GPS2_SOURCE(ioConfig) ((ioConfig>>IO_CONFIG_GPS2_SOURCE_OFFSET)&IO_CONFIG_GPS_SOURCE_MASK)
1872 #define IO_CONFIG_GPS1_TYPE(ioConfig) ((ioConfig>>IO_CONFIG_GPS1_TYPE_OFFSET)&IO_CONFIG_GPS_TYPE_MASK)
1873 #define IO_CONFIG_GPS2_TYPE(ioConfig) ((ioConfig>>IO_CONFIG_GPS2_TYPE_OFFSET)&IO_CONFIG_GPS_TYPE_MASK)
1874 
1876  IO_CONFIG_IMU_1_DISABLE = (int)0x00100000,
1878  IO_CONFIG_IMU_2_DISABLE = (int)0x00200000,
1879 
1881  IO_CONFIG_CAN_BUS_ENABLE = (int)0x01000000,
1882 };
1883 
1884 
1886 typedef struct PACKED
1887 {
1889  double timeOfWeek;
1890 
1892  uint32_t status;
1893 
1895  float theta_l;
1896 
1898  float theta_r;
1899 
1901  float omega_l;
1902 
1904  float omega_r;
1905 
1907  uint32_t wrap_count_l;
1908 
1910  uint32_t wrap_count_r;
1911 
1912 } wheel_encoder_t;
1913 
1915 {
1918  WHEEL_CFG_BITS_ENABLE_MASK = (int)0x0000000F,
1919 };
1920 
1922 typedef struct PACKED
1923 {
1925  uint32_t bits;
1926 
1928  float e_i2l[3];
1929 
1931  float t_i2l[3];
1932 
1934  float distance;
1935 
1937  float diameter;
1938 
1939 } wheel_config_t;
1940 
1941 typedef enum
1942 {
1952 } eInsDynModel;
1953 
1958 typedef struct PACKED
1959 {
1961  uint32_t size;
1962 
1964  uint32_t checksum;
1965 
1967  uint32_t key;
1968 
1970  uint32_t startupImuDtMs;
1971 
1973  uint32_t startupNavDtMs;
1974 
1976  uint32_t ser0BaudRate;
1977 
1979  uint32_t ser1BaudRate;
1980 
1982  float insRotation[3];
1983 
1985  float insOffset[3];
1986 
1988  float gps1AntOffset[3];
1989 
1991  uint8_t insDynModel;
1992 
1994  uint8_t reserved;
1995 
1998 
2000  uint32_t sysCfgBits;
2001 
2003  double refLla[3];
2004 
2006  double lastLla[3];
2007 
2010 
2012  uint32_t lastLlaWeek;
2013 
2016 
2018  uint32_t ioConfig;
2019 
2021  uint32_t cBrdConfig;
2022 
2024  float gps2AntOffset[3];
2025 
2028 
2030  float zeroVelOffset[3];
2031 
2034 
2037 
2040 
2042  uint32_t startupGPSDtMs;
2043 
2045  uint32_t RTKCfgBits;
2046 
2048  uint32_t sensorConfig;
2049 
2052 
2055 
2057  uint32_t ser2BaudRate;
2058 
2059 } nvm_flash_cfg_t;
2060 
2062 typedef struct PACKED
2063 {
2065  unsigned int timeOfWeekMs;
2067  float PxyzNED[3];
2069  float PvelNED[3];
2071  float PattNED[3];
2073  float PABias[3];
2075  float PWBias[3];
2077  float PBaroBias;
2081 
2083 typedef struct PACKED
2084 {
2086  uint32_t week;
2087 
2089  uint32_t timeOfWeekMs;
2090 
2092  uint32_t pin;
2093 
2095  uint32_t count;
2097 
2098 #define DEBUG_I_ARRAY_SIZE 9
2099 #define DEBUG_F_ARRAY_SIZE 9
2100 #define DEBUG_LF_ARRAY_SIZE 3
2101 
2102 /* (DID_DEBUG_ARRAY) */
2103 typedef struct PACKED
2104 {
2108 } debug_array_t;
2109 
2110 #define DEBUG_STRING_SIZE 80
2111 
2112 /* (DID_DEBUG_STRING) */
2113 typedef struct PACKED
2114 {
2116 } debug_string_t;
2117 
2118 POP_PACK
2119 
2121 
2123 typedef struct
2124 {
2126  int64_t time;
2127 
2129  double sec;
2130 } gtime_t;
2131 
2132 typedef struct PACKED
2133 {
2135  double rp_ecef[3]; // Rover position
2136  double rv_ecef[3]; // Rover velocity
2137  double ra_ecef[3]; // Rover acceleration
2138  double bp_ecef[3]; // Base position
2139  double bv_ecef[3]; // Base velocity
2140  double qr[6]; // rover position and velocity covariance main diagonal
2141  double b[24]; // satellite bias
2142  double qb[24]; // main diagonal of sat bias covariances
2143  uint8_t sat_id[24]; // satellite id of b[]
2144 } rtk_state_t;
2145 
2146 typedef struct PACKED
2147 {
2148  gtime_t time;
2149  int32_t nv; // number of measurements
2150  uint8_t sat_id_i[24]; // sat id of measurements (reference sat)
2151  uint8_t sat_id_j[24]; // sat id of measurements
2152  uint8_t type[24]; // type (0 = dd-range, 1 = dd-phase, 2 = baseline)
2153  double v[24]; // residual
2154 } rtk_residual_t;
2155 
2156 typedef struct PACKED
2157 {
2158  gtime_t time;
2159 
2160  uint8_t rej_ovfl;
2161  uint8_t code_outlier;
2162  uint8_t phase_outlier;
2164 
2169 
2170  uint8_t outc_ovfl;
2171  uint8_t reset_timer;
2173  uint8_t large_v2b;
2174 
2177  uint8_t reset_bias;
2178  uint8_t start_relpos;
2179 
2180  uint8_t end_relpos;
2181  uint8_t start_rtkpos;
2182  uint8_t pnt_pos_error;
2184 
2189 
2190  uint8_t lsq_error;
2194 
2195  uint32_t cycle_slips;
2196 
2197  float ubx_error;
2198 
2199  uint8_t solStatus;
2201  uint8_t error_count;
2202  uint8_t error_code;
2203 
2204  float dist2base;
2205 
2206  uint8_t reserved1;
2207  uint8_t gdop_error;
2208  uint8_t warning_count;
2209  uint8_t warning_code;
2210 
2211  double double_debug[4];
2212 
2213  uint8_t debug[2];
2214  uint8_t obs_count_bas;
2215  uint8_t obs_count_rov;
2216 
2221 } rtk_debug_t;
2222 
2223 POP_PACK
2224 
2226 
2228 typedef struct
2229 {
2231  int32_t mode;
2232 
2234  int32_t soltype;
2235 
2237  int32_t nf;
2238 
2240  int32_t navsys;
2241 
2243  double elmin;
2244 
2246  int32_t snrmin;
2247 
2249  int32_t modear;
2250 
2252  int32_t glomodear;
2253 
2255  int32_t gpsmodear;
2256 
2258  int32_t sbsmodear;
2259 
2261  int32_t bdsmodear;
2262 
2264  int32_t arfilter;
2265 
2267  int32_t maxout;
2268 
2270  int32_t maxrej;
2271 
2273  int32_t minlock;
2274 
2276  int32_t minfixsats;
2277 
2279  int32_t minholdsats;
2280 
2282  int32_t mindropsats;
2283 
2285  int32_t rcvstds;
2286 
2288  int32_t minfix;
2289 
2291  int32_t armaxiter;
2292 
2294  int32_t dynamics;
2295 
2297  int32_t niter;
2298 
2300  int32_t intpref;
2301 
2303  int32_t rovpos;
2304 
2306  int32_t refpos;
2307 
2309  double eratio[1];
2310 
2312  double err[5];
2313 
2315  double std[3];
2316 
2318  double prn[6];
2319 
2321  double sclkstab;
2322 
2324  double thresar[8];
2325 
2327  double elmaskar;
2328 
2330  double elmaskhold;
2331 
2333  double thresslip;
2334 
2336  double varholdamb;
2337 
2339  double gainholdamb;
2340 
2342  double maxtdiff;
2343 
2346 
2348  double maxinnocode;
2350  double maxnis;
2351 
2353  double maxgdop;
2354 
2356  double baseline[3];
2359 
2362 
2364  double ru[3];
2365 
2367  double rb[3];
2368 
2370  int32_t maxaveep;
2371 
2373  int32_t outsingle;
2374 } prcopt_t;
2376 
2378 typedef struct PACKED
2379 {
2381  gtime_t time;
2382 
2384  uint8_t sat;
2385 
2387  uint8_t rcv;
2388 
2390  uint8_t SNR[1];
2391 
2393  uint8_t LLI[1];
2394 
2396  uint8_t code[1];
2397 
2399  uint8_t qualL[1];
2400 
2402  uint8_t qualP[1];
2403 
2405  uint8_t reserved;
2406 
2408  double L[1];
2409 
2411  double P[1];
2412 
2414  float D[1];
2415 } obsd_t;
2416 
2417 #define GPS_RAW_MESSAGE_BUF_SIZE 1000
2418 #define MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE (GPS_RAW_MESSAGE_BUF_SIZE / sizeof(obsd_t))
2419 
2421 typedef struct
2422 {
2424  uint32_t n;
2425 
2427  uint32_t nmax;
2428 
2431 } obs_t;
2432 
2434 typedef struct
2435 {
2437  int32_t sat;
2438 
2440  int32_t iode;
2441 
2443  int32_t iodc;
2444 
2446  int32_t sva;
2447 
2449  int32_t svh;
2450 
2452  int32_t week;
2453 
2455  int32_t code;
2456 
2458  int32_t flag;
2459 
2462 
2465 
2468 
2470  double A;
2471 
2473  double e;
2474 
2476  double i0;
2477 
2479  double OMG0;
2480 
2482  double omg;
2483 
2485  double M0;
2486 
2488  double deln;
2489 
2491  double OMGd;
2492 
2494  double idot;
2495 
2497  double crc;
2498 
2500  double crs;
2501 
2503  double cuc;
2504 
2506  double cus;
2507 
2509  double cic;
2510 
2512  double cis;
2513 
2515  double toes;
2516 
2518  double fit;
2519 
2521  double f0;
2522 
2524  double f1;
2525 
2527  double f2;
2528 
2530  double tgd[4];
2531 
2533  double Adot;
2534 
2536  double ndot;
2537 } eph_t;
2538 
2540 typedef struct
2541 {
2543  int32_t sat;
2544 
2546  int32_t iode;
2547 
2549  int32_t frq;
2550 
2552  int32_t svh;
2553 
2555  int32_t sva;
2556 
2558  int32_t age;
2559 
2562 
2565 
2567  double pos[3];
2568 
2570  double vel[3];
2571 
2573  double acc[3];
2574 
2576  double taun;
2577 
2579  double gamn;
2580 
2582  double dtaun;
2583 } geph_t;
2584 
2586 typedef struct
2587 {
2589  int32_t week;
2590 
2592  int32_t tow;
2593 
2595  int32_t prn;
2596 
2598  uint8_t msg[29];
2599 
2601  uint8_t reserved[3];
2602 } sbsmsg_t;
2603 
2605 typedef struct
2606 {
2608  int32_t deltype;
2609 
2611  double pos[3];
2612 
2614  double del[3];
2615 
2617  double hgt;
2618 
2620  int32_t stationId;
2621 } sta_t;
2622 
2624 typedef struct
2625 {
2627  int32_t sat;
2628 
2630  int32_t svh;
2631 
2633  int32_t svconf;
2634 
2635  /* GPS/QZS: gps week, GAL: galileo week */
2636  int32_t week;
2637 
2638  /* Toa */
2640 
2642  double A;
2643 
2645  double e;
2646 
2648  double i0;
2649 
2651  double OMG0;
2652 
2654  double omg;
2655 
2657  double M0;
2658 
2660  double OMGd;
2661 
2663  double toas;
2664 
2666  double f0;
2667 
2669  double f1;
2670 } alm_t;
2671 
2673 typedef struct
2674 {
2675  double ion_gps[8]; /* GPS iono model parameters {a0,a1,a2,a3,b0,b1,b2,b3} */
2676  double ion_gal[4]; /* Galileo iono model parameters {ai0,ai1,ai2,0} */
2677  double ion_qzs[8]; /* QZSS iono model parameters {a0,a1,a2,a3,b0,b1,b2,b3} */
2678  double ion_cmp[8]; /* BeiDou iono model parameters {a0,a1,a2,a3,b0,b1,b2,b3} */
2679  double ion_irn[8]; /* IRNSS iono model parameters {a0,a1,a2,a3,b0,b1,b2,b3} */
2680 
2681  double utc_gps[4]; /* GPS delta-UTC parameters {A0,A1,T,W} */
2682  double utc_glo[4]; /* GLONASS UTC GPS time parameters */
2683  double utc_gal[4]; /* Galileo UTC GPS time parameters */
2684  double utc_qzs[4]; /* QZS UTC GPS time parameters */
2685  double utc_cmp[4]; /* BeiDou UTC parameters */
2686  double utc_irn[4]; /* IRNSS UTC parameters */
2687  double utc_sbs[4]; /* SBAS UTC parameters */
2688 
2689  int32_t leaps; /* leap seconds (s) */
2690 
2691  alm_t alm; /* almanac */
2693 
2695 typedef enum
2696 {
2699 
2702 
2705 
2708 
2711 
2714 } eRtkSolStatus;
2715 
2717 typedef struct PACKED
2718 {
2720  uint32_t timeOfWeekMs;
2721 
2724 
2726  float arRatio;
2727 
2730 
2733 
2736 
2739 
2741  uint32_t status;
2742 
2743 } gps_rtk_rel_t;
2744 
2746 typedef struct PACKED
2747 {
2749  uint32_t timeOfWeekMs;
2750 
2752  float accuracyPos[3];
2753 
2755  float accuracyCov[3];
2756 
2759 
2761  float gDop;
2762 
2764  float hDop;
2765 
2767  float vDop;
2768 
2770  double baseLla[3];
2771 
2773  uint32_t cycleSlipCount;
2774 
2777 
2780 
2783 
2786 
2789 
2792 
2795 
2798 
2801 
2804 
2807 
2810 
2813 
2816 
2819 
2822 
2825 
2828 
2831 
2834 
2836  uint32_t roverSbasCount;
2837 
2839  uint32_t baseSbasCount;
2840 
2843 
2845  uint32_t ionUtcAlmCount;
2846 
2849 
2852 
2853 } gps_rtk_misc_t;
2854 
2856 typedef enum
2857 {
2860 
2863 
2866 
2869 
2872 
2875 
2878 } eRawDataType;
2879 
2880 typedef union PACKED
2881 {
2884 
2887 
2890 
2893 
2896 
2899 
2902 } uGpsRawData;
2903 
2905 typedef struct PACKED
2906 {
2908  uint8_t receiverIndex;
2909 
2911  uint8_t dataType;
2912 
2914  uint8_t obsCount;
2915 
2917  uint8_t reserved;
2918 
2921 } gps_raw_t;
2922 
2926 typedef struct
2927 {
2929  uint32_t timeOfWeekMs;
2930 
2932  uint32_t messageLength;
2933 
2935  char message[256];
2936 } diag_msg_t;
2937 
2938 typedef enum
2939 {
2940  // default state
2942 
2943  // commands
2948 
2949  // status
2955 } eSurveyInStatus;
2956 
2960 typedef struct
2961 {
2963  uint32_t state;
2964 
2966  uint32_t maxDurationSec;
2967 
2970 
2972  uint32_t elapsedTimeSec;
2973 
2975  float hAccuracy;
2976 
2978  double lla[3];
2979 } survey_in_t;
2980 
2981 
2982 typedef enum
2983 {
2986 
2989 
2992 
2995 
2998 
3001 
3004 
3007 
3010 
3013 
3016 
3017 } eEvbStatus;
3018 
3021 {
3025  EVB2_PORT_XRADIO = 3, // H4-8 (orange) Tx, H4-7 (brown) Rx
3027  EVB2_PORT_SP330 = 5, // H3-2 (brown) Tx, H3-5 (green) Rx
3028  EVB2_PORT_GPIO_H8 = 6, // H8-5 (brown) Tx, H8-6 (orange) Rx
3031  EVB2_PORT_CAN = 9, // H2-3 CANL (brown), H2-4 CANH (orange)
3033 };
3034 
3037 {
3045  EVB2_CB_OPTIONS_I2C_ENABLE = 0x00000200, // Tied to uINS G1,G2
3046 };
3047 
3049 {
3050  EVB2_PORT_OPTIONS_RADIO_RTK_FILTER = 0x00000001, // Allow RTCM3, NMEA, and RTCM3. Reject IS binary.
3052 };
3053 
3057 typedef struct
3058 {
3060  uint32_t week;
3061 
3063  uint32_t timeOfWeekMs;
3064 
3066  uint8_t firmwareVer[4];
3067 
3069  uint32_t evbStatus;
3070 
3072  uint32_t loggerMode;
3073 
3076 
3078  uint32_t wifiIpAddr;
3079 
3081  uint32_t sysCommand;
3082 
3083 } evb_status_t;
3084 
3085 #define WIFI_SSID_PSK_SIZE 40
3086 
3087 typedef struct
3088 {
3091 
3094 
3095 } evb_wifi_t;
3096 
3097 typedef struct
3098 {
3100  union {
3101  uint32_t u32;
3102  uint8_t u8[4];
3103  } ipAddr;
3104 
3106  uint32_t port;
3107 
3108 } evb_server_t;
3109 
3110 typedef enum
3111 {
3116  EVB_CFG_BITS_NO_STREAM_PPD_ON_LOG_BUTTON = 0x00000010, // Don't enable PPD stream when log button is pressed
3120 
3121 #define NUM_WIFI_PRESETS 3
3122 #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);}
3123 #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);}
3124 #define EVB_CFG_BITS_IDX_WIFI(bits) ((bits&EVB_CFG_BITS_WIFI_SELECT_MASK)>>EVB_CFG_BITS_WIFI_SELECT_OFFSET)
3125 #define EVB_CFG_BITS_IDX_SERVER(bits) ((bits&EVB_CFG_BITS_SERVER_SELECT_MASK)>>EVB_CFG_BITS_SERVER_SELECT_OFFSET)
3126 
3130 typedef struct
3131 {
3133  uint32_t size;
3134 
3136  uint32_t checksum;
3137 
3139  uint32_t key;
3140 
3142  uint8_t cbPreset;
3143 
3144  // 32-bit alignment
3145  uint8_t reserved1[3];
3146 
3148  uint32_t cbf[EVB2_PORT_COUNT];
3149 
3151  uint32_t cbOptions;
3152 
3154  uint32_t bits;
3155 
3157  uint32_t radioPID;
3158 
3160  uint32_t radioNID;
3161 
3164 
3167 
3170 
3173 
3175  uint32_t CANbaud_kbps;
3176 
3179 
3181  uint8_t uinsComPort;
3182 
3184  uint8_t uinsAuxPort;
3185 
3186  // Ensure 32-bit alignment
3187  uint8_t reserved2[2];
3188 
3190  uint32_t portOptions;
3191 
3194 
3197 
3199  uint32_t h8gpioBaudRate;
3200 
3201 } evb_flash_cfg_t;
3202 
3203 
3206 {
3209 
3212 
3215 
3218 
3221 
3224 
3227 
3230 
3233 
3234 };
3235 
3236 #define EVB2_CB_PRESET_DEFAULT EVB2_CB_PRESET_RS232
3237 
3240 {
3243 
3246 
3249 
3252 
3253 };
3254 
3255 
3259 typedef struct
3260 {
3262  uint32_t txBytesPerS;
3263 
3265  uint32_t rxBytesPerS;
3266 
3268  uint32_t status;
3269 
3271 
3272 typedef struct
3273 {
3276 
3277 } port_monitor_t;
3278 
3279 
3283 #define SYS_FAULT_STATUS_HARDWARE_RESET 0x00000000
3284 #define SYS_FAULT_STATUS_USER_RESET 0x00000001
3285 #define SYS_FAULT_STATUS_ENABLE_BOOTLOADER 0x00000002
3286 // General:
3287 #define SYS_FAULT_STATUS_SOFT_RESET 0x00000010
3288 #define SYS_FAULT_STATUS_FLASH_MIGRATION_EVENT 0x00000020
3289 #define SYS_FAULT_STATUS_FLASH_MIGRATION_COMPLETED 0x00000040
3290 #define SYS_FAULT_STATUS_RTK_MISC_ERROR 0x00000080
3291 #define SYS_FAULT_STATUS_MASK_GENERAL_ERROR 0xFFFFFFF0
3292 // Critical: (usually associated with system reset)
3293 #define SYS_FAULT_STATUS_HARD_FAULT 0x00010000
3294 #define SYS_FAULT_STATUS_USAGE_FAULT 0x00020000
3295 #define SYS_FAULT_STATUS_MEM_MANGE 0x00040000
3296 #define SYS_FAULT_STATUS_BUS_FAULT 0x00080000
3297 #define SYS_FAULT_STATUS_MALLOC_FAILED 0x00100000
3298 #define SYS_FAULT_STATUS_STACK_OVERFLOW 0x00200000
3299 #define SYS_FAULT_STATUS_INVALID_CODE_OPERATION 0x00400000
3300 #define SYS_FAULT_STATUS_FLASH_MIGRATION_MARKER_UPDATED 0x00800000
3301 #define SYS_FAULT_STATUS_WATCHDOG_RESET 0x01000000
3302 #define SYS_FAULT_STATUS_RTK_BUFFER_LIMIT 0x02000000
3303 #define SYS_FAULT_STATUS_SENSOR_CALIBRATION 0x04000000
3304 #define SYS_FAULT_STATUS_HARDWARE_DETECTION 0x08000000
3305 #define SYS_FAULT_STATUS_MASK_CRITICAL_ERROR 0xFFFF0000
3306 
3307 typedef struct
3308 {
3310  uint32_t status;
3311 
3313  uint32_t g1Task;
3314 
3316  uint32_t g2FileNum;
3317 
3319  uint32_t g3LineNum;
3320 
3322  uint32_t g4;
3323 
3325  uint32_t g5Lr;
3326 
3328  uint32_t pc;
3329 
3331  uint32_t psr;
3332 
3333 } system_fault_t;
3334 
3336 typedef struct
3337 {
3339  uint32_t gapCountSerialDriver[NUM_SERIAL_PORTS];
3340 
3342  uint32_t gapCountSerialParser[NUM_SERIAL_PORTS];
3343 
3345  uint32_t rxOverflowCount[NUM_SERIAL_PORTS];
3346 
3348  uint32_t txOverflowCount[NUM_SERIAL_PORTS];
3349 
3351  uint32_t checksumFailCount[NUM_SERIAL_PORTS];
3353 
3355 typedef enum
3356 {
3359 
3362 
3365 
3368 
3371 
3374 
3376  UINS_RTOS_NUM_TASKS // Keep last
3377 } eRtosTask;
3378 
3380 typedef enum
3381 {
3384 
3387 
3390 
3393 
3396 
3399 
3402 
3404  EVB_RTOS_NUM_TASKS // Keep last
3405 } eEvbRtosTask;
3406 
3408 #define MAX_TASK_NAME_LEN 12
3409 
3411 typedef struct PACKED
3412 {
3415 
3417  uint32_t priority;
3418 
3420  uint32_t stackUnused;
3421 
3423  uint32_t periodMs;
3424 
3426  uint32_t runTimeUs;
3427 
3429  uint32_t maxRunTimeUs;
3430 
3433 
3435  uint32_t gapCount;
3436 
3438  float cpuUsage;
3439 
3441  uint32_t handle;
3442 } rtos_task_t;
3443 
3445 typedef struct PACKED
3446 {
3448  uint32_t freeHeapSize;
3449 
3451  uint32_t mallocSize;
3452 
3454  uint32_t freeSize;
3455 
3458 
3459 } rtos_info_t;
3460 
3462 typedef struct PACKED
3463 {
3465  uint32_t freeHeapSize;
3466 
3468  uint32_t mallocSize;
3469 
3471  uint32_t freeSize;
3472 
3475 
3476 } evb_rtos_info_t;
3477 enum
3478 {
3505 };
3506 
3508 typedef struct PACKED
3509 {
3512 
3515 
3518 
3521 
3522 } can_config_t;
3523 
3525 typedef union PACKED
3526 {
3555 } uDatasets;
3556 
3558 typedef union PACKED
3559 {
3560  ins_1_t ins1;
3561  ins_2_t ins2;
3562  ins_3_t ins3;
3563  ins_4_t ins4;
3564 } uInsOutDatasets;
3565 
3566 POP_PACK
3567 
3576 uint32_t checksum32(const void* data, int count);
3577 uint32_t serialNumChecksum32(const void* data, int size);
3578 uint32_t flashChecksum32(const void* data, int size);
3579 
3586 void flipEndianess32(uint8_t* data, int dataLength);
3587 
3593 void flipFloat(uint8_t* ptr);
3594 
3601 float flipFloatCopy(float val);
3602 
3609 void flipDouble(void* ptr);
3610 
3618 double flipDoubleCopy(double val);
3619 
3629 void flipDoubles(uint8_t* data, int dataLength, int offset, uint16_t* offsets, uint16_t offsetsLength);
3630 
3640 void flipStrings(uint8_t* data, int dataLength, int offset, uint16_t* offsets, uint16_t offsetsLength);
3641 
3642 // BE_SWAP: if big endian then swap, else no-op
3643 // LE_SWAP: if little endian then swap, else no-op
3644 #if CPU_IS_BIG_ENDIAN
3645 #define BE_SWAP64F(_i) flipDoubleCopy(_i)
3646 #define BE_SWAP32F(_i) flipFloatCopy(_i)
3647 #define BE_SWAP32(_i) (SWAP32(_i))
3648 #define BE_SWAP16(_i) (SWAP16(_i))
3649 #define LE_SWAP64F(_i) (_i)
3650 #define LE_SWAP32F(_i) (_i)
3651 #define LE_SWAP32(_i) (_i)
3652 #define LE_SWAP16(_i) (_i)
3653 #else // little endian
3654 #define BE_SWAP64F(_i) (_i)
3655 #define BE_SWAP32F(_i) (_i)
3656 #define BE_SWAP32(_i) (_i)
3657 #define BE_SWAP16(_i) (_i)
3658 #define LE_SWAP64F(_i) flipDoubleCopy(_i)
3659 #define LE_SWAP32F(_i) flipFloatCopy(_i)
3660 #define LE_SWAP32(_i) (SWAP32(_i))
3661 #define LE_SWAP16(_i) (SWAP16(_i))
3662 #endif
3663 
3672 uint16_t* getDoubleOffsets(eDataIDs dataId, uint16_t* offsetsLength);
3673 
3682 uint16_t* getStringOffsetsLengths(eDataIDs dataId, uint16_t* offsetsLength);
3683 
3685 uint64_t didToRmcBit(uint32_t dataId, uint64_t defaultRmcBits);
3686 
3687 //Time conversion constants
3688 #define SECONDS_PER_WEEK 604800
3689 #define SECONDS_PER_DAY 86400
3690 #define GPS_TO_UNIX_OFFSET 315964800
3691 
3692 double gpsToUnix(uint32_t gpsWeek, uint32_t gpsTimeofWeekMS, uint8_t leapSeconds);
3693 
3695 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);
3696 
3698 double gpsToJulian(int32_t gpsWeek, int32_t gpsMilliseconds, int32_t leapSeconds);
3699 
3700 /*
3701 Convert gps pos to nmea gga
3702 
3703 @param gps gps position
3704 @param buffer buffer to fill with nmea gga
3705 @param bufferLength number of chars available in buffer, should be at least 128
3706 @return number of chars written to buffer, not including the null terminator
3707 */
3708 int gpsToNmeaGGA(const gps_pos_t* gps, char* buffer, int bufferLength);
3709 
3710 #ifndef RTKLIB_H
3711 #define SYS_NONE 0x00 /* navigation system: none */
3712 #define SYS_GPS 0x01 /* navigation system: GPS */
3713 #define SYS_SBS 0x02 /* navigation system: SBAS */
3714 #define SYS_GLO 0x04 /* navigation system: GLONASS */
3715 #define SYS_GAL 0x08 /* navigation system: Galileo */
3716 #define SYS_QZS 0x10 /* navigation system: QZSS */
3717 #define SYS_CMP 0x20 /* navigation system: BeiDou */
3718 #define SYS_IRN 0x40 /* navigation system: IRNS */
3719 #define SYS_LEO 0x80 /* navigation system: LEO */
3720 #define SYS_ALL 0xFF /* navigation system: all */
3721 #endif
3722 
3723 /*
3724 Convert gnssID to ubx gnss indicator (ref [2] 25)
3725 
3726 @param gnssID gnssID of satellite
3727 @return ubx gnss indicator
3728 */
3729 int ubxSys(int gnssID);
3730 
3731 #ifndef __RTKLIB_EMBEDDED_DEFINES_H_
3732 
3733 #undef ENAGLO
3734 #define ENAGLO
3735 
3736 #undef ENAGAL
3737 #define ENAGAL
3738 
3739 #undef ENAQZS
3740 //#define ENAQZS
3741 
3742 #undef ENASBS
3743 #define ENASBS
3744 
3745 #undef MAXSUBFRMLEN
3746 #define MAXSUBFRMLEN 152
3747 
3748 #undef MAXRAWLEN
3749 #define MAXRAWLEN 2048
3750 
3751 #undef NFREQ
3752 #define NFREQ 1
3753 
3754 #undef NFREQGLO
3755 #ifdef ENAGLO
3756 #define NFREQGLO 1
3757 #else
3758 #define NFREQGLO 0
3759 #endif
3760 
3761 #undef NFREQGAL
3762 #ifdef ENAGAL
3763 #define NFREQGAL 1
3764 #else
3765 #define NFREQGAL 0
3766 #endif
3767 
3768 #undef NEXOBS
3769 #define NEXOBS 0
3770 
3771 #undef MAXOBS
3772 #define MAXOBS 56 // Also defined inside rtklib_defines.h
3773 #define HALF_MAXOBS (MAXOBS/2)
3774 
3775 #undef NUMSATSOL
3776 #define NUMSATSOL 22
3777 
3778 #undef MAXERRMSG
3779 #define MAXERRMSG 0
3780 
3781 #ifdef ENASBS
3782 
3783 // sbas waas only satellites
3784 #undef MINPRNSBS
3785 #define MINPRNSBS 133 /* min satellite PRN number of SBAS */
3786 
3787 #undef MAXPRNSBS
3788 #define MAXPRNSBS 138 /* max satellite PRN number of SBAS */
3789 
3790 #undef NSATSBS
3791 #define NSATSBS (MAXPRNSBS - MINPRNSBS + 1) /* number of SBAS satellites */
3792 
3793 #define SBAS_EPHEMERIS_ARRAY_SIZE NSATSBS
3794 
3795 #else
3796 
3797 #define SBAS_EPHEMERIS_ARRAY_SIZE 0
3798 
3799 #endif
3800 
3801 
3802 #endif
3803 
3804 #ifndef RTKLIB_H
3805 
3806 #define MINPRNGPS 1 /* min satellite PRN number of GPS */
3807 #define MAXPRNGPS 32 /* max satellite PRN number of GPS */
3808 #define NSATGPS (MAXPRNGPS-MINPRNGPS+1) /* number of GPS satellites */
3809 #define NSYSGPS 1
3810 
3811 #ifdef ENAGLO
3812 #define MINPRNGLO 1 /* min satellite slot number of GLONASS */
3813 #define MAXPRNGLO 27 /* max satellite slot number of GLONASS */
3814 #define NSATGLO (MAXPRNGLO-MINPRNGLO+1) /* number of GLONASS satellites */
3815 #define NSYSGLO 1
3816 #else
3817 #define MINPRNGLO 0
3818 #define MAXPRNGLO 0
3819 #define NSATGLO 0
3820 #define NSYSGLO 0
3821 #endif
3822 #ifdef ENAGAL
3823 #define MINPRNGAL 1 /* min satellite PRN number of Galileo */
3824 #define MAXPRNGAL 30 /* max satellite PRN number of Galileo */
3825 #define NSATGAL (MAXPRNGAL-MINPRNGAL+1) /* number of Galileo satellites */
3826 #define NSYSGAL 1
3827 #else
3828 #define MINPRNGAL 0
3829 #define MAXPRNGAL 0
3830 #define NSATGAL 0
3831 #define NSYSGAL 0
3832 #endif
3833 #ifdef ENAQZS
3834 #define MINPRNQZS 193 /* min satellite PRN number of QZSS */
3835 #define MAXPRNQZS 199 /* max satellite PRN number of QZSS */
3836 #define MINPRNQZS_S 183 /* min satellite PRN number of QZSS SAIF */
3837 #define MAXPRNQZS_S 189 /* max satellite PRN number of QZSS SAIF */
3838 #define NSATQZS (MAXPRNQZS-MINPRNQZS+1) /* number of QZSS satellites */
3839 #define NSYSQZS 1
3840 #else
3841 #define MINPRNQZS 0
3842 #define MAXPRNQZS 0
3843 #define MINPRNQZS_S 0
3844 #define MAXPRNQZS_S 0
3845 #define NSATQZS 0
3846 #define NSYSQZS 0
3847 #endif
3848 #ifdef ENACMP
3849 #define MINPRNCMP 1 /* min satellite sat number of BeiDou */
3850 #define MAXPRNCMP 35 /* max satellite sat number of BeiDou */
3851 #define NSATCMP (MAXPRNCMP-MINPRNCMP+1) /* number of BeiDou satellites */
3852 #define NSYSCMP 1
3853 #else
3854 #define MINPRNCMP 0
3855 #define MAXPRNCMP 0
3856 #define NSATCMP 0
3857 #define NSYSCMP 0
3858 #endif
3859 #ifdef ENAIRN
3860 #define MINPRNIRN 1 /* min satellite sat number of IRNSS */
3861 #define MAXPRNIRN 7 /* max satellite sat number of IRNSS */
3862 #define NSATIRN (MAXPRNIRN-MINPRNIRN+1) /* number of IRNSS satellites */
3863 #define NSYSIRN 1
3864 #else
3865 #define MINPRNIRN 0
3866 #define MAXPRNIRN 0
3867 #define NSATIRN 0
3868 #define NSYSIRN 0
3869 #endif
3870 #ifdef ENALEO
3871 #define MINPRNLEO 1 /* min satellite sat number of LEO */
3872 #define MAXPRNLEO 10 /* max satellite sat number of LEO */
3873 #define NSATLEO (MAXPRNLEO-MINPRNLEO+1) /* number of LEO satellites */
3874 #define NSYSLEO 1
3875 #else
3876 #define MINPRNLEO 0
3877 #define MAXPRNLEO 0
3878 #define NSATLEO 0
3879 #define NSYSLEO 0
3880 #endif
3881 #define NSYS (NSYSGPS+NSYSGLO+NSYSGAL+NSYSQZS+NSYSCMP+NSYSIRN+NSYSLEO) /* number of systems */
3882 #ifndef NSATSBS
3883 #ifdef ENASBS
3884 #define MINPRNSBS 120 /* min satellite PRN number of SBAS */
3885 #define MAXPRNSBS 142 /* max satellite PRN number of SBAS */
3886 #define NSATSBS (MAXPRNSBS-MINPRNSBS+1) /* number of SBAS satellites */
3887 #else
3888 #define MINPRNSBS 0
3889 #define MAXPRNSBS 0
3890 #define NSATSBS 0
3891 #endif
3892 #endif
3893 
3894 #endif
3895 /*
3896 Convert satellite constelation and prn/slot number to satellite number
3897 
3898 @param sys satellite system (SYS_GPS,SYS_GLO,...)
3899 @param prn satellite prn/slot number
3900 @return satellite number (0:error)
3901 */
3902 int satNo(int sys, int prn);
3903 
3904 /*
3905 convert satellite gnssID + svID to satellite number
3906 
3907 @param gnssID satellite system
3908 @param svID satellite prn/slot number
3909 @return satellite number (0:error)
3910 */
3911 int satNumCalc(int gnssID, int svID);
3912 
3913 
3914 #ifdef __cplusplus
3915 }
3916 #endif
3917 
3918 #endif // DATA_SETS_H
uint8_t type[24]
Definition: data_sets.h:2152
float max_ubx_error
Definition: data_sets.h:2361
uint32_t bits
Definition: data_sets.h:3154
void flipFloat(uint8_t *ptr)
Definition: data_sets.c:19
double refLla[3]
Definition: data_sets.h:2003
double lastLla[3]
Definition: data_sets.h:2006
double hgt
Definition: data_sets.h:2617
int stat_magfield
Definition: data_sets.h:937
gps_pos_t gpsPos
Definition: data_sets.h:3540
uint8_t start_rtkpos
Definition: data_sets.h:2181
uint32_t g1Task
Definition: data_sets.h:3313
unsigned int timeOfWeekMs
Definition: data_sets.h:2065
eInsStatusFlags
Definition: data_sets.h:167
double f0
Definition: data_sets.h:2521
struct PACKED can_config_t
uint8_t qualP[1]
Definition: data_sets.h:2402
uint8_t base_position_update
Definition: data_sets.h:2175
imus_t I
Definition: data_sets.h:617
float bar
Definition: data_sets.h:666
float baseToRoverVector[3]
Definition: data_sets.h:2729
uint32_t options
Definition: data_sets.h:1152
uint32_t bufferLength
Definition: USBD.h:91
uint8_t sat_id_j[24]
Definition: data_sets.h:2151
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:2452
uint32_t h3sp330BaudRate
Definition: data_sets.h:3193
double P[1]
Definition: data_sets.h:2411
uint8_t rej_ovfl
Definition: data_sets.h:2160
float humidity
Definition: data_sets.h:675
double taun
Definition: data_sets.h:2576
uint16_t reserved
Definition: data_sets.h:1170
uint32_t recalCmd
Definition: data_sets.h:1390
int16_t azim
Definition: data_sets.h:832
ins_2_t ins2
Definition: data_sets.h:3529
float PxyzNED[3]
Definition: data_sets.h:2067
struct PACKED rtk_residual_t
int32_t i[DEBUG_I_ARRAY_SIZE]
Definition: data_sets.h:2105
uint8_t LLI[1]
Definition: data_sets.h:2393
double i0
Definition: data_sets.h:2648
uint8_t gnssId
Definition: data_sets.h:820
gps_raw_t gpsRaw
Definition: data_sets.h:3552
gps_vel_t gpsVel
Definition: data_sets.h:3541
float val
Definition: data_sets.h:947
uint32_t lastLlaTimeOfWeekMs
Definition: data_sets.h:2009
struct PACKED debug_array_t
double rv_ecef[3]
Definition: data_sets.h:2136
float vDop
Definition: data_sets.h:2767
int32_t iode
Definition: data_sets.h:2440
int32_t navsys
Definition: data_sets.h:2240
uint32_t correctionChecksumFailures
Definition: data_sets.h:2848
inl2_states_t inl2States
Definition: data_sets.h:3545
double elmaskar
Definition: data_sets.h:2327
#define DEBUG_LF_ARRAY_SIZE
Definition: data_sets.h:2100
uint32_t messageLength
Definition: data_sets.h:2932
double sclkstab
Definition: data_sets.h:2321
float nis
Definition: data_sets.h:1410
double towOffset
Definition: data_sets.h:787
uint32_t repoRevision
Definition: data_sets.h:457
eBitState
Definition: data_sets.h:1420
double sec
Definition: data_sets.h:2129
struct PACKED gps_pos_t
uint8_t reset_timer
Definition: data_sets.h:2171
f_t f[DEBUG_F_ARRAY_SIZE]
Definition: data_sets.h:2106
double lf[DEBUG_LF_ARRAY_SIZE]
Definition: data_sets.h:2107
float pqrSigma
Definition: data_sets.h:1512
int start_proc_done
Definition: data_sets.h:934
is_can_ve ve
Definition: CAN_comm.h:258
float insHdg
Definition: data_sets.h:1408
uint32_t g3LineNum
Definition: data_sets.h:3319
int32_t rcvstds
Definition: data_sets.h:2285
uint32_t baseGpsEphemerisCount
Definition: data_sets.h:2809
uint32_t startupImuDtMs
Definition: data_sets.h:1970
struct PACKED gps_sat_t
uint8_t sat
Definition: data_sets.h:2384
uint32_t wrap_count_l
Definition: data_sets.h:1907
int32_t armaxiter
Definition: data_sets.h:2291
double maxinnocode
Definition: data_sets.h:2348
struct PACKED imu_t
uint32_t pashr
Definition: data_sets.h:1232
uint8_t hwVersion[10]
Definition: data_sets.h:883
double toes
Definition: data_sets.h:2515
double b[24]
Definition: data_sets.h:2141
uint8_t leapS
Definition: data_sets.h:790
uint32_t gpgga
Definition: data_sets.h:1217
eEvb2CommPorts
Definition: data_sets.h:3020
uint32_t gprmc
Definition: data_sets.h:1226
float hAccuracy
Definition: data_sets.h:2975
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:2183
float f_t
Definition: ISConstants.h:786
uint8_t warning_count
Definition: data_sets.h:2208
double gamn
Definition: data_sets.h:2579
float accuracyCov[3]
Definition: data_sets.h:2755
int32_t deltype
Definition: data_sets.h:2608
uint8_t sat_id[24]
Definition: data_sets.h:2143
int32_t rovpos
Definition: data_sets.h:2303
float progress
Definition: data_sets.h:1393
gtime_t toc
Definition: data_sets.h:2464
float lastLlaUpdateDistance
Definition: data_sets.h:2015
float gDop
Definition: data_sets.h:2761
union PACKED uDatasets
uint32_t ser2BaudRate
Definition: data_sets.h:2057
#define DEVINFO_MANUFACTURER_STRLEN
Definition: data_sets.h:149
uint32_t sysCommand
Definition: data_sets.h:3081
uint32_t evbStatus
Definition: data_sets.h:3069
float val2[3]
Definition: data_sets.h:970
float PABias[3]
Definition: data_sets.h:2073
ins_1_t ins1
Definition: data_sets.h:3528
eRtosTask
Definition: data_sets.h:3355
float insOffset[3]
Definition: data_sets.h:1985
eImuStatus
Definition: data_sets.h:730
uint8_t error_code
Definition: data_sets.h:2202
struct PACKED imus_t
uint32_t elapsedTimeSec
Definition: data_sets.h:2972
uint32_t can_period_mult[NUM_CIDS]
Definition: data_sets.h:3511
float arThreshold
Definition: data_sets.h:2758
int32_t niter
Definition: data_sets.h:2297
uint32_t outlier
Definition: data_sets.h:1406
uint32_t calBitStatus
Definition: data_sets.h:1491
int32_t mode
Definition: data_sets.h:2231
is_can_uvw uvw
Definition: CAN_comm.h:257
#define IO_CONFIG_GPS1_SOURCE(ioConfig)
Definition: data_sets.h:1870
uint32_t radioNID
Definition: data_sets.h:3160
struct PACKED inl2_status_t
double v[24]
Definition: data_sets.h:2153
double bv_ecef[3]
Definition: data_sets.h:2139
eGpsNavFixStatus
Definition: data_sets.h:268
uint8_t chi_square_error
Definition: data_sets.h:2193
float vel[3]
Definition: data_sets.h:806
uint32_t checksum
Definition: data_sets.h:1964
struct PACKED rmc_t
uint32_t maxDurationSec
Definition: data_sets.h:2966
float baseToRoverHeadingAcc
Definition: data_sets.h:2738
uint8_t large_v2b
Definition: data_sets.h:2173
#define DEVINFO_ADDINFO_STRLEN
Definition: data_sets.h:150
uint8_t svId
Definition: data_sets.h:823
float dt
Definition: data_sets.h:698
float msl
Definition: CAN_comm.h:165
double cis
Definition: data_sets.h:2512
int32_t stationId
Definition: data_sets.h:2620
float Tcal
Definition: data_sets.h:1415
uint8_t lack_of_valid_sats
Definition: data_sets.h:2191
uint32_t state
Definition: data_sets.h:2963
int32_t flag
Definition: data_sets.h:2458
magnetometer_t mag2
Definition: data_sets.h:713
float tcPqrLinearity
Definition: data_sets.h:1502
int32_t age
Definition: data_sets.h:2558
float distance
Definition: data_sets.h:1934
float omega_r
Definition: data_sets.h:1904
uint32_t loggerElapsedTimeMs
Definition: data_sets.h:3075
double maxtdiff
Definition: data_sets.h:2342
uint64_t bits
Definition: data_sets.h:1359
int32_t arfilter
Definition: data_sets.h:2264
obsd_t obs[MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE]
Definition: data_sets.h:2883
uGpsRawData data
Definition: data_sets.h:2920
int32_t sat
Definition: data_sets.h:2627
float baroTemp
Definition: data_sets.h:1058
eSurveyInStatus
Definition: data_sets.h:2938
double e
Definition: data_sets.h:2645
uint32_t baseGpsObservationCount
Definition: data_sets.h:2779
#define MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE
Definition: data_sets.h:2418
sys_params_t sysParams
Definition: data_sets.h:3549
int mag_cal_done
Definition: data_sets.h:936
float mag[3]
Definition: data_sets.h:655
uint32_t psr
Definition: data_sets.h:3331
#define GPS_RAW_MESSAGE_BUF_SIZE
Definition: data_sets.h:2417
uint32_t wrap_count_r
Definition: data_sets.h:1910
double dtaun
Definition: data_sets.h:2582
float theta_l
Definition: data_sets.h:1895
float biasPqr[3]
Definition: data_sets.h:906
float averageRunTimeUs
Definition: data_sets.h:3432
uint32_t timeOfWeekMs
Definition: data_sets.h:760
struct PACKED wheel_encoder_t
struct PACKED ins_1_t
#define NUM_WIFI_PRESETS
Definition: data_sets.h:3121
struct PACKED sys_params_t
uint8_t reserved2
Definition: data_sets.h:644
dual_imu_t imu
Definition: data_sets.h:638
uint16_t gnssSatSigConst
Definition: data_sets.h:1997
eSatSvFlags
Definition: data_sets.h:843
uint32_t gpzda
Definition: data_sets.h:1229
float barTemp
Definition: data_sets.h:672
struct PACKED inl2_ned_sigma_t
int32_t svh
Definition: data_sets.h:2449
#define PUSH_PACK_1
Definition: ISConstants.h:231
rtos_task_t task[UINS_RTOS_NUM_TASKS]
Definition: data_sets.h:3457
double OMGd
Definition: data_sets.h:2491
uint32_t eDataIDs
Definition: data_sets.h:32
double M0
Definition: data_sets.h:2485
imu_t imu
Definition: data_sets.h:3532
uint8_t code_outlier
Definition: data_sets.h:2161
struct PACKED rtos_info_t
uint32_t txBytesPerS
Definition: data_sets.h:3262
struct PACKED sys_sensors_adc_t
uint32_t h4xRadioBaudRate
Definition: data_sets.h:3196
double max_baseline_error
Definition: data_sets.h:2357
uint32_t gpioStatus
Definition: data_sets.h:1375
int32_t svconf
Definition: data_sets.h:2633
int satNumCalc(int gnssID, int svID)
Definition: data_sets.c:908
uint8_t divergent_pnt_pos_iteration
Definition: data_sets.h:2192
uint32_t roverSbasCount
Definition: data_sets.h:2836
double gainholdamb
Definition: data_sets.h:2339
#define WIFI_SSID_PSK_SIZE
Definition: data_sets.h:3085
uint32_t pins1
Definition: data_sets.h:1205
float diameter
Definition: data_sets.h:1937
float ana4
Definition: data_sets.h:1023
double f2
Definition: data_sets.h:2527
uint32_t port
Definition: data_sets.h:3106
uint16_t gpzda
Definition: data_sets.h:1185
double omg
Definition: data_sets.h:2482
struct PACKED ascii_msgs_t
double baseLla[3]
Definition: data_sets.h:2770
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:2138
#define HDW_BIT_MODE(hdwBitStatus)
Definition: data_sets.h:1441
struct PACKED dual_imu_t
uint8_t phase_outlier
Definition: data_sets.h:2162
int32_t gpsmodear
Definition: data_sets.h:2255
float tcAccLinearity
Definition: data_sets.h:1503
uint32_t timeOfWeekMs
Definition: data_sets.h:3063
uint8_t end_relpos
Definition: data_sets.h:2180
uint32_t key
Definition: data_sets.h:485
uint8_t receiverIndex
Definition: data_sets.h:2908
uint32_t week
Definition: data_sets.h:3060
uint16_t gprmc
Definition: data_sets.h:1182
eGpsStatus
Definition: data_sets.h:360
uint32_t checksum
Definition: data_sets.h:3136
uint32_t bits
Definition: data_sets.h:1925
uint32_t week
Definition: CAN_comm.h:26
float tcAccBias
Definition: data_sets.h:1495
uint32_t ser0BaudRate
Definition: data_sets.h:1976
eEvb2ComBridgePreset
Definition: data_sets.h:3205
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:3534
uint8_t cno
Definition: data_sets.h:826
struct PACKED gps_rtk_misc_t
gps_rtk_misc_t gpsRtkMisc
Definition: data_sets.h:3544
uint32_t handle
Definition: data_sets.h:3441
uint32_t u32
Definition: data_sets.h:3101
double OMG0
Definition: data_sets.h:2651
int att_aligned
Definition: data_sets.h:932
double L[1]
Definition: data_sets.h:2408
int32_t prn
Definition: data_sets.h:2595
int16_t theta1
Definition: CAN_comm.h:48
gtime_t toe
Definition: data_sets.h:2561
#define DEBUG_I_ARRAY_SIZE
Definition: data_sets.h:2098
double A
Definition: data_sets.h:2642
uint32_t timeOfWeekMs
Definition: data_sets.h:2929
float Wcal[9]
Definition: data_sets.h:1412
mag_cal_t magCal
Definition: data_sets.h:3535
int16_t vel2
Definition: CAN_comm.h:191
uint32_t radioPowerLevel
Definition: data_sets.h:3163
float magHdgOffset
Definition: data_sets.h:1414
float magInc
Definition: data_sets.h:918
int32_t iode
Definition: data_sets.h:2546
int zero_vel
Definition: data_sets.h:928
int32_t outsingle
Definition: data_sets.h:2373
int att_aligning
Definition: data_sets.h:933
double M0
Definition: data_sets.h:2657
uint32_t status
Definition: data_sets.h:3310
int ahrs
Definition: data_sets.h:923
float zeroVelRotation[3]
Definition: data_sets.h:2027
uint32_t g5Lr
Definition: data_sets.h:3325
ins_3_t ins3
Definition: data_sets.h:3530
int32_t minholdsats
Definition: data_sets.h:2279
float encoderTickToWheelRad
Definition: data_sets.h:3172
uint8_t warning_code
Definition: data_sets.h:2209
double timeOfWeek
Definition: data_sets.h:417
double ndot
Definition: data_sets.h:2536
double idot
Definition: data_sets.h:2494
uint32_t n
Definition: data_sets.h:2424
struct PACKED strobe_in_time_t
int32_t code
Definition: data_sets.h:2455
int gpsToNmeaGGA(const gps_pos_t *gps, char *buffer, int bufferLength)
Definition: data_sets.c:745
int zero_accel
Definition: data_sets.h:924
uint16_t pins1
Definition: data_sets.h:1161
gtime_t tof
Definition: data_sets.h:2564
int32_t svh
Definition: data_sets.h:2552
uint32_t timeToFirstFixMs
Definition: data_sets.h:2851
uint32_t ppimu
Definition: data_sets.h:1202
#define NUM_ANA_CHANNELS
Definition: data_sets.h:1245
float hMSL
Definition: data_sets.h:772
wheel_encoder_t wheelEncoder
Definition: data_sets.h:3537
float baseToRoverDistance
Definition: data_sets.h:2732
uint32_t roverGlonassObservationCount
Definition: data_sets.h:2782
int32_t iodc
Definition: data_sets.h:2443
gtime_t toa
Definition: data_sets.h:2639
int accel_motion
Definition: data_sets.h:926
struct PACKED inl2_mag_obs_info_t
float reserved1
Definition: data_sets.h:1064
uint32_t roverGpsObservationCount
Definition: data_sets.h:2776
uint32_t roverBeidouEphemerisCount
Definition: data_sets.h:2824
eIoConfig
Definition: data_sets.h:1805
double double_debug[4]
Definition: data_sets.h:2211
uint32_t invCommand
Definition: data_sets.h:1125
f_t barTemp
Definition: data_sets.h:1251
struct PACKED gen_1axis_sensor_t
uint8_t obs_pairs_used
Definition: data_sets.h:2218
wheel_config_t wheelConfig
Definition: data_sets.h:2051
int32_t week
Definition: data_sets.h:2636
double gpsToUnix(uint32_t gpsWeek, uint32_t gpsTimeofWeekMS, uint8_t leapSeconds)
Definition: data_sets.c:699
uint32_t ser1BaudRate
Definition: data_sets.h:1979
uint32_t auto_recal
Definition: data_sets.h:1405
double cus
Definition: data_sets.h:2506
uint16_t pimu
Definition: data_sets.h:1155
uint8_t waiting_for_base_packet
Definition: data_sets.h:2188
int ahrs_gps_cnt
Definition: data_sets.h:929
double crs
Definition: data_sets.h:2500
int32_t nv
Definition: data_sets.h:2149
float theta_r
Definition: data_sets.h:1898
double f1
Definition: data_sets.h:2524
uint32_t pins2
Definition: data_sets.h:1208
uint32_t serialNumChecksum32(const void *data, int size)
Definition: data_sets.c:551
uint32_t gapCount
Definition: data_sets.h:3435
uint32_t baseQzsObservationCount
Definition: data_sets.h:2803
float pDop
Definition: data_sets.h:781
double maxgdop
Definition: data_sets.h:2353
preintegrated_imu_t pImu
Definition: data_sets.h:3539
struct PACKED inl2_states_t
uint32_t baseAntennaCount
Definition: data_sets.h:2842
uint32_t ionUtcAlmCount
Definition: data_sets.h:2845
uint32_t lotNumber
Definition: data_sets.h:479
uint8_t bad_baseline_holdamb
Definition: data_sets.h:2167
uint32_t gpgsa
Definition: data_sets.h:1223
uint32_t buildNumber
Definition: data_sets.h:451
uint32_t numSats
Definition: data_sets.h:871
uint32_t startupGPSDtMs
Definition: data_sets.h:2042
double cuc
Definition: data_sets.h:2503
float vin
Definition: data_sets.h:1014
float minAccuracy
Definition: data_sets.h:2969
uint32_t command
Definition: data_sets.h:1122
PUSH_PACK_1 struct PACKED pos_measurement_t
float D[1]
Definition: data_sets.h:2414
float arRatio
Definition: data_sets.h:2726
uint32_t hdwStatus
Definition: CAN_comm.h:40
prcopt_t gps_rtk_opt_t
Definition: data_sets.h:2375
struct PACKED manufacturing_info_t
f_t humidity
Definition: data_sets.h:1252
uint32_t cbOptions
Definition: data_sets.h:3151
uint8_t hardwareVer[4]
Definition: data_sets.h:445
double i0
Definition: data_sets.h:2476
uint32_t runTimeUs
Definition: data_sets.h:3426
uint32_t reserved
Definition: data_sets.h:439
struct PACKED ins_3_t
double rp_ecef[3]
Definition: data_sets.h:2135
uint8_t cbPreset
Definition: data_sets.h:3142
float cpuUsage
Definition: data_sets.h:3438
float magInclination
Definition: data_sets.h:2033
pos_measurement_t posMeasurement
Definition: data_sets.h:3538
float accuracyCovUD[6]
Definition: data_sets.h:426
float hDop
Definition: data_sets.h:2764
uint8_t waiting_for_rover_packet
Definition: data_sets.h:2187
int32_t maxout
Definition: data_sets.h:2267
int32_t glomodear
Definition: data_sets.h:2252
float mslBar
Definition: data_sets.h:669
uint16_t ppimu
Definition: data_sets.h:1158
uint8_t code[1]
Definition: data_sets.h:2396
uint8_t raw_ptr_queue_overrun
Definition: data_sets.h:2219
struct PACKED io_t
struct PACKED gps_version_t
uint8_t reserved1
Definition: data_sets.h:643
float declination
Definition: data_sets.h:1396
uint32_t roverGpsEphemerisCount
Definition: data_sets.h:2806
eRTKConfigBits
Definition: data_sets.h:1586
uint8_t swVersion[30]
Definition: data_sets.h:881
uint16_t gpgll
Definition: data_sets.h:1176
double elmin
Definition: data_sets.h:2243
double A
Definition: data_sets.h:2470
float nis_threshold
Definition: data_sets.h:1411
float PvelNED[3]
Definition: data_sets.h:2069
uint32_t genFaultCode
Definition: data_sets.h:1079
uint8_t start_relpos
Definition: data_sets.h:2178
struct PACKED preintegrated_imu_t
sta_t sta
Definition: data_sets.h:2895
struct PACKED wheel_config_t
uint8_t buf[GPS_RAW_MESSAGE_BUF_SIZE]
Definition: data_sets.h:2901
ins_4_t ins4
Definition: data_sets.h:3531
eph_t eph
Definition: data_sets.h:2886
char addInfo[DEVINFO_ADDINFO_STRLEN]
Definition: data_sets.h:469
float tcPqrSlope
Definition: data_sets.h:1498
float baseToRoverHeading
Definition: data_sets.h:2735
float sAcc
Definition: data_sets.h:809
int32_t minfix
Definition: data_sets.h:2288
double OMGd
Definition: data_sets.h:2660
int zero_angrate
Definition: data_sets.h:925
int32_t sva
Definition: data_sets.h:2555
uint8_t buildDate[4]
Definition: data_sets.h:463
int64_t time
Definition: data_sets.h:2126
double lla[3]
Definition: data_sets.h:511
int16_t theta2
Definition: CAN_comm.h:49
float magInsHdgDelta
Definition: data_sets.h:1409
uint32_t roverGlonassEphemerisCount
Definition: data_sets.h:2812
eMagRecalMode
Definition: data_sets.h:1378
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:2071
double thresslip
Definition: data_sets.h:2333
float magDeclination
Definition: data_sets.h:2036
double cic
Definition: data_sets.h:2509
eRtkSolStatus
Definition: data_sets.h:2695
eEvbFlashCfgBits
Definition: data_sets.h:3110
uint8_t gdop_error
Definition: data_sets.h:2207
double omg
Definition: data_sets.h:2654
int32_t svh
Definition: data_sets.h:2630
uint32_t status
Definition: CAN_comm.h:114
struct PACKED ins_output_t
union PACKED uGpsRawData
uint32_t gpgll
Definition: data_sets.h:1220
uint32_t baseSbasCount
Definition: data_sets.h:2839
f_t ana[NUM_ANA_CHANNELS]
Definition: data_sets.h:1253
char manufacturer[DEVINFO_MANUFACTURER_STRLEN]
Definition: data_sets.h:460
uint8_t rescode_err_marker
Definition: data_sets.h:2200
uint32_t sensorConfig
Definition: data_sets.h:2048
double qr[6]
Definition: data_sets.h:2140
uint8_t pnt_pos_error
Definition: data_sets.h:2182
int32_t maxaveep
Definition: data_sets.h:2370
sys_sensors_t sysSensors
Definition: data_sets.h:3550
int32_t bdsmodear
Definition: data_sets.h:2261
float PBaroBias
Definition: data_sets.h:2077
uint32_t count
Definition: data_sets.h:2095
uint32_t RTKCfgBits
Definition: data_sets.h:2045
uint16_t pgpsp
Definition: data_sets.h:1167
float gps1AntOffset[3]
Definition: data_sets.h:1988
int32_t modear
Definition: data_sets.h:2249
int32_t refpos
Definition: data_sets.h:2306
struct PACKED barometer_t
float magHdg
Definition: data_sets.h:1407
uint32_t ioConfig
Definition: data_sets.h:2018
uint32_t key
Definition: data_sets.h:3139
eCalBitStatusFlags
Definition: data_sets.h:1455
#define INS_STATUS_SOLUTION(insStatus)
Definition: data_sets.h:213
float insRotation[3]
Definition: data_sets.h:1982
dev_info_t devInfo
Definition: data_sets.h:3527
uint8_t code_large_residual
Definition: data_sets.h:2163
gtime_t toe
Definition: data_sets.h:2461
int ubxSys(int gnssID)
Definition: data_sets.c:849
float tcPqrBias
Definition: data_sets.h:1494
float gpsMinimumElevation
Definition: data_sets.h:2054
int32_t sbsmodear
Definition: data_sets.h:2258
def insStatus(istatus)
INS Status #####.
uint8_t insDynModel
Definition: data_sets.h:1991
uint32_t baseGalileoEphemerisCount
Definition: data_sets.h:2821
uint8_t obs_pairs_filtered
Definition: data_sets.h:2217
int16_t vel1
Definition: CAN_comm.h:181
uint32_t wifiIpAddr
Definition: data_sets.h:3078
int32_t tow
Definition: data_sets.h:2592
gtime_t ttr
Definition: data_sets.h:2467
uint8_t rcv
Definition: data_sets.h:2387
uint8_t use_ubx_position
Definition: data_sets.h:2172
rmc_t rmc
Definition: data_sets.h:3554
double varholdamb
Definition: data_sets.h:2336
double deln
Definition: data_sets.h:2488
int32_t mindropsats
Definition: data_sets.h:2282
uint32_t freeHeapSize
Definition: data_sets.h:3448
f_t bar
Definition: data_sets.h:1250
uint32_t activeCalSet
Definition: data_sets.h:1413
struct PACKED dual_imu_ok_t
struct PACKED gps_rtk_rel_t
struct PACKED gen_3axis_sensord_t
int32_t sat
Definition: data_sets.h:2543
struct PACKED ascii_msgs_u32_t
eWheelCfgBits
Definition: data_sets.h:1914
float acc[3]
Definition: data_sets.h:606
uint8_t debug[2]
Definition: data_sets.h:2213
uint32_t insStatus
Definition: CAN_comm.h:37
uint32_t roverGalileoEphemerisCount
Definition: data_sets.h:2818
sensors_mpu_w_temp_t mpu[NUM_IMU_DEVICES]
Definition: data_sets.h:1249
double time
Definition: data_sets.h:614
obsd_t * data
Definition: data_sets.h:2430
float tcAccSlope
Definition: data_sets.h:1499
struct PACKED nvm_flash_cfg_t
int fix_reset_base_msgs
Definition: data_sets.h:2345
uint32_t maxRunTimeUs
Definition: data_sets.h:3429
uint8_t reset_bias
Definition: data_sets.h:2177
#define MAX_TASK_NAME_LEN
Definition: data_sets.h:3408
ROSCPP_DECL bool del(const std::string &key)
uint8_t rover_position_error
Definition: data_sets.h:2176
double Adot
Definition: data_sets.h:2533
float differentialAge
Definition: data_sets.h:2723
#define MAX_NUM_SAT_CHANNELS
Definition: data_sets.h:146
uint32_t baseGalileoObservationCount
Definition: data_sets.h:2791
uint8_t base_position_error
Definition: data_sets.h:2168
uint32_t periodMs
Definition: data_sets.h:3423
int32_t snrmin
Definition: data_sets.h:2246
float theta[3]
Definition: data_sets.h:505
struct PACKED sys_sensors_t
uint32_t baseGlonassEphemerisCount
Definition: data_sets.h:2815
struct PACKED sensors_mpu_w_temp_t
uint32_t pgpsp
Definition: data_sets.h:1211
eEvbStatus
Definition: data_sets.h:2982
uint32_t gpsTimeSyncPeriodMs
Definition: data_sets.h:2039
int32_t minfixsats
Definition: data_sets.h:2276
int32_t week
Definition: data_sets.h:2589
uint16_t pins2
Definition: data_sets.h:1164
uint32_t serialNumber
Definition: data_sets.h:442
uint32_t lastLlaWeek
Definition: data_sets.h:2012
uint8_t lsq_error
Definition: data_sets.h:2190
struct PACKED debug_string_t
uint32_t sysCfgBits
Definition: data_sets.h:2000
uint32_t baseQzsEphemerisCount
Definition: data_sets.h:2833
int32_t maxrej
Definition: data_sets.h:2270
magnetometer_t mag1
Definition: data_sets.h:712
uint32_t mallocSize
Definition: data_sets.h:3451
eEvb2PortOptions
Definition: data_sets.h:3048
uint32_t size
Definition: data_sets.h:3133
struct PACKED obsd_t
float ned[3]
Definition: data_sets.h:514
float biasAcc[3]
Definition: data_sets.h:909
double reset_baseline_error
Definition: data_sets.h:2358
barometer_t baro
Definition: data_sets.h:3536
float e_i2l[3]
Definition: data_sets.h:1928
#define POP_PACK
Definition: ISConstants.h:234
uint8_t invalid_base_position
Definition: data_sets.h:2166
gps_rtk_rel_t gpsRtkRel
Definition: data_sets.h:3543
uint32_t cycle_slips
Definition: data_sets.h:2195
double f0
Definition: data_sets.h:2666
double ecef[3]
Definition: data_sets.h:420
union PACKED uInsOutDatasets
struct PACKED pimu_mag_t
uint32_t g4
Definition: data_sets.h:3322
struct PACKED gen_dual_3axis_sensor_t
uint8_t obs_count_bas
Definition: data_sets.h:2214
float dist2base
Definition: data_sets.h:2204
double maxnis
Definition: data_sets.h:2350
float psi
Definition: data_sets.h:423
struct PACKED bit_t
float imuTemp
Definition: data_sets.h:1055
uint8_t raw_dat_queue_overrun
Definition: data_sets.h:2220
gps_sat_sv_t sat[MAX_NUM_SAT_CHANNELS]
Definition: data_sets.h:873
float ana1
Definition: data_sets.h:1017
uint16_t * getStringOffsetsLengths(eDataIDs dataId, uint16_t *offsetsLength)
Definition: data_sets.c:382
eEvb2ComBridgeOptions
Definition: data_sets.h:3036
int32_t sat
Definition: data_sets.h:2437
nvm_flash_cfg_t flashCfg
Definition: data_sets.h:3547
struct PACKED magnetometer_t
uint32_t ready
Definition: data_sets.h:1403
struct PACKED system_command_t
float zeroVelOffset[3]
Definition: data_sets.h:2030
survey_in_t surveyIn
Definition: data_sets.h:3548
uint32_t rxBytesPerS
Definition: data_sets.h:3265
struct PACKED gps_raw_t
rtos_info_t rtosInfo
Definition: data_sets.h:3551
uint64_t didToRmcBit(uint32_t dataId, uint64_t defaultRmcBits)
Definition: data_sets.c:563
uint8_t obs_count_rov
Definition: data_sets.h:2215
float ana3
Definition: data_sets.h:1020
void flipEndianess32(uint8_t *data, int dataLength)
Definition: data_sets.c:73
double maxinnophase
Definition: data_sets.h:2349
uint8_t buildTime[4]
Definition: data_sets.h:466
float bias_cal[3]
Definition: data_sets.h:1416
ion_model_utc_alm_t ion
Definition: data_sets.h:2898
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:2197
struct PACKED rtos_task_t
inl2_ned_sigma_t inl2NedSigma
Definition: data_sets.h:3546
int8_t elev
Definition: data_sets.h:829
double f1
Definition: data_sets.h:2669
uint32_t roverGalileoObservationCount
Definition: data_sets.h:2788
uint8_t firmwareVer[4]
Definition: data_sets.h:448
int32_t nf
Definition: data_sets.h:2237
double sensorTruePeriod
Definition: data_sets.h:1073
uint16_t gpgsa
Definition: data_sets.h:1179
float hAcc
Definition: data_sets.h:775
struct PACKED ins_2_t
uint32_t can_transmit_address[NUM_CIDS]
Definition: data_sets.h:3514
uint32_t g2FileNum
Definition: data_sets.h:3316
eSystemCommand
Definition: data_sets.h:1129
uint32_t baseBeidouObservationCount
Definition: data_sets.h:2797
uint32_t hdwBitStatus
Definition: data_sets.h:1488
uint32_t roverBeidouObservationCount
Definition: data_sets.h:2794
uint32_t pin
Definition: data_sets.h:2092
float vAcc
Definition: data_sets.h:778
uint16_t pashr
Definition: data_sets.h:1188
uint8_t imu1ok
Definition: data_sets.h:641
float qe2b[4]
Definition: data_sets.h:589
int32_t soltype
Definition: data_sets.h:2234
float PDeclination
Definition: data_sets.h:2079
int32_t sva
Definition: data_sets.h:2446
uint32_t loggerMode
Definition: data_sets.h:3072
float mcuTemp
Definition: data_sets.h:1061
float accuracyPos[3]
Definition: data_sets.h:2752
int32_t dynamics
Definition: data_sets.h:2294
uint32_t portOptions
Definition: data_sets.h:3190
uint32_t roverQzsEphemerisCount
Definition: data_sets.h:2830
geph_t gloEph
Definition: data_sets.h:2889
struct PACKED gps_vel_t
uint32_t can_receive_address
Definition: data_sets.h:3520
uint8_t solStatus
Definition: data_sets.h:2199
int16_t prRes
Definition: data_sets.h:835
POP_PACK uint32_t checksum32(const void *data, int count)
Definition: data_sets.c:531
#define DEBUG_STRING_SIZE
Definition: data_sets.h:2110
int32_t intpref
Definition: data_sets.h:2300
uint8_t obsCount
Definition: data_sets.h:2914
eEvb2LoggerMode
Definition: data_sets.h:3239
sys_sensors_adc_t sensorsAdc
Definition: data_sets.h:3553
float gps2AntOffset[3]
Definition: data_sets.h:2024
uint32_t baseBeidouEphemerisCount
Definition: data_sets.h:2827
int rot_motion
Definition: data_sets.h:927
uint8_t outc_ovfl
Definition: data_sets.h:2170
is_can_time time
Definition: CAN_comm.h:252
struct PACKED rtk_debug_t
uint32_t pimu
Definition: data_sets.h:1199
double elmaskhold
Definition: data_sets.h:2330
uint8_t moveb_time_sync_error
Definition: data_sets.h:2186
struct PACKED gen_3axis_sensor_t
struct PACKED dev_info_t
uint8_t dataType
Definition: data_sets.h:2911
#define NUM_SERIAL_PORTS
Definition: data_sets.h:1258
uint8_t s[DEBUG_STRING_SIZE]
Definition: data_sets.h:2115
float t_i2l[3]
Definition: data_sets.h:1931
int32_t frq
Definition: data_sets.h:2549
float flipFloatCopy(float val)
Definition: data_sets.c:31
eHdwBitStatusFlags
Definition: data_sets.h:1434
eEvbRtosTask
Definition: data_sets.h:3380
uint32_t can_baudrate_kbps
Definition: data_sets.h:3517
float biasBaro
Definition: data_sets.h:912
float att_err
Definition: data_sets.h:930
double gpsToJulian(int32_t gpsWeek, int32_t gpsMilliseconds, int32_t leapSeconds)
Definition: data_sets.c:708
uint32_t radioPID
Definition: data_sets.h:3157
uint8_t phase_large_residual
Definition: data_sets.h:2165
uint32_t Ncal_samples
Definition: data_sets.h:1402
uint32_t calibrated
Definition: data_sets.h:1404
float val1[3]
Definition: data_sets.h:967
uint32_t stackUnused
Definition: data_sets.h:3420
uint32_t startupNavDtMs
Definition: data_sets.h:1973
double fit
Definition: data_sets.h:2518
uint8_t extension[30]
Definition: data_sets.h:885
uint32_t nmax
Definition: data_sets.h:2427
uint8_t uinsComPort
Definition: data_sets.h:3181
float omega_l
Definition: data_sets.h:1901
float accSigma
Definition: data_sets.h:1515
eHdwStatusFlags
Definition: data_sets.h:277
eSysConfigBits
Definition: data_sets.h:1521
uint32_t imuPeriodMs
Definition: data_sets.h:1067
uint8_t sat_id_i[24]
Definition: data_sets.h:2150
uint32_t freeSize
Definition: data_sets.h:3454
preintegrated_imu_t pimu
Definition: data_sets.h:721
float temp
Definition: data_sets.h:990
uint8_t SNR[1]
Definition: data_sets.h:2390
struct PACKED imu_mag_t
float PWBias[3]
Definition: data_sets.h:2075
char name[MAX_TASK_NAME_LEN]
Definition: data_sets.h:3414
uint32_t navPeriodMs
Definition: data_sets.h:1070
eGnssSatSigConst
Definition: data_sets.h:1561
uint8_t diff_age_error
Definition: data_sets.h:2185
struct PACKED rtk_state_t
uint32_t can_receive_address
Definition: data_sets.h:3178
f_t temp
Definition: data_sets.h:1242
int32_t minlock
Definition: data_sets.h:2273
float cnoMean
Definition: data_sets.h:784
uint32_t cycleSlipCount
Definition: data_sets.h:2773
uint32_t size
uint32_t state
Definition: data_sets.h:1485
double ra_ecef[3]
Definition: data_sets.h:2137
float magDec
Definition: data_sets.h:915
uint8_t qualL[1]
Definition: data_sets.h:2399
double qb[24]
Definition: data_sets.h:2142
gps_sat_t gpsSat
Definition: data_sets.h:3542
uint16_t gpgga
Definition: data_sets.h:1173
eSensorConfig
Definition: data_sets.h:1732
#define PUSH_PACK_8
Definition: ISConstants.h:233
uint32_t roverQzsObservationCount
Definition: data_sets.h:2800
struct PACKED gps_sat_sv_t
uint32_t pc
Definition: data_sets.h:3328
uint32_t cBrdConfig
Definition: data_sets.h:2021
uint32_t baseGlonassObservationCount
Definition: data_sets.h:2785
#define DEBUG_F_ARRAY_SIZE
Definition: data_sets.h:2099
double OMG0
Definition: data_sets.h:2479
struct PACKED evb_rtos_info_t
double crc
Definition: data_sets.h:2497
struct PACKED mag_cal_t
uint32_t priority
Definition: data_sets.h:3417
uint32_t h8gpioBaudRate
Definition: data_sets.h:3199
uint8_t error_count
Definition: data_sets.h:2201
uint8_t uinsAuxPort
Definition: data_sets.h:3184
uint32_t CANbaud_kbps
Definition: data_sets.h:3175
eInsDynModel
Definition: data_sets.h:1941
char date[16]
Definition: data_sets.h:482
eRawDataType
Definition: data_sets.h:2856
double e
Definition: data_sets.h:2473
dual_imu_t dualImu
Definition: data_sets.h:3533
int mag_cal_good
Definition: data_sets.h:935
sbsmsg_t sbas
Definition: data_sets.h:2892
eGenFaultCodes
Definition: data_sets.h:1083
double toas
Definition: data_sets.h:2663
uint8_t imu2ok
Definition: data_sets.h:642
void flipDouble(void *ptr)
Definition: data_sets.c:47
int att_coarse
Definition: data_sets.h:931
uint32_t flags
Definition: data_sets.h:838


inertial_sense_ros
Author(s):
autogenerated on Sun Feb 28 2021 03:17:57