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? 138 #define DID_COUNT (eDataIDs)96 141 #define DID_MAX_COUNT 256 146 #define MAX_NUM_SAT_CHANNELS 50 149 #define DEVINFO_MANUFACTURER_STRLEN 24 150 #define DEVINFO_ADDINFO_STRLEN 24 156 #define PROTOCOL_VERSION_CHAR2 (0x000000FF&DID_COUNT) 157 #define PROTOCOL_VERSION_CHAR3 8 // Minor (in data_sets.h) 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 164 #define NUM_IMU_DEVICES 2 237 #define INS_STATUS_NAV_FIX_STATUS(insStatus) ((insStatus&INS_STATUS_GPS_NAV_FIX_MASK)>>INS_STATUS_GPS_NAV_FIX_OFFSET) 330 #define HDW_STATUS_COM_PARSE_ERROR_COUNT(hdwStatus) ((hdwStatus&HDW_STATUS_COM_PARSE_ERR_COUNT_MASK)>>HDW_STATUS_COM_PARSE_ERR_COUNT_OFFSET) 1188 #define NUM_ANA_CHANNELS 4 1199 #define NUM_COM_PORTS 3 // Number of communication ports. (Ser0, Ser1, and USB). 1200 #ifndef NUM_SERIAL_PORTS 1201 #define NUM_SERIAL_PORTS 5 1211 #define RMC_OPTIONS_PORT_MASK 0x000000FF 1212 #define RMC_OPTIONS_PORT_ALL (RMC_OPTIONS_PORT_MASK) 1213 #define RMC_OPTIONS_PORT_CURRENT 0x00000000 1214 #define RMC_OPTIONS_PORT_SER0 0x00000001 1215 #define RMC_OPTIONS_PORT_SER1 0x00000002 // also SPI 1216 #define RMC_OPTIONS_PORT_USB 0x00000004 1217 #define RMC_OPTIONS_PRESERVE_CTRL 0x00000100 // Prevent any messages from getting turned off by bitwise OR'ing new message bits with current message bits. 1218 #define RMC_OPTIONS_PERSISTENT 0x00000200 // Save current port RMC to flash memory for use following reboot, eliminating need to re-enable RMC to start data streaming. 1221 #define RMC_BITS_INS1 0x0000000000000001 // rmc.insPeriodMs (4ms default) 1222 #define RMC_BITS_INS2 0x0000000000000002 // " 1223 #define RMC_BITS_INS3 0x0000000000000004 // " 1224 #define RMC_BITS_INS4 0x0000000000000008 // " 1225 #define RMC_BITS_DUAL_IMU 0x0000000000000010 // DID_FLASH_CONFIG.startupNavDtMs (4ms default) 1226 #define RMC_BITS_PREINTEGRATED_IMU 0x0000000000000020 // " 1227 #define RMC_BITS_BAROMETER 0x0000000000000040 // ~8ms 1228 #define RMC_BITS_MAGNETOMETER1 0x0000000000000080 // ~10ms 1229 #define RMC_BITS_MAGNETOMETER2 0x0000000000000100 // " 1231 #define RMC_BITS_GPS1_POS 0x0000000000000400 // DID_FLASH_CONFIG.startupGpsDtMs (200ms default) 1232 #define RMC_BITS_GPS2_POS 0x0000000000000800 // " 1233 #define RMC_BITS_GPS1_RAW 0x0000000000001000 // " 1234 #define RMC_BITS_GPS2_RAW 0x0000000000002000 // " 1235 #define RMC_BITS_GPS1_SAT 0x0000000000004000 // 1s 1236 #define RMC_BITS_GPS2_SAT 0x0000000000008000 // " 1237 #define RMC_BITS_GPS_BASE_RAW 0x0000000000010000 // 1238 #define RMC_BITS_STROBE_IN_TIME 0x0000000000020000 // On strobe input event 1239 #define RMC_BITS_DIAGNOSTIC_MESSAGE 0x0000000000040000 1240 #define RMC_BITS_DUAL_IMU_RAW 0x0000000000080000 // DID_FLASH_CONFIG.startupImuDtMs (1ms default) 1241 #define RMC_BITS_GPS1_VEL 0x0000000000100000 // DID_FLASH_CONFIG.startupGpsDtMs (200ms default) 1242 #define RMC_BITS_GPS2_VEL 0x0000000000200000 // " 1243 #define RMC_BITS_GPS1_UBX_POS 0x0000000000400000 // " 1244 #define RMC_BITS_GPS1_RTK_POS 0x0000000000800000 // " 1245 #define RMC_BITS_GPS1_RTK_POS_REL 0x0000000001000000 // " 1246 #define RMC_BITS_GPS1_RTK_POS_MISC 0x0000000004000000 // " 1247 #define RMC_BITS_INL2_NED_SIGMA 0x0000000008000000 1248 #define RMC_BITS_RTK_STATE 0x0000000010000000 1249 #define RMC_BITS_RTK_CODE_RESIDUAL 0x0000000020000000 1250 #define RMC_BITS_RTK_PHASE_RESIDUAL 0x0000000040000000 1251 #define RMC_BITS_WHEEL_ENCODER 0x0000000080000000 1252 #define RMC_BITS_WHEEL_CONFIG 0x0000000100000000 1253 #define RMC_BITS_DUAL_IMU_MAG_RAW 0x0000000200000000 1254 #define RMC_BITS_DUAL_IMU_MAG 0x0000000400000000 1255 #define RMC_BITS_PREINTEGRATED_IMU_MAG 0x0000000800000000 1256 #define RMC_BITS_GPS1_RTK_HDG_REL 0x0000001000000000 // DID_FLASH_CONFIG.startupGpsDtMs (200ms default) 1257 #define RMC_BITS_GPS1_RTK_HDG_MISC 0x0000002000000000 // " 1258 #define RMC_BITS_MASK 0x0FFFFFFFFFFFFFFF 1259 #define RMC_BITS_INTERNAL_PPD 0x4000000000000000 // 1260 #define RMC_BITS_PRESET 0x8000000000000000 // Indicate BITS is a preset 1262 #define RMC_PRESET_PPD_NAV_PERIOD_MULT 25 1263 #define RMC_PRESET_INS_NAV_PERIOD_MULT 1 // fastest rate (nav filter update rate) 1266 #define RMC_PRESET_PPD_BITS_NO_IMU (RMC_BITS_PRESET \ 1268 | RMC_BITS_BAROMETER \ 1269 | RMC_BITS_MAGNETOMETER1 \ 1270 | RMC_BITS_MAGNETOMETER2 \ 1271 | RMC_BITS_GPS1_POS \ 1272 | RMC_BITS_GPS2_POS \ 1273 | RMC_BITS_GPS1_VEL \ 1274 | RMC_BITS_GPS2_VEL \ 1275 | RMC_BITS_GPS1_RAW \ 1276 | RMC_BITS_GPS2_RAW \ 1277 | RMC_BITS_GPS_BASE_RAW \ 1278 | RMC_BITS_GPS1_RTK_POS_REL \ 1279 | RMC_BITS_GPS1_RTK_HDG_REL \ 1280 | RMC_BITS_INTERNAL_PPD \ 1281 | RMC_BITS_DIAGNOSTIC_MESSAGE) 1282 #define RMC_PRESET_PPD_BITS (RMC_PRESET_PPD_BITS_NO_IMU \ 1283 | RMC_BITS_PREINTEGRATED_IMU) 1284 #define RMC_PRESET_INS_BITS (RMC_BITS_INS2 \ 1285 | RMC_BITS_GPS1_POS \ 1287 #define RMC_PRESET_PPD_BITS_RAW_IMU (RMC_PRESET_PPD_BITS_NO_IMU \ 1288 | RMC_BITS_DUAL_IMU_RAW) 1289 #define RMC_PRESET_PPD_BITS_RTK_DBG (RMC_PRESET_PPD_BITS \ 1290 | RMC_BITS_RTK_STATE \ 1291 | RMC_BITS_RTK_CODE_RESIDUAL \ 1292 | RMC_BITS_RTK_PHASE_RESIDUAL) 1293 #define RMC_PRESET_PPD_ROBOT (RMC_PRESET_PPD_BITS\ 1294 | RMC_BITS_WHEEL_ENCODER \ 1295 | RMC_BITS_WHEEL_CONFIG) 1402 #define CAL_BIT_MODE(calBitStatus) ((calBitStatus&CAL_BIT_MODE_MASK)>>CAL_BIT_MODE_OFFSET) 1478 #define SYS_CFG_BITS_MAG_RECAL_MODE(sysCfgBits) ((sysCfgBits&SYS_CFG_BITS_MAG_RECAL_MODE_MASK)>>SYS_CFG_BITS_MAG_RECAL_MODE_OFFSET) 1522 GNSS_SAT_SIG_CONST_GPS | \
1523 GNSS_SAT_SIG_CONST_SBAS | \
1524 GNSS_SAT_SIG_CONST_QZSS | \
1525 GNSS_SAT_SIG_CONST_GAL | \
1526 GNSS_SAT_SIG_CONST_GLO
1726 #define IO_CFG_GPS_TIMEPUSE_SOURCE(ioConfig) ((ioConfig>>IO_CFG_GPS_TIMEPUSE_SOURCE_OFFSET)&IO_CFG_GPS_TIMEPUSE_SOURCE_MASK) 1759 #define IO_CONFIG_GPS1_SOURCE(ioConfig) ((ioConfig>>IO_CONFIG_GPS1_SOURCE_OFFSET)&IO_CONFIG_GPS_SOURCE_MASK) 1760 #define IO_CONFIG_GPS2_SOURCE(ioConfig) ((ioConfig>>IO_CONFIG_GPS2_SOURCE_OFFSET)&IO_CONFIG_GPS_SOURCE_MASK) 1761 #define IO_CONFIG_GPS1_TYPE(ioConfig) ((ioConfig>>IO_CONFIG_GPS1_TYPE_OFFSET)&IO_CONFIG_GPS_TYPE_MASK) 1762 #define IO_CONFIG_GPS2_TYPE(ioConfig) ((ioConfig>>IO_CONFIG_GPS2_TYPE_OFFSET)&IO_CONFIG_GPS_TYPE_MASK) 1981 #define DEBUG_I_ARRAY_SIZE 9 1982 #define DEBUG_F_ARRAY_SIZE 9 1983 #define DEBUG_LF_ARRAY_SIZE 3 1993 #define DEBUG_STRING_SIZE 80 2300 #define GPS_RAW_MESSAGE_BUF_SIZE 1000 2301 #define MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE (GPS_RAW_MESSAGE_BUF_SIZE / sizeof(obsd_t)) 2968 #define WIFI_SSID_PSK_SIZE 40 2999 #define NUM_WIFI_PRESETS 3 3000 #define EVB_CFG_BITS_SET_IDX_WIFI(bits,idx) {bits&=EVB_CFG_BITS_WIFI_SELECT_MASK; bits|=((idx<<EVB_CFG_BITS_WIFI_SELECT_OFFSET)&EVB_CFG_BITS_WIFI_SELECT_MASK);} 3001 #define EVB_CFG_BITS_SET_IDX_SERVER(bits,idx) {bits&=EVB_CFG_BITS_SERVER_SELECT_MASK; bits|=((idx<<EVB_CFG_BITS_SERVER_SELECT_OFFSET)&EVB_CFG_BITS_SERVER_SELECT_MASK);} 3002 #define EVB_CFG_BITS_IDX_WIFI(bits) ((bits&EVB_CFG_BITS_WIFI_SELECT_MASK)>>EVB_CFG_BITS_WIFI_SELECT_OFFSET) 3003 #define EVB_CFG_BITS_IDX_SERVER(bits) ((bits&EVB_CFG_BITS_SERVER_SELECT_MASK)>>EVB_CFG_BITS_SERVER_SELECT_OFFSET) 3114 #define EVB2_CB_PRESET_DEFAULT EVB2_CB_PRESET_RS232 3161 #define SYS_FAULT_STATUS_HARDWARE_RESET 0x00000000 3162 #define SYS_FAULT_STATUS_USER_RESET 0x00000001 3163 #define SYS_FAULT_STATUS_ENABLE_BOOTLOADER 0x00000002 3165 #define SYS_FAULT_STATUS_SOFT_RESET 0x00000010 3166 #define SYS_FAULT_STATUS_FLASH_MIGRATION_EVENT 0x00000020 3167 #define SYS_FAULT_STATUS_FLASH_MIGRATION_COMPLETED 0x00000040 3168 #define SYS_FAULT_STATUS_RTK_MISC_ERROR 0x00000080 3169 #define SYS_FAULT_STATUS_MASK_GENERAL_ERROR 0xFFFFFFF0 3171 #define SYS_FAULT_STATUS_HARD_FAULT 0x00010000 3172 #define SYS_FAULT_STATUS_USAGE_FAULT 0x00020000 3173 #define SYS_FAULT_STATUS_MEM_MANGE 0x00040000 3174 #define SYS_FAULT_STATUS_BUS_FAULT 0x00080000 3175 #define SYS_FAULT_STATUS_MALLOC_FAILED 0x00100000 3176 #define SYS_FAULT_STATUS_STACK_OVERFLOW 0x00200000 3177 #define SYS_FAULT_STATUS_INVALID_CODE_OPERATION 0x00400000 3178 #define SYS_FAULT_STATUS_FLASH_MIGRATION_MARKER_UPDATED 0x00800000 3179 #define SYS_FAULT_STATUS_WATCHDOG_RESET 0x01000000 3180 #define SYS_FAULT_STATUS_RTK_BUFFER_LIMIT 0x02000000 3181 #define SYS_FAULT_STATUS_SENSOR_CALIBRATION 0x04000000 3182 #define SYS_FAULT_STATUS_HARDWARE_DETECTION 0x08000000 3183 #define SYS_FAULT_STATUS_MASK_CRITICAL_ERROR 0xFFFF0000 3286 #define MAX_TASK_NAME_LEN 12 3507 void flipDoubles(uint8_t* data,
int dataLength,
int offset, uint16_t* offsets, uint16_t offsetsLength);
3518 void flipStrings(uint8_t* data,
int dataLength,
int offset, uint16_t* offsets, uint16_t offsetsLength);
3522 #if CPU_IS_BIG_ENDIAN 3523 #define BE_SWAP64F(_i) flipDoubleCopy(_i) 3524 #define BE_SWAP32F(_i) flipFloatCopy(_i) 3525 #define BE_SWAP32(_i) (SWAP32(_i)) 3526 #define BE_SWAP16(_i) (SWAP16(_i)) 3527 #define LE_SWAP64F(_i) (_i) 3528 #define LE_SWAP32F(_i) (_i) 3529 #define LE_SWAP32(_i) (_i) 3530 #define LE_SWAP16(_i) (_i) 3531 #else // little endian 3532 #define BE_SWAP64F(_i) (_i) 3533 #define BE_SWAP32F(_i) (_i) 3534 #define BE_SWAP32(_i) (_i) 3535 #define BE_SWAP16(_i) (_i) 3536 #define LE_SWAP64F(_i) flipDoubleCopy(_i) 3537 #define LE_SWAP32F(_i) flipFloatCopy(_i) 3538 #define LE_SWAP32(_i) (SWAP32(_i)) 3539 #define LE_SWAP16(_i) (SWAP16(_i)) 3563 uint64_t
didToRmcBit(uint32_t dataId, uint64_t defaultRmcBits);
3566 #define SECONDS_PER_WEEK 604800 3567 #define SECONDS_PER_DAY 86400 3568 #define GPS_TO_UNIX_OFFSET 315964800 3570 double gpsToUnix(uint32_t
gpsWeek, uint32_t gpsTimeofWeekMS, uint8_t leapSeconds);
3573 void julianToDate(
double julian, int32_t* year, int32_t* month, int32_t* day, int32_t* hour, int32_t* minute, int32_t* second, int32_t* millisecond);
3589 #define SYS_NONE 0x00 3590 #define SYS_GPS 0x01 3591 #define SYS_SBS 0x02 3592 #define SYS_GLO 0x04 3593 #define SYS_GAL 0x08 3594 #define SYS_QZS 0x10 3595 #define SYS_CMP 0x20 3596 #define SYS_IRN 0x40 3597 #define SYS_LEO 0x80 3598 #define SYS_ALL 0xFF 3609 #ifndef __RTKLIB_EMBEDDED_DEFINES_H_ 3624 #define MAXSUBFRMLEN 152 3627 #define MAXRAWLEN 2048 3650 #define MAXOBS 56 // Also defined inside rtklib_defines.h 3651 #define HALF_MAXOBS (MAXOBS/2) 3654 #define NUMSATSOL 22 3663 #define MINPRNSBS 133 3666 #define MAXPRNSBS 138 3669 #define NSATSBS (MAXPRNSBS - MINPRNSBS + 1) 3671 #define SBAS_EPHEMERIS_ARRAY_SIZE NSATSBS 3675 #define SBAS_EPHEMERIS_ARRAY_SIZE 0 3685 #define MAXPRNGPS 32 3686 #define NSATGPS (MAXPRNGPS-MINPRNGPS+1) 3691 #define MAXPRNGLO 27 3692 #define NSATGLO (MAXPRNGLO-MINPRNGLO+1) 3702 #define MAXPRNGAL 30 3703 #define NSATGAL (MAXPRNGAL-MINPRNGAL+1) 3712 #define MINPRNQZS 193 3713 #define MAXPRNQZS 199 3714 #define MINPRNQZS_S 183 3715 #define MAXPRNQZS_S 189 3716 #define NSATQZS (MAXPRNQZS-MINPRNQZS+1) 3721 #define MINPRNQZS_S 0 3722 #define MAXPRNQZS_S 0 3728 #define MAXPRNCMP 35 3729 #define NSATCMP (MAXPRNCMP-MINPRNCMP+1) 3740 #define NSATIRN (MAXPRNIRN-MINPRNIRN+1) 3750 #define MAXPRNLEO 10 3751 #define NSATLEO (MAXPRNLEO-MINPRNLEO+1) 3759 #define NSYS (NSYSGPS+NSYSGLO+NSYSGAL+NSYSQZS+NSYSCMP+NSYSIRN+NSYSLEO) 3762 #define MINPRNSBS 120 3763 #define MAXPRNSBS 142 3764 #define NSATSBS (MAXPRNSBS-MINPRNSBS+1) 3780 int satNo(
int sys,
int prn);
3796 #endif // DATA_SETS_H
void flipFloat(uint8_t *ptr)
unsigned int timeOfWeekMs
struct PACKED can_config_t
uint8_t base_position_update
float baseToRoverVector[3]
void flipStrings(uint8_t *data, int dataLength, int offset, uint16_t *offsets, uint16_t offsetsLength)
struct PACKED rtk_residual_t
int32_t i[DEBUG_I_ARRAY_SIZE]
uint32_t lastLlaTimeOfWeekMs
struct PACKED debug_array_t
uint32_t correctionChecksumFailures
#define DEBUG_LF_ARRAY_SIZE
f_t f[DEBUG_F_ARRAY_SIZE]
double lf[DEBUG_LF_ARRAY_SIZE]
uint32_t baseGpsEphemerisCount
int satNo(int sys, int prn)
float lastLlaUpdateDistance
#define DEVINFO_MANUFACTURER_STRLEN
uint32_t can_period_mult[NUM_CIDS]
struct PACKED inl2_status_t
float baseToRoverHeadingAcc
#define DEVINFO_ADDINFO_STRLEN
uint8_t lack_of_valid_sats
uint32_t loggerElapsedTimeMs
obsd_t obs[MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE]
#define SET_STATUS_OFFSET_MASK(result, val, offset, mask)
uint32_t baseGpsObservationCount
#define MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE
#define GPS_RAW_MESSAGE_BUF_SIZE
struct PACKED wheel_encoder_t
struct PACKED sys_params_t
struct PACKED inl2_ned_sigma_t
rtos_task_t task[UINS_RTOS_NUM_TASKS]
struct PACKED rtos_info_t
struct PACKED sys_sensors_adc_t
uint32_t h4xRadioBaudRate
double max_baseline_error
int satNumCalc(int gnssID, int svID)
uint8_t divergent_pnt_pos_iteration
#define WIFI_SSID_PSK_SIZE
struct PACKED ascii_msgs_t
#define HDW_BIT_MODE(hdwBitStatus)
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)
struct PACKED gps_rtk_misc_t
gps_rtk_misc_t gpsRtkMisc
#define DEBUG_I_ARRAY_SIZE
float encoderTickToWheelRad
struct PACKED strobe_in_time_t
int gpsToNmeaGGA(const gps_pos_t *gps, char *buffer, int bufferLength)
uint32_t timeToFirstFixMs
wheel_encoder_t wheelEncoder
float baseToRoverDistance
uint32_t roverGlonassObservationCount
struct PACKED inl2_mag_obs_info_t
uint32_t roverGpsObservationCount
uint32_t roverBeidouEphemerisCount
struct PACKED gen_1axis_sensor_t
wheel_config_t wheelConfig
double gpsToUnix(uint32_t gpsWeek, uint32_t gpsTimeofWeekMS, uint8_t leapSeconds)
uint8_t waiting_for_base_packet
uint32_t serialNumChecksum32(const void *data, int size)
uint32_t baseQzsObservationCount
struct PACKED inl2_states_t
uint32_t baseAntennaCount
uint8_t bad_baseline_holdamb
PUSH_PACK_1 struct PACKED pos_measurement_t
struct PACKED manufacturing_info_t
pos_measurement_t posMeasurement
uint8_t waiting_for_rover_packet
uint8_t raw_ptr_queue_overrun
struct PACKED gps_version_t
uint32_t roverGpsEphemerisCount
struct PACKED preintegrated_imu_t
struct PACKED wheel_config_t
uint8_t buf[GPS_RAW_MESSAGE_BUF_SIZE]
char addInfo[DEVINFO_ADDINFO_STRLEN]
uint32_t roverGlonassEphemerisCount
void flipDoubles(uint8_t *data, int dataLength, int offset, uint16_t *offsets, uint16_t offsetsLength)
uint16_t * getDoubleOffsets(eDataIDs dataId, uint16_t *offsetsLength)
double flipDoubleCopy(double val)
struct PACKED ins_output_t
f_t ana[NUM_ANA_CHANNELS]
char manufacturer[DEVINFO_MANUFACTURER_STRLEN]
uint8_t rescode_err_marker
struct PACKED barometer_t
#define INS_STATUS_SOLUTION(insStatus)
uint8_t code_large_residual
float gpsMinimumElevation
uint32_t baseGalileoEphemerisCount
uint8_t obs_pairs_filtered
struct PACKED gps_rtk_rel_t
struct PACKED gen_3axis_sensord_t
uint32_t roverGalileoEphemerisCount
sensors_mpu_w_temp_t mpu[NUM_IMU_DEVICES]
struct PACKED nvm_flash_cfg_t
#define MAX_TASK_NAME_LEN
ROSCPP_DECL bool del(const std::string &key)
uint8_t rover_position_error
#define MAX_NUM_SAT_CHANNELS
uint32_t baseGalileoObservationCount
uint8_t base_position_error
struct PACKED sys_sensors_t
uint32_t baseGlonassEphemerisCount
struct PACKED sensors_mpu_w_temp_t
uint32_t gpsTimeSyncPeriodMs
struct PACKED debug_string_t
uint32_t baseQzsEphemerisCount
double reset_baseline_error
uint8_t invalid_base_position
union PACKED uInsOutDatasets
struct PACKED gen_dual_3axis_sensor_t
uint8_t raw_dat_queue_overrun
gps_sat_sv_t sat[MAX_NUM_SAT_CHANNELS]
uint16_t * getStringOffsetsLengths(eDataIDs dataId, uint16_t *offsetsLength)
struct PACKED magnetometer_t
struct PACKED system_command_t
uint64_t didToRmcBit(uint32_t dataId, uint64_t defaultRmcBits)
void flipEndianess32(uint8_t *data, int dataLength)
uint32_t flashChecksum32(const void *data, int size)
struct PACKED rtos_task_t
inl2_ned_sigma_t inl2NedSigma
uint32_t roverGalileoObservationCount
uint32_t can_transmit_address[NUM_CIDS]
uint32_t baseBeidouObservationCount
uint32_t roverBeidouObservationCount
uint32_t roverQzsEphemerisCount
uint32_t can_receive_address
POP_PACK uint32_t checksum32(const void *data, int count)
#define DEBUG_STRING_SIZE
sys_sensors_adc_t sensorsAdc
uint32_t baseBeidouEphemerisCount
struct PACKED rtk_debug_t
uint8_t moveb_time_sync_error
struct PACKED gen_3axis_sensor_t
uint8_t s[DEBUG_STRING_SIZE]
float flipFloatCopy(float val)
uint32_t can_baudrate_kbps
double gpsToJulian(int32_t gpsWeek, int32_t gpsMilliseconds, int32_t leapSeconds)
uint8_t phase_large_residual
char name[MAX_TASK_NAME_LEN]
struct PACKED rtk_state_t
uint32_t can_receive_address
uint32_t roverQzsObservationCount
struct PACKED gps_sat_sv_t
uint32_t baseGlonassObservationCount
#define DEBUG_F_ARRAY_SIZE
struct PACKED evb_rtos_info_t
void flipDouble(void *ptr)