Classes | Macros | Typedefs | Enumerations | Functions
data_sets.h File Reference
#include <stdint.h>
#include <stdlib.h>
#include <time.h>
#include <string.h>
#include "ISConstants.h"
Include dependency graph for data_sets.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  alm_t
 
struct  diag_msg_t
 
struct  eph_t
 
struct  evb_flash_cfg_t
 
struct  evb_server_t
 
struct  evb_status_t
 
struct  evb_wifi_t
 
struct  geph_t
 
struct  gtime_t
 
struct  internal_diagnostic_t
 
struct  ion_model_utc_alm_t
 
struct  obs_t
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
union  PACKED
 
struct  port_monitor_set_t
 
struct  port_monitor_t
 
struct  prcopt_t
 
struct  sbsmsg_t
 
struct  sta_t
 
struct  survey_in_t
 
struct  system_fault_t
 

Macros

#define BE_SWAP16(_i)   (_i)
 
#define BE_SWAP32(_i)   (_i)
 
#define BE_SWAP32F(_i)   (_i)
 
#define BE_SWAP64F(_i)   (_i)
 
#define CAL_BIT_MODE(calBitStatus)   ((calBitStatus&CAL_BIT_MODE_MASK)>>CAL_BIT_MODE_OFFSET)
 
#define DEBUG_F_ARRAY_SIZE   9
 
#define DEBUG_I_ARRAY_SIZE   9
 
#define DEBUG_LF_ARRAY_SIZE   3
 
#define DEBUG_STRING_SIZE   80
 
#define DEVINFO_ADDINFO_STRLEN   24
 
#define DEVINFO_MANUFACTURER_STRLEN   24
 
#define DID_ASCII_BCAST_PERIOD   (eDataIDs)8 /** (ascii_msgs_t) Broadcast period for ASCII messages */
 
#define DID_BAROMETER   (eDataIDs)53 /** (barometer_t) Barometric pressure sensor data */
 
#define DID_BIT   (eDataIDs)64 /** (bit_t) System built-in self-test */
 
#define DID_CAL_SC   (eDataIDs)42 /** INTERNAL USE ONLY (sensor_cal_mem_t) */
 
#define DID_CAL_SC1   (eDataIDs)43 /** INTERNAL USE ONLY (sensor_cal_mpu_t) */
 
#define DID_CAL_SC2   (eDataIDs)44 /** INTERNAL USE ONLY (sensor_cal_mpu_t) */
 
#define DID_CAL_SC_INFO   (eDataIDs)74 /** INTERNAL USE ONLY (sensor_cal_info_t) */
 
#define DID_CAN_CONFIG   (eDataIDs)90 /** (can_config_t) Addresses for CAN messages*/
 
#define DID_COMMUNICATIONS_LOOPBACK   (eDataIDs)56 /** INTERNAL USE ONLY - Unit test for communications manager */
 
#define DID_COUNT   (eDataIDs)96
 
#define DID_DEBUG_ARRAY   (eDataIDs)39 /** INTERNAL USE ONLY (debug_array_t) */
 
#define DID_DEBUG_STRING   (eDataIDs)37 /** INTERNAL USE ONLY (debug_string_t) */
 
#define DID_DEV_INFO   (eDataIDs)1 /** (dev_info_t) Device information */
 
#define DID_DIAGNOSTIC_MESSAGE   (eDataIDs)72 /** (diag_msg_t) Diagnostic message */
 
#define DID_DUAL_IMU   (eDataIDs)58 /** (dual_imu_t) Dual inertial measurement unit data down-sampled from 1KHz to navigation update rate (DID_FLASH_CONFIG.startupNavDtMs) as an anti-aliasing filter to reduce noise and preserve accuracy. Minimum data period is DID_FLASH_CONFIG.startupNavDtMs (1KHz max). */
 
#define DID_DUAL_IMU_MAG   (eDataIDs)85 /** (imu_mag_t) DID_DUAL_IMU + DID_MAGNETOMETER + MAGNETOMETER_2 Only one of DID_DUAL_IMU_RAW_MAG, DID_DUAL_IMU_MAG, or DID_PREINTEGRATED_IMU_MAG should be streamed simultaneously. */
 
#define DID_DUAL_IMU_RAW   (eDataIDs)57 /** (dual_imu_t) Dual inertial measurement unit data directly from IMU. We recommend use of DID_DUAL_IMU or DID_PREINTEGRATED_IMU. Minimum data period is DID_FLASH_CONFIG.startupImuDtMs or 4, whichever is larger (250Hz max). */
 
#define DID_DUAL_IMU_RAW_MAG   (eDataIDs)84 /** (imu_mag_t) DID_DUAL_IMU_RAW + DID_MAGNETOMETER + MAGNETOMETER_2 Only one of DID_DUAL_IMU_RAW_MAG, DID_DUAL_IMU_MAG, or DID_PREINTEGRATED_IMU_MAG should be streamed simultaneously. */
 
#define DID_EVB_DEBUG_ARRAY   (eDataIDs)82 /** INTERNAL USE ONLY (debug_array_t) */
 
#define DID_EVB_DEV_INFO   (eDataIDs)93 /** (dev_info_t) EVB device information */
 
#define DID_EVB_FLASH_CFG   (eDataIDs)81 /** (evb_flash_cfg_t) EVB configuration. */
 
#define DID_EVB_RTOS_INFO   (eDataIDs)83 /** (evb_rtos_info_t) EVB-2 RTOS information. */
 
#define DID_EVB_STATUS   (eDataIDs)80 /** (evb_status_t) EVB monitor and log control interface. */
 
#define DID_FEATURE_BITS   (eDataIDs)23 /** INTERNAL USE ONLY (feature_bits_t) */
 
#define DID_FLASH_CONFIG   (eDataIDs)12 /** (nvm_flash_cfg_t) Flash memory configuration */
 
#define DID_GPS1_POS   (eDataIDs)13 /** (gps_pos_t) GPS 1 position data. This comes from DID_GPS1_UBX_POS or DID_GPS1_RTK_POS, depending on whichever is more accurate. */
 
#define DID_GPS1_RAW   (eDataIDs)69 /** (gps_raw_t) GPS raw data for rover (observation, ephemeris, etc.) - requires little endian CPU. The contents of data can vary for this message and are determined by dataType field. RTK positioning or RTK compassing must be enabled to stream this message. */
 
#define DID_GPS1_RTK_POS   (eDataIDs)54 /** (gps_pos_t) GPS RTK position data */
 
#define DID_GPS1_RTK_POS_MISC   (eDataIDs)22 /** (gps_rtk_misc_t) RTK precision position related data. */
 
#define DID_GPS1_RTK_POS_REL   (eDataIDs)21 /** (gps_rtk_rel_t) RTK precision position base to rover relative info. */
 
#define DID_GPS1_SAT   (eDataIDs)15 /** (gps_sat_t) GPS 1 GNSS and sat identifiers, carrier to noise ratio (signal strength), elevation and azimuth angles, pseudo range residual. */
 
#define DID_GPS1_UBX_POS   (eDataIDs)6 /** (gps_pos_t) GPS 1 position data from ublox receiver. */
 
#define DID_GPS1_VEL   (eDataIDs)30 /** (gps_vel_t) GPS 1 velocity data */
 
#define DID_GPS1_VERSION   (eDataIDs)17 /** (gps_version_t) GPS 1 version info */
 
#define DID_GPS2_POS   (eDataIDs)14 /** (gps_pos_t) GPS 2 position data */
 
#define DID_GPS2_RAW   (eDataIDs)70 /** (gps_raw_t) GPS raw data for rover (observation, ephemeris, etc.) - requires little endian CPU. The contents of data can vary for this message and are determined by dataType field. RTK positioning or RTK compassing must be enabled to stream this message. */
 
#define DID_GPS2_RTK_CMP_MISC   (eDataIDs)92 /** (gps_rtk_misc_t) RTK Dual GNSS RTK compassing related data. */
 
#define DID_GPS2_RTK_CMP_REL   (eDataIDs)91 /** (gps_rtk_rel_t) Dual GNSS RTK compassing / moving base to rover (GPS 1 to GPS 2) relative info. */
 
#define DID_GPS2_SAT   (eDataIDs)16 /** (gps_sat_t) GPS 2 GNSS and sat identifiers, carrier to noise ratio (signal strength), elevation and azimuth angles, pseudo range residual. */
 
#define DID_GPS2_VEL   (eDataIDs)31 /** (gps_vel_t) GPS 2 velocity data */
 
#define DID_GPS2_VERSION   (eDataIDs)18 /** (gps_version_t) GPS 2 version info */
 
#define DID_GPS_BASE_RAW   (eDataIDs)60 /** (gps_raw_t) GPS raw data for base station (observation, ephemeris, etc.) - requires little endian CPU. The contents of data can vary for this message and are determined by dataType field. RTK positioning or RTK compassing must be enabled to stream this message. */
 
#define DID_GPS_RTK_OPT   (eDataIDs)61 /** (gps_rtk_opt_t) RTK options - requires little endian CPU. */
 
#define DID_HDW_PARAMS   (eDataIDs)32 /** INTERNAL USE ONLY (hdw_params_t) */
 
#define DID_INL2_COVARIANCE_LD   (eDataIDs)49 /** (INL2_COVARIANCE_LD_ARRAY_SIZE) */
 
#define DID_INL2_MAG_OBS_INFO   (eDataIDs)59 /** (inl2_mag_obs_info_t) INL2 magnetometer calibration information. */
 
#define DID_INL2_MISC   (eDataIDs)51 /** (inl2_misc_t) */
 
#define DID_INL2_NED_SIGMA   (eDataIDs)67 /** (inl2_ned_sigma_t) INL2 standard deviation in the NED frame */
 
#define DID_INL2_STATES   (eDataIDs)48 /** (inl2_states_t) */
 
#define DID_INL2_STATUS   (eDataIDs)50 /** (inl2_status_t) */
 
#define DID_INS_1   (eDataIDs)4 /** (ins_1_t) INS output: euler rotation w/ respect to NED, NED position from reference LLA. */
 
#define DID_INS_2   (eDataIDs)5 /** (ins_2_t) INS output: quaternion rotation w/ respect to NED, ellipsoid altitude */
 
#define DID_INS_3   (eDataIDs)65 /** (ins_3_t) Inertial navigation data with quaternion NED to body rotation and ECEF position. */
 
#define DID_INS_4   (eDataIDs)66 /** (ins_4_t) INS output: quaternion rotation w/ respect to ECEF, ECEF position. */
 
#define DID_INS_DEV_1   (eDataIDs)47 /** INTERNAL USE ONLY (ins_dev_1_t) */
 
#define DID_INTERNAL_DIAGNOSTIC   (eDataIDs)20 /** INTERNAL USE ONLY (internal_diagnostic_t) Internal diagnostic info */
 
#define DID_IO   (eDataIDs)27 /** (io_t) I/O */
 
#define DID_MAG_CAL   (eDataIDs)19 /** (mag_cal_t) Magnetometer calibration */
 
#define DID_MAGNETOMETER_1   (eDataIDs)52 /** (magnetometer_t) Magnetometer sensor 1 output */
 
#define DID_MAGNETOMETER_2   (eDataIDs)55 /** (magnetometer_t) 2nd magnetometer sensor data */
 
#define DID_MANUFACTURING_INFO   (eDataIDs)63 /** INTERNAL USE ONLY (manufacturing_info_t) Manufacturing info */
 
#define DID_MAX_COUNT   256
 
#define DID_NULL   (eDataIDs)0 /** NULL (INVALID) */
 
#define DID_NVR_MANAGE_USERPAGE   (eDataIDs)33 /** INTERNAL USE ONLY (nvr_manage_t) */
 
#define DID_NVR_USERPAGE_G0   (eDataIDs)35 /** INTERNAL USE ONLY (nvm_group_0_t) */
 
#define DID_NVR_USERPAGE_G1   (eDataIDs)36 /** INTERNAL USE ONLY (nvm_group_1_t) */
 
#define DID_NVR_USERPAGE_INTERNAL   (eDataIDs)62 /** (internal) Internal user page data */
 
#define DID_NVR_USERPAGE_SN   (eDataIDs)34 /** INTERNAL USE ONLY (nvm_group_sn_t) */
 
#define DID_PORT_MONITOR   (eDataIDs)75 /** (port_monitor_t) Data rate and status monitoring for each communications port. */
 
#define DID_POSITION_MEASUREMENT   (eDataIDs)88 /** (pos_measurement_t) External position estimate*/
 
#define DID_PREINTEGRATED_IMU   (eDataIDs)3 /** (preintegrated_imu_t) Coning and sculling integral in body/IMU frame. Updated at IMU rate. Also know as Delta Theta Delta Velocity, or Integrated IMU. For clarification, we use the name "Preintegrated IMU" through the User Manual. This data is integrated from the IMU data at the IMU update rate (startupImuDtMs, default 1ms). The integration period (dt) and output data rate are the same as the NAV rate (startupNavDtMs, default 4ms) and cannot be output at any other rate. If a different output data rate is desired, DID_DUAL_IMU which is derived from DID_PREINTEGRATED_IMU can be used instead. Preintegrated IMU data acts as a form of compression, adding the benefit of higher integration rates for slower output data rates, preserving the IMU data without adding filter delay and addresses antialiasing. It is most effective for systems that have higher dynamics and lower communications data rates. The minimum data period is DID_FLASH_CONFIG.startupImuDtMs or 4, whichever is larger (250Hz max). */
 
#define DID_PREINTEGRATED_IMU_MAG   (eDataIDs)86 /** (pimu_mag_t) DID_PREINTEGRATED_IMU + DID_MAGNETOMETER + MAGNETOMETER_2 Only one of DID_DUAL_IMU_RAW_MAG, DID_DUAL_IMU_MAG, or DID_PREINTEGRATED_IMU_MAG should be streamed simultaneously. */
 
#define DID_RMC   (eDataIDs)9 /** (rmc_t) Realtime Message Controller (RMC). The data sets available through RMC are driven by the availability of the data. The RMC provides updates from various data sources (i.e. sensors) as soon as possible with minimal latency. Several of the data sources (sensors) output data at different data rates that do not all correspond. The RMC is provided so that broadcast of sensor data is done as soon as it becomes available. All RMC messages can be enabled using the standard Get Data packet format. */
 
#define DID_RTK_CODE_RESIDUAL   (eDataIDs)78 /** INTERNAL USE ONLY (rtk_residual_t) */
 
#define DID_RTK_DEBUG   (eDataIDs)79 /** INTERNAL USE ONLY (rtk_debug_t) */
 
#define DID_RTK_DEBUG_2   (eDataIDs)89 /** INTERNAL USE ONLY (rtk_debug_2_t) */
 
#define DID_RTK_PHASE_RESIDUAL   (eDataIDs)77 /** INTERNAL USE ONLY (rtk_residual_t) */
 
#define DID_RTK_STATE   (eDataIDs)76 /** INTERNAL USE ONLY (rtk_state_t) */
 
#define DID_RTOS_INFO   (eDataIDs)38 /** (rtos_info_t) RTOS information. */
 
#define DID_SCOMP   (eDataIDs)29 /** INTERNAL USE ONLY (sensor_compensation_t) */
 
#define DID_SENSORS_ADC   (eDataIDs)28 /** INTERNAL USE ONLY (sys_sensors_adc_t) */
 
#define DID_SENSORS_ADC_SIGMA   (eDataIDs)46 /** INTERNAL USE ONLY (sys_sensors_adc_t) */
 
#define DID_SENSORS_CAL1   (eDataIDs)40 /** INTERNAL USE ONLY (sensors_mpu_w_temp_t) */
 
#define DID_SENSORS_CAL2   (eDataIDs)41 /** INTERNAL USE ONLY (sensors_mpu_w_temp_t) */
 
#define DID_SENSORS_IS1   (eDataIDs)24 /** INTERNAL USE ONLY (sensors_w_temp_t) Cross-axis aligned w/ scale factor */
 
#define DID_SENSORS_IS2   (eDataIDs)25 /** INTERNAL USE ONLY (sensors_w_temp_t) Temperature compensated */
 
#define DID_SENSORS_TC_BIAS   (eDataIDs)26 /** INTERNAL USE ONLY (sensors_t) */
 
#define DID_STROBE_IN_TIME   (eDataIDs)68 /** (strobe_in_time_t) Timestamp for input strobe. */
 
#define DID_SURVEY_IN   (eDataIDs)73 /** (survey_in_t) Survey in, used to determine position for RTK base station. Base correction output cannot run during a survey and will be automatically disabled if a survey is started. */
 
#define DID_SYS_CMD   (eDataIDs)7 /** (system_command_t) System commands. Both the command and invCommand fields must be set at the same time for a command to take effect. */
 
#define DID_SYS_FAULT   (eDataIDs)2 /** (system_fault_t) System fault information */
 
#define DID_SYS_PARAMS   (eDataIDs)10 /** (sys_params_t) System parameters / info */
 
#define DID_SYS_SENSORS   (eDataIDs)11 /** (sys_sensors_t) System sensor information */
 
#define DID_SYS_SENSORS_SIGMA   (eDataIDs)45 /** INTERNAL USE ONLY (sys_sensors_t) */
 
#define DID_WHEEL_CONFIG   (eDataIDs)87 /** (wheel_config_t) [NOT SUPPORTED, INTERNAL USE ONLY] Static configuration for wheel encoder measurements. */
 
#define DID_WHEEL_ENCODER   (eDataIDs)71 /** (wheel_encoder_t) [NOT SUPPORTED, INTERNAL USE ONLY] Wheel encoder data to be fused with GPS-INS measurements, set DID_WHEEL_CONFIG for configuration before sending this message */
 
#define ENAGAL
 
#define ENAGLO
 
#define ENASBS
 
#define EVB2_CB_PRESET_DEFAULT   EVB2_CB_PRESET_RS232
 
#define EVB_CFG_BITS_IDX_SERVER(bits)   ((bits&EVB_CFG_BITS_SERVER_SELECT_MASK)>>EVB_CFG_BITS_SERVER_SELECT_OFFSET)
 
#define EVB_CFG_BITS_IDX_WIFI(bits)   ((bits&EVB_CFG_BITS_WIFI_SELECT_MASK)>>EVB_CFG_BITS_WIFI_SELECT_OFFSET)
 
#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);}
 
#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);}
 
#define GPS_RAW_MESSAGE_BUF_SIZE   1000
 
#define GPS_TO_UNIX_OFFSET   315964800
 
#define HALF_MAXOBS   (MAXOBS/2)
 
#define HDW_BIT_MODE(hdwBitStatus)   ((hdwBitStatus&HDW_BIT_MODE_MASK)>>HDW_BIT_MODE_OFFSET)
 
#define HDW_STATUS_COM_PARSE_ERROR_COUNT(hdwStatus)   ((hdwStatus&HDW_STATUS_COM_PARSE_ERR_COUNT_MASK)>>HDW_STATUS_COM_PARSE_ERR_COUNT_OFFSET)
 
#define INS_STATUS_NAV_FIX_STATUS(insStatus)   ((insStatus&INS_STATUS_GPS_NAV_FIX_MASK)>>INS_STATUS_GPS_NAV_FIX_OFFSET)
 
#define INS_STATUS_SOLUTION(insStatus)   ((insStatus&INS_STATUS_SOLUTION_MASK)>>INS_STATUS_SOLUTION_OFFSET)
 
#define IO_CFG_GPS_TIMEPUSE_SOURCE(ioConfig)   ((ioConfig>>IO_CFG_GPS_TIMEPUSE_SOURCE_OFFSET)&IO_CFG_GPS_TIMEPUSE_SOURCE_MASK)
 
#define IO_CONFIG_GPS1_SOURCE(ioConfig)   ((ioConfig>>IO_CONFIG_GPS1_SOURCE_OFFSET)&IO_CONFIG_GPS_SOURCE_MASK)
 
#define IO_CONFIG_GPS1_TYPE(ioConfig)   ((ioConfig>>IO_CONFIG_GPS1_TYPE_OFFSET)&IO_CONFIG_GPS_TYPE_MASK)
 
#define IO_CONFIG_GPS2_SOURCE(ioConfig)   ((ioConfig>>IO_CONFIG_GPS2_SOURCE_OFFSET)&IO_CONFIG_GPS_SOURCE_MASK)
 
#define IO_CONFIG_GPS2_TYPE(ioConfig)   ((ioConfig>>IO_CONFIG_GPS2_TYPE_OFFSET)&IO_CONFIG_GPS_TYPE_MASK)
 
#define LE_SWAP16(_i)   (SWAP16(_i))
 
#define LE_SWAP32(_i)   (SWAP32(_i))
 
#define LE_SWAP32F(_i)   flipFloatCopy(_i)
 
#define LE_SWAP64F(_i)   flipDoubleCopy(_i)
 
#define MAX_NUM_SAT_CHANNELS   50
 
#define MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE   (GPS_RAW_MESSAGE_BUF_SIZE / sizeof(obsd_t))
 
#define MAX_TASK_NAME_LEN   12
 
#define MAXERRMSG   0
 
#define MAXOBS   56
 
#define MAXPRNCMP   0
 
#define MAXPRNGAL   30 /* max satellite PRN number of Galileo */
 
#define MAXPRNGLO   27 /* max satellite slot number of GLONASS */
 
#define MAXPRNGPS   32 /* max satellite PRN number of GPS */
 
#define MAXPRNIRN   0
 
#define MAXPRNLEO   0
 
#define MAXPRNQZS   0
 
#define MAXPRNQZS_S   0
 
#define MAXPRNSBS   138 /* max satellite PRN number of SBAS */
 
#define MAXRAWLEN   2048
 
#define MAXSUBFRMLEN   152
 
#define MINPRNCMP   0
 
#define MINPRNGAL   1 /* min satellite PRN number of Galileo */
 
#define MINPRNGLO   1 /* min satellite slot number of GLONASS */
 
#define MINPRNGPS   1 /* min satellite PRN number of GPS */
 
#define MINPRNIRN   0
 
#define MINPRNLEO   0
 
#define MINPRNQZS   0
 
#define MINPRNQZS_S   0
 
#define MINPRNSBS   133 /* min satellite PRN number of SBAS */
 
#define NEXOBS   0
 
#define NFREQ   1
 
#define NFREQGAL   1
 
#define NFREQGLO   1
 
#define NSATCMP   0
 
#define NSATGAL   (MAXPRNGAL-MINPRNGAL+1) /* number of Galileo satellites */
 
#define NSATGLO   (MAXPRNGLO-MINPRNGLO+1) /* number of GLONASS satellites */
 
#define NSATGPS   (MAXPRNGPS-MINPRNGPS+1) /* number of GPS satellites */
 
#define NSATIRN   0
 
#define NSATLEO   0
 
#define NSATQZS   0
 
#define NSATSBS   (MAXPRNSBS - MINPRNSBS + 1) /* number of SBAS satellites */
 
#define NSYS   (NSYSGPS+NSYSGLO+NSYSGAL+NSYSQZS+NSYSCMP+NSYSIRN+NSYSLEO) /* number of systems */
 
#define NSYSCMP   0
 
#define NSYSGAL   1
 
#define NSYSGLO   1
 
#define NSYSGPS   1
 
#define NSYSIRN   0
 
#define NSYSLEO   0
 
#define NSYSQZS   0
 
#define NUM_ANA_CHANNELS   4
 
#define NUM_COM_PORTS   4
 
#define NUM_IMU_DEVICES   2
 
#define NUM_SERIAL_PORTS   6
 
#define NUM_WIFI_PRESETS   3
 
#define NUMSATSOL   22
 
#define PROTOCOL_VERSION_CHAR2   (0x000000FF&DID_COUNT)
 
#define PROTOCOL_VERSION_CHAR3   8
 
#define RECEIVER_INDEX_EXTERNAL_BASE   2
 
#define RECEIVER_INDEX_GPS1   1
 
#define RECEIVER_INDEX_GPS2   3
 
#define RMC_BITS_BAROMETER   0x0000000000000040
 
#define RMC_BITS_DIAGNOSTIC_MESSAGE   0x0000000000040000
 
#define RMC_BITS_DUAL_IMU   0x0000000000000010
 
#define RMC_BITS_DUAL_IMU_MAG   0x0000000400000000
 
#define RMC_BITS_DUAL_IMU_MAG_RAW   0x0000000200000000
 
#define RMC_BITS_DUAL_IMU_RAW   0x0000000000080000
 
#define RMC_BITS_GPS1_POS   0x0000000000000400
 
#define RMC_BITS_GPS1_RAW   0x0000000000001000
 
#define RMC_BITS_GPS1_RTK_HDG_MISC   0x0000002000000000
 
#define RMC_BITS_GPS1_RTK_HDG_REL   0x0000001000000000
 
#define RMC_BITS_GPS1_RTK_POS   0x0000000000800000
 
#define RMC_BITS_GPS1_RTK_POS_MISC   0x0000000004000000
 
#define RMC_BITS_GPS1_RTK_POS_REL   0x0000000001000000
 
#define RMC_BITS_GPS1_SAT   0x0000000000004000
 
#define RMC_BITS_GPS1_UBX_POS   0x0000000000400000
 
#define RMC_BITS_GPS1_VEL   0x0000000000100000
 
#define RMC_BITS_GPS2_POS   0x0000000000000800
 
#define RMC_BITS_GPS2_RAW   0x0000000000002000
 
#define RMC_BITS_GPS2_SAT   0x0000000000008000
 
#define RMC_BITS_GPS2_VEL   0x0000000000200000
 
#define RMC_BITS_GPS_BASE_RAW   0x0000000000010000
 
#define RMC_BITS_INL2_NED_SIGMA   0x0000000008000000
 
#define RMC_BITS_INS1   0x0000000000000001
 
#define RMC_BITS_INS2   0x0000000000000002
 
#define RMC_BITS_INS3   0x0000000000000004
 
#define RMC_BITS_INS4   0x0000000000000008
 
#define RMC_BITS_INTERNAL_PPD   0x4000000000000000
 
#define RMC_BITS_MAGNETOMETER1   0x0000000000000080
 
#define RMC_BITS_MAGNETOMETER2   0x0000000000000100
 
#define RMC_BITS_MASK   0x0FFFFFFFFFFFFFFF
 
#define RMC_BITS_PREINTEGRATED_IMU   0x0000000000000020
 
#define RMC_BITS_PREINTEGRATED_IMU_MAG   0x0000000800000000
 
#define RMC_BITS_PRESET   0x8000000000000000
 
#define RMC_BITS_RTK_CODE_RESIDUAL   0x0000000020000000
 
#define RMC_BITS_RTK_PHASE_RESIDUAL   0x0000000040000000
 
#define RMC_BITS_RTK_STATE   0x0000000010000000
 
#define RMC_BITS_STROBE_IN_TIME   0x0000000000020000
 
#define RMC_BITS_WHEEL_CONFIG   0x0000000100000000
 
#define RMC_BITS_WHEEL_ENCODER   0x0000000080000000
 
#define RMC_OPTIONS_PERSISTENT   0x00000200
 
#define RMC_OPTIONS_PORT_ALL   (RMC_OPTIONS_PORT_MASK)
 
#define RMC_OPTIONS_PORT_CURRENT   0x00000000
 
#define RMC_OPTIONS_PORT_MASK   0x000000FF
 
#define RMC_OPTIONS_PORT_SER0   0x00000001
 
#define RMC_OPTIONS_PORT_SER1   0x00000002
 
#define RMC_OPTIONS_PORT_SER2   0x00000004
 
#define RMC_OPTIONS_PORT_USB   0x00000008
 
#define RMC_OPTIONS_PRESERVE_CTRL   0x00000100
 
#define RMC_PRESET_INS_BITS
 
#define RMC_PRESET_INS_NAV_PERIOD_MULT   1
 
#define RMC_PRESET_PPD_BITS
 
#define RMC_PRESET_PPD_BITS_NO_IMU
 
#define RMC_PRESET_PPD_BITS_RAW_IMU
 
#define RMC_PRESET_PPD_BITS_RTK_DBG
 
#define RMC_PRESET_PPD_NAV_PERIOD_MULT   25
 
#define RMC_PRESET_PPD_ROBOT
 
#define SBAS_EPHEMERIS_ARRAY_SIZE   NSATSBS
 
#define SECONDS_PER_DAY   86400
 
#define SECONDS_PER_WEEK   604800
 
#define SET_STATUS_OFFSET_MASK(result, val, offset, mask)   { (result) &= ~((mask)<<(offset)); (result) |= ((val)<<(offset)); }
 
#define SYS_ALL   0xFF /* navigation system: all */
 
#define SYS_CFG_BITS_MAG_RECAL_MODE(sysCfgBits)   ((sysCfgBits&SYS_CFG_BITS_MAG_RECAL_MODE_MASK)>>SYS_CFG_BITS_MAG_RECAL_MODE_OFFSET)
 
#define SYS_CMP   0x20 /* navigation system: BeiDou */
 
#define SYS_FAULT_STATUS_BUS_FAULT   0x00080000
 
#define SYS_FAULT_STATUS_ENABLE_BOOTLOADER   0x00000002
 
#define SYS_FAULT_STATUS_FLASH_MIGRATION_COMPLETED   0x00000040
 
#define SYS_FAULT_STATUS_FLASH_MIGRATION_EVENT   0x00000020
 
#define SYS_FAULT_STATUS_FLASH_MIGRATION_MARKER_UPDATED   0x00800000
 
#define SYS_FAULT_STATUS_HARD_FAULT   0x00010000
 
#define SYS_FAULT_STATUS_HARDWARE_DETECTION   0x08000000
 
#define SYS_FAULT_STATUS_HARDWARE_RESET   0x00000000
 
#define SYS_FAULT_STATUS_INVALID_CODE_OPERATION   0x00400000
 
#define SYS_FAULT_STATUS_MALLOC_FAILED   0x00100000
 
#define SYS_FAULT_STATUS_MASK_CRITICAL_ERROR   0xFFFF0000
 
#define SYS_FAULT_STATUS_MASK_GENERAL_ERROR   0xFFFFFFF0
 
#define SYS_FAULT_STATUS_MEM_MANGE   0x00040000
 
#define SYS_FAULT_STATUS_RTK_BUFFER_LIMIT   0x02000000
 
#define SYS_FAULT_STATUS_RTK_MISC_ERROR   0x00000080
 
#define SYS_FAULT_STATUS_SENSOR_CALIBRATION   0x04000000
 
#define SYS_FAULT_STATUS_SOFT_RESET   0x00000010
 
#define SYS_FAULT_STATUS_STACK_OVERFLOW   0x00200000
 
#define SYS_FAULT_STATUS_USAGE_FAULT   0x00020000
 
#define SYS_FAULT_STATUS_USER_RESET   0x00000001
 
#define SYS_FAULT_STATUS_WATCHDOG_RESET   0x01000000
 
#define SYS_GAL   0x08 /* navigation system: Galileo */
 
#define SYS_GLO   0x04 /* navigation system: GLONASS */
 
#define SYS_GPS   0x01 /* navigation system: GPS */
 
#define SYS_IRN   0x40 /* navigation system: IRNS */
 
#define SYS_LEO   0x80 /* navigation system: LEO */
 
#define SYS_NONE   0x00 /* navigation system: none */
 
#define SYS_QZS   0x10 /* navigation system: QZSS */
 
#define SYS_SBS   0x02 /* navigation system: SBAS */
 
#define WIFI_SSID_PSK_SIZE   40
 

Typedefs

typedef struct PACKED ascii_msgs_t
 
typedef struct PACKED ascii_msgs_u32_t
 
typedef struct PACKED barometer_t
 
typedef struct PACKED bit_t
 
typedef struct PACKED can_config_t
 
typedef struct PACKED debug_array_t
 
typedef struct PACKED debug_string_t
 
typedef struct PACKED dev_info_t
 
typedef struct PACKED dual_imu_ok_t
 
typedef struct PACKED dual_imu_t
 
typedef uint32_t eDataIDs
 
typedef struct PACKED evb_rtos_info_t
 
typedef struct PACKED gen_1axis_sensor_t
 
typedef struct PACKED gen_3axis_sensor_t
 
typedef struct PACKED gen_3axis_sensord_t
 
typedef struct PACKED gen_dual_3axis_sensor_t
 
typedef struct PACKED gps_pos_t
 
typedef struct PACKED gps_raw_t
 
typedef struct PACKED gps_rtk_misc_t
 
typedef prcopt_t gps_rtk_opt_t
 
typedef struct PACKED gps_rtk_rel_t
 
typedef struct PACKED gps_sat_sv_t
 
typedef struct PACKED gps_sat_t
 
typedef struct PACKED gps_vel_t
 
typedef struct PACKED gps_version_t
 
typedef struct PACKED imu_mag_t
 
typedef struct PACKED imu_t
 
typedef struct PACKED imus_t
 
typedef struct PACKED inl2_mag_obs_info_t
 
typedef struct PACKED inl2_ned_sigma_t
 
typedef struct PACKED inl2_states_t
 
typedef struct PACKED inl2_status_t
 
typedef struct PACKED ins_1_t
 
typedef struct PACKED ins_2_t
 
typedef struct PACKED ins_3_t
 
typedef struct PACKED ins_4_t
 
typedef struct PACKED ins_output_t
 
typedef struct PACKED io_t
 
typedef struct PACKED mag_cal_t
 
typedef struct PACKED magnetometer_t
 
typedef struct PACKED manufacturing_info_t
 
typedef struct PACKED nvm_flash_cfg_t
 
typedef struct PACKED obsd_t
 
typedef struct PACKED pimu_mag_t
 
typedef PUSH_PACK_1 struct PACKED pos_measurement_t
 
typedef struct PACKED preintegrated_imu_t
 
typedef struct PACKED rmc_t
 
typedef struct PACKED rtk_debug_t
 
typedef struct PACKED rtk_residual_t
 
typedef struct PACKED rtk_state_t
 
typedef struct PACKED rtos_info_t
 
typedef struct PACKED rtos_task_t
 
typedef struct PACKED sensors_mpu_w_temp_t
 
typedef struct PACKED strobe_in_time_t
 
typedef struct PACKED sys_params_t
 
typedef struct PACKED sys_sensors_adc_t
 
typedef struct PACKED sys_sensors_t
 
typedef struct PACKED system_command_t
 
typedef union PACKED uDatasets
 
typedef union PACKED uGpsRawData
 
typedef union PACKED uInsOutDatasets
 
typedef struct PACKED wheel_config_t
 
typedef struct PACKED wheel_encoder_t
 

Enumerations

enum  {
  CID_INS_TIME, CID_INS_STATUS, CID_INS_EULER, CID_INS_QUATN2B,
  CID_INS_QUATE2B, CID_INS_UVW, CID_INS_VE, CID_INS_LAT,
  CID_INS_LON, CID_INS_ALT, CID_INS_NORTH_EAST, CID_INS_DOWN,
  CID_INS_ECEF_X, CID_INS_ECEF_Y, CID_INS_ECEF_Z, CID_INS_MSL,
  CID_PREINT_PX, CID_PREINT_QY, CID_PREINT_RZ, CID_DUAL_PX,
  CID_DUAL_QY, CID_DUAL_RZ, CID_GPS1_POS, CID_GPS1_RTK_REL,
  CID_ROLL_ROLLRATE, NUM_CIDS
}
 
enum  eBitState {
  BIT_STATE_OFF = (int)0, BIT_STATE_DONE = (int)1, BIT_STATE_CMD_FULL_STATIONARY = (int)2, BIT_STATE_CMD_BASIC_MOVING = (int)3,
  BIT_STATE_RESERVED_1 = (int)4, BIT_STATE_RESERVED_2 = (int)5, BIT_STATE_RUNNING = (int)6, BIT_STATE_FINISH = (int)7,
  BIT_STATE_COMMAND_OFF = (int)8
}
 
enum  eCalBitStatusFlags {
  CAL_BIT_PASSED_MASK = (int)0x0000000F, CAL_BIT_PASSED_ALL = (int)0x00000001, CAL_BIT_MODE_MASK = (int)0x000000F0, CAL_BIT_MODE_OFFSET = (int)4,
  CAL_BIT_FAILED_MASK = (int)0xFFFFFF00, CAL_BIT_FAULT_TCAL_EMPTY = (int)0x00000100, CAL_BIT_FAULT_TCAL_TSPAN = (int)0x00000200, CAL_BIT_FAULT_TCAL_INCONSISTENT = (int)0x00000400,
  CAL_BIT_FAULT_TCAL_CORRUPT = (int)0x00000800, CAL_BIT_FAULT_TCAL_PQR_BIAS = (int)0x00001000, CAL_BIT_FAULT_TCAL_PQR_SLOPE = (int)0x00002000, CAL_BIT_FAULT_TCAL_PQR_LIN = (int)0x00004000,
  CAL_BIT_FAULT_TCAL_ACC_BIAS = (int)0x00008000, CAL_BIT_FAULT_TCAL_ACC_SLOPE = (int)0x00010000, CAL_BIT_FAULT_TCAL_ACC_LIN = (int)0x00020000, CAL_BIT_FAULT_CAL_SERIAL_NUM = (int)0x00040000,
  CAL_BIT_FAULT_ORTO_EMPTY = (int)0x00100000, CAL_BIT_FAULT_ORTO_INVALID = (int)0x00200000, CAL_BIT_FAULT_MOTION_PQR = (int)0x00400000, CAL_BIT_FAULT_MOTION_ACC = (int)0x00800000
}
 
enum  eEvb2ComBridgeOptions {
  EVB2_CB_OPTIONS_TRISTATE_UINS_IO = 0x00000001, EVB2_CB_OPTIONS_SP330_RS422 = 0x00000002, EVB2_CB_OPTIONS_XBEE_ENABLE = 0x00000010, EVB2_CB_OPTIONS_WIFI_ENABLE = 0x00000020,
  EVB2_CB_OPTIONS_BLE_ENABLE = 0x00000040, EVB2_CB_OPTIONS_SPI_ENABLE = 0x00000080, EVB2_CB_OPTIONS_CAN_ENABLE = 0x00000100, EVB2_CB_OPTIONS_I2C_ENABLE = 0x00000200
}
 
enum  eEvb2ComBridgePreset {
  EVB2_CB_PRESET_NA = 0, EVB2_CB_PRESET_ALL_OFF = 1, EVB2_CB_PRESET_RS232 = 2, EVB2_CB_PRESET_RS232_XBEE = 3,
  EVB2_CB_PRESET_RS422_WIFI = 4, EVB2_CB_PRESET_SPI_RS232 = 5, EVB2_CB_PRESET_USB_HUB_RS232 = 6, EVB2_CB_PRESET_USB_HUB_RS422 = 7,
  EVB2_CB_PRESET_COUNT = 8
}
 
enum  eEvb2CommPorts {
  EVB2_PORT_UINS0 = 0, EVB2_PORT_UINS1 = 1, EVB2_PORT_XBEE = 2, EVB2_PORT_XRADIO = 3,
  EVB2_PORT_BLE = 4, EVB2_PORT_SP330 = 5, EVB2_PORT_GPIO_H8 = 6, EVB2_PORT_USB = 7,
  EVB2_PORT_WIFI = 8, EVB2_PORT_CAN = 9, EVB2_PORT_COUNT
}
 
enum  eEvb2LoggerMode { EVB2_LOG_NA = 0, EVB2_LOG_CMD_START = 2, EVB2_LOG_CMD_STOP = 4, EVB2_LOG_CMD_PURGE = 1002 }
 
enum  eEvb2PortOptions { EVB2_PORT_OPTIONS_RADIO_RTK_FILTER = 0x00000001, EVB2_PORT_OPTIONS_DEFAULT = EVB2_PORT_OPTIONS_RADIO_RTK_FILTER }
 
enum  eEvbFlashCfgBits {
  EVB_CFG_BITS_WIFI_SELECT_MASK = 0x00000003, EVB_CFG_BITS_WIFI_SELECT_OFFSET = 0, EVB_CFG_BITS_SERVER_SELECT_MASK = 0x0000000C, EVB_CFG_BITS_SERVER_SELECT_OFFSET = 2,
  EVB_CFG_BITS_NO_STREAM_PPD_ON_LOG_BUTTON = 0x00000010, EVB_CFG_BITS_ENABLE_WHEEL_ENCODER = 0x00000100, EVB_CFG_BITS_ENABLE_ADC = 0x00000200
}
 
enum  eEvbRtosTask {
  EVB_TASK_COMMUNICATIONS, EVB_TASK_LOGGER, EVB_TASK_WIFI, EVB_TASK_MAINTENANCE,
  EVB_TASK_IDLE, EVB_TASK_TIMER, EVB_TASK_SPI_UINS_COM, EVB_RTOS_NUM_TASKS
}
 
enum  eEvbStatus {
  EVB_STATUS_SD_CARD_READY = 0x00000001, EVB_STATUS_SD_LOG_ENABLED = 0x00000002, EVB_STATUS_SD_ERR_CARD_FAULT = 0x00000010, EVB_STATUS_SD_ERR_CARD_FULL = 0x00000020,
  EVB_STATUS_SD_ERR_CARD_MASK = 0x000000F0, EVB_STATUS_WIFI_ENABLED = 0x00010000, EVB_STATUS_WIFI_CONNECTED = 0x00020000, EVB_STATUS_XBEE_ENABLED = 0x00100000,
  EVB_STATUS_XBEE_CONNECTED = 0x00200000, EVB_STATUS_XBEE_CONFIGURED = 0x00400000, EVB_STATUS_XBEE_CONFIG_FAILURE = 0x00800000
}
 
enum  eGenFaultCodes {
  GFC_INS_STATE_ORUN_UVW = 0x00000001, GFC_INS_STATE_ORUN_LAT = 0x00000002, GFC_INS_STATE_ORUN_ALT = 0x00000004, GFC_UNHANDLED_INTERRUPT = 0x00000010,
  GFC_INIT_SENSORS = 0x00000100, GFC_INIT_SPI = 0x00000200, GFC_CONFIG_SPI = 0x00000400, GFC_INIT_GPS1 = 0x00000800,
  GFC_INIT_GPS2 = 0x00001000, GFC_FLASH_INVALID_VALUES = 0x00002000, GFC_FLASH_CHECKSUM_FAILURE = 0x00004000, GFC_FLASH_WRITE_FAILURE = 0x00008000,
  GFC_SYS_FAULT_GENERAL = 0x00010000, GFC_SYS_FAULT_CRITICAL = 0x00020000, GFC_SENSOR_SATURATION = 0x00040000
}
 
enum  eGnssSatSigConst {
  GNSS_SAT_SIG_CONST_GPS = (uint16_t)0x0003, GNSS_SAT_SIG_CONST_QZSS = (uint16_t)0x000C, GNSS_SAT_SIG_CONST_GAL = (uint16_t)0x0030, GNSS_SAT_SIG_CONST_BDS = (uint16_t)0x00C0,
  GNSS_SAT_SIG_CONST_GLO = (uint16_t)0x0300, GNSS_SAT_SIG_CONST_SBAS = (uint16_t)0x1000, GNSS_SAT_SIG_CONST_DEFAULT
}
 
enum  eGpsNavFixStatus { GPS_NAV_FIX_NONE = (int)0x00000000, GPS_NAV_FIX_POSITIONING_3D = (int)0x00000001, GPS_NAV_FIX_POSITIONING_RTK_FLOAT = (int)0x00000002, GPS_NAV_FIX_POSITIONING_RTK_FIX = (int)0x00000003 }
 
enum  eGpsStatus {
  GPS_STATUS_NUM_SATS_USED_MASK = (int)0x000000FF, GPS_STATUS_FIX_NONE = (int)0x00000000, GPS_STATUS_FIX_DEAD_RECKONING_ONLY = (int)0x00000100, GPS_STATUS_FIX_2D = (int)0x00000200,
  GPS_STATUS_FIX_3D = (int)0x00000300, GPS_STATUS_FIX_GPS_PLUS_DEAD_RECK = (int)0x00000400, GPS_STATUS_FIX_TIME_ONLY = (int)0x00000500, GPS_STATUS_FIX_UNUSED1 = (int)0x00000600,
  GPS_STATUS_FIX_UNUSED2 = (int)0x00000700, GPS_STATUS_FIX_DGPS = (int)0x00000800, GPS_STATUS_FIX_SBAS = (int)0x00000900, GPS_STATUS_FIX_RTK_SINGLE = (int)0x00000A00,
  GPS_STATUS_FIX_RTK_FLOAT = (int)0x00000B00, GPS_STATUS_FIX_RTK_FIX = (int)0x00000C00, GPS_STATUS_FIX_MASK = (int)0x00001F00, GPS_STATUS_FIX_BIT_OFFSET = (int)8,
  GPS_STATUS_FLAGS_FIX_OK = (int)0x00010000, GPS_STATUS_FLAGS_DGPS_USED = (int)0x00020000, GPS_STATUS_FLAGS_RTK_FIX_AND_HOLD = (int)0x00040000, GPS_STATUS_FLAGS_RTK_POSITION_ENABLED = (int)0x00100000,
  GPS_STATUS_FLAGS_STATIC_MODE = (int)0x00200000, GPS_STATUS_FLAGS_RTK_COMPASSING_ENABLED = (int)0x00400000, GPS_STATUS_FLAGS_RTK_RAW_GPS_DATA_ERROR = (int)0x00800000, GPS_STATUS_FLAGS_RTK_BASE_DATA_MISSING = (int)0x01000000,
  GPS_STATUS_FLAGS_RTK_BASE_POSITION_MOVING = (int)0x02000000, GPS_STATUS_FLAGS_RTK_BASE_POSITION_INVALID = (int)0x03000000, GPS_STATUS_FLAGS_RTK_BASE_POSITION_MASK = (int)0x03000000, GPS_STATUS_FLAGS_ERROR_MASK,
  GPS_STATUS_FLAGS_RTK_POSITION_VALID = (int)0x04000000, GPS_STATUS_FLAGS_RTK_COMPASSING_VALID = (int)0x08000000, GPS_STATUS_FLAGS_RTK_COMPASSING_BASELINE_BAD = (int)0x00002000, GPS_STATUS_FLAGS_RTK_COMPASSING_BASELINE_UNSET = (int)0x00004000,
  GPS_STATUS_FLAGS_RTK_COMPASSING_MASK, GPS_STATUS_FLAGS_GPS_NMEA_DATA = (int)0x00008000, GPS_STATUS_FLAGS_MASK = (int)0x0FFFE000, GPS_STATUS_FLAGS_BIT_OFFSET = (int)16
}
 
enum  eHdwBitStatusFlags {
  HDW_BIT_PASSED_MASK = (int)0x0000000F, HDW_BIT_PASSED_ALL = (int)0x00000001, HDW_BIT_PASSED_NO_GPS = (int)0x00000002, HDW_BIT_MODE_MASK = (int)0x000000F0,
  HDW_BIT_MODE_OFFSET = (int)4, HDW_BIT_FAILED_MASK = (int)0xFFFFFF00, HDW_BIT_FAILED_AHRS_MASK = (int)0xFFFF0F00, HDW_BIT_FAULT_NOISE_PQR = (int)0x00000100,
  HDW_BIT_FAULT_NOISE_ACC = (int)0x00000200, HDW_BIT_FAULT_MAGNETOMETER = (int)0x00000400, HDW_BIT_FAULT_BAROMETER = (int)0x00000800, HDW_BIT_FAULT_GPS_NO_COM = (int)0x00001000,
  HDW_BIT_FAULT_GPS_POOR_CNO = (int)0x00002000, HDW_BIT_FAULT_GPS_POOR_ACCURACY = (int)0x00002000, HDW_BIT_FAULT_GPS_NOISE = (int)0x00004000
}
 
enum  eHdwStatusFlags {
  HDW_STATUS_MOTION_GYR_SIG = (int)0x00000001, HDW_STATUS_MOTION_ACC_SIG = (int)0x00000002, HDW_STATUS_MOTION_SIG_MASK = (int)0x00000003, HDW_STATUS_MOTION_GYR_DEV = (int)0x00000004,
  HDW_STATUS_MOTION_ACC_DEV = (int)0x00000008, HDW_STATUS_MOTION_MASK = (int)0x0000000F, HDW_STATUS_GPS_SATELLITE_RX = (int)0x00000010, HDW_STATUS_STROBE_IN_EVENT = (int)0x00000020,
  HDW_STATUS_GPS_TIME_OF_WEEK_VALID = (int)0x00000040, HDW_STATUS_UNUSED_1 = (int)0x00000080, HDW_STATUS_SATURATION_GYR = (int)0x00000100, HDW_STATUS_SATURATION_ACC = (int)0x00000200,
  HDW_STATUS_SATURATION_MAG = (int)0x00000400, HDW_STATUS_SATURATION_BARO = (int)0x00000800, HDW_STATUS_SATURATION_MASK = (int)0x00000F00, HDW_STATUS_SATURATION_OFFSET = 8,
  HDW_STATUS_SYSTEM_RESET_REQUIRED = (int)0x00001000, HDW_STATUS_UNUSED_3 = (int)0x00002000, HDW_STATUS_UNUSED_4 = (int)0x00004000, HDW_STATUS_UNUSED_5 = (int)0x00008000,
  HDW_STATUS_ERR_COM_TX_LIMITED = (int)0x00010000, HDW_STATUS_ERR_COM_RX_OVERRUN = (int)0x00020000, HDW_STATUS_COM_PARSE_ERR_COUNT_MASK = (int)0x00F00000, HDW_STATUS_COM_PARSE_ERR_COUNT_OFFSET = 20,
  HDW_STATUS_BIT_FAULT = (int)0x01000000, HDW_STATUS_ERR_TEMPERATURE = (int)0x02000000, HDW_STATUS_UNUSED_6 = (int)0x08000000, HDW_STATUS_FAULT_RESET_MASK = (int)0x70000000,
  HDW_STATUS_FAULT_RESET_BACKUP_MODE = (int)0x10000000, HDW_STATUS_FAULT_RESET_WATCHDOG = (int)0x20000000, HDW_STATUS_FAULT_RESET_SOFT = (int)0x30000000, HDW_STATUS_FAULT_RESET_HDW = (int)0x40000000,
  HDW_STATUS_FAULT_SYS_CRITICAL = (int)0x80000000, HDW_STATUS_OUTPUT_RESET_MASK = (HDW_STATUS_SATURATION_MASK)
}
 
enum  eImuStatus {
  IMU_STATUS_SATURATION_IMU1_GYR = (int)0x00000001, IMU_STATUS_SATURATION_IMU2_GYR = (int)0x00000002, IMU_STATUS_SATURATION_IMU1_ACC = (int)0x00000004, IMU_STATUS_SATURATION_IMU2_ACC = (int)0x00000008,
  IMU_STATUS_RESERVED1 = (int)0x00000020, IMU_STATUS_RESERVED2 = (int)0x00000040
}
 
enum  eInsDynModel {
  DYN_PORTABLE = 0, DYN_STATIONARY = 2, DYN_PEDESTRIAN = 3, DYN_AUTOMOTIVE = 4,
  DYN_MARINE = 5, DYN_AIRBORNE_1G = 6, DYN_AIRBORNE_2G = 7, DYN_AIRBORNE_4G = 8,
  DYN_WRIST = 9
}
 
enum  eInsStatusFlags {
  INS_STATUS_ATT_ALIGN_COARSE = (int)0x00000001, INS_STATUS_VEL_ALIGN_COARSE = (int)0x00000002, INS_STATUS_POS_ALIGN_COARSE = (int)0x00000004, INS_STATUS_ALIGN_COARSE_MASK = (int)0x00000007,
  INS_STATUS_UNUSED_1 = (int)0x00000008, INS_STATUS_ATT_ALIGN_FINE = (int)0x00000010, INS_STATUS_VEL_ALIGN_FINE = (int)0x00000020, INS_STATUS_POS_ALIGN_FINE = (int)0x00000040,
  INS_STATUS_ALIGN_FINE_MASK = (int)0x00000070, INS_STATUS_GPS_AIDING_HEADING = (int)0x00000080, INS_STATUS_GPS_AIDING_POS_VEL = (int)0x00000100, INS_STATUS_GPS_UPDATE_IN_SOLUTION = (int)0x00000200,
  INS_STATUS_RESERVED_1 = (int)0x00000400, INS_STATUS_MAG_AIDING_HEADING = (int)0x00000800, INS_STATUS_NAV_MODE = (int)0x00001000, INS_STATUS_DO_NOT_MOVE = (int)0x00002000,
  INS_STATUS_UNUSED_3 = (int)0x00004000, INS_STATUS_UNUSED_4 = (int)0x00008000, INS_STATUS_SOLUTION_MASK = (int)0x000F0000, INS_STATUS_SOLUTION_OFFSET = 16,
  INS_STATUS_SOLUTION_OFF = 0, INS_STATUS_SOLUTION_ALIGNING = 1, INS_STATUS_SOLUTION_ALIGNMENT_COMPLETE = 2, INS_STATUS_SOLUTION_NAV = 3,
  INS_STATUS_SOLUTION_NAV_HIGH_VARIANCE = 4, INS_STATUS_SOLUTION_AHRS = 5, INS_STATUS_SOLUTION_AHRS_HIGH_VARIANCE = 6, INS_STATUS_RTK_COMPASSING_BASELINE_UNSET = (int)0x00100000,
  INS_STATUS_RTK_COMPASSING_BASELINE_BAD = (int)0x00200000, INS_STATUS_RTK_COMPASSING_MASK = (INS_STATUS_RTK_COMPASSING_BASELINE_UNSET|INS_STATUS_RTK_COMPASSING_BASELINE_BAD), INS_STATUS_MAG_RECALIBRATING = (int)0x00400000, INS_STATUS_MAG_INTERFERENCE_OR_BAD_CAL = (int)0x00800000,
  INS_STATUS_GPS_NAV_FIX_MASK = (int)0x03000000, INS_STATUS_GPS_NAV_FIX_OFFSET = 24, INS_STATUS_RTK_COMPASSING_VALID = (int)0x04000000, INS_STATUS_RTK_RAW_GPS_DATA_ERROR = (int)0x08000000,
  INS_STATUS_RTK_ERR_BASE_DATA_MISSING = (int)0x10000000, INS_STATUS_RTK_ERR_BASE_POSITION_MOVING = (int)0x20000000, INS_STATUS_RTK_ERR_BASE_POSITION_INVALID = (int)0x30000000, INS_STATUS_RTK_ERR_BASE_MASK = (int)0x30000000,
  INS_STATUS_RTK_ERROR_MASK = (INS_STATUS_RTK_RAW_GPS_DATA_ERROR|INS_STATUS_RTK_ERR_BASE_MASK), INS_STATUS_RTOS_TASK_PERIOD_OVERRUN = (int)0x40000000, INS_STATUS_GENERAL_FAULT = (int)0x80000000, INS_STATUS_OUTPUT_RESET_MASK = (0)
}
 
enum  eIoConfig {
  IO_CONFIG_INPUT_STROBE_TRIGGER_HIGH = (int)0x00000001, IO_CONFIG_INPUT_STROBE_G2_ENABLE = (int)0x00000002, IO_CONFIG_INPUT_STROBE_G5_ENABLE = (int)0x00000004, IO_CONFIG_INPUT_STROBE_G8_ENABLE = (int)0x00000008,
  IO_CONFIG_INPUT_STROBE_G9_ENABLE = (int)0x00000010, IO_CONFIG_OUTPUT_STROBE_NAV_G9_ENABLE = (int)0x10000000, IO_CFG_GPS_TIMEPUSE_SOURCE_BITMASK = (int)0x000000E0, IO_CFG_GPS_TIMEPUSE_SOURCE_OFFSET = (int)5,
  IO_CFG_GPS_TIMEPUSE_SOURCE_MASK = (int)0x00000007, IO_CFG_GPS_TIMEPUSE_SOURCE_DISABLED = (int)0, IO_CFG_GPS_TIMEPUSE_SOURCE_ONBOARD_1 = (int)1, IO_CFG_GPS_TIMEPUSE_SOURCE_ONBOARD_2 = (int)2,
  IO_CFG_GPS_TIMEPUSE_SOURCE_STROBE_G2_PIN6 = (int)3, IO_CFG_GPS_TIMEPUSE_SOURCE_STROBE_G5_PIN9 = (int)4, IO_CFG_GPS_TIMEPUSE_SOURCE_STROBE_G8_PIN12 = (int)5, IO_CFG_GPS_TIMEPUSE_SOURCE_STROBE_G9_PIN13 = (int)6,
  IO_CONFIG_GPS1_SOURCE_OFFSET = (int)8, IO_CONFIG_GPS2_SOURCE_OFFSET = (int)11, IO_CONFIG_GPS1_TYPE_OFFSET = (int)14, IO_CONFIG_GPS2_TYPE_OFFSET = (int)17,
  IO_CONFIG_GPS_SOURCE_MASK = (int)0x00000007, IO_CONFIG_GPS_SOURCE_DISABLE = (int)0, IO_CONFIG_GPS_SOURCE_ONBOARD_1 = (int)1, IO_CONFIG_GPS_SOURCE_ONBOARD_2 = (int)2,
  IO_CONFIG_GPS_SOURCE_SER0 = (int)3, IO_CONFIG_GPS_SOURCE_SER1 = (int)4, IO_CONFIG_GPS_SOURCE_SER2 = (int)5, IO_CONFIG_GPS_TYPE_MASK = (int)0x00000003,
  IO_CONFIG_GPS_TYPE_UBX_M8 = (int)0, IO_CONFIG_GPS_TYPE_UBX_F9P = (int)1, IO_CONFIG_GPS_TYPE_NMEA = (int)2, IO_CONFIG_IMU_1_DISABLE = (int)0x00100000,
  IO_CONFIG_IMU_2_DISABLE = (int)0x00200000, IO_CONFIG_CAN_BUS_ENABLE = (int)0x01000000
}
 
enum  eMagRecalMode { MAG_RECAL_CMD_DO_NOTHING = (int)0, MAG_RECAL_CMD_MULTI_AXIS = (int)1, MAG_RECAL_CMD_SINGLE_AXIS = (int)2, MAG_RECAL_CMD_ABORT = (int)101 }
 
enum  eRawDataType {
  raw_data_type_observation = 1, raw_data_type_ephemeris = 2, raw_data_type_glonass_ephemeris = 3, raw_data_type_sbas = 4,
  raw_data_type_base_station_antenna_position = 5, raw_data_type_ionosphere_model_utc_alm = 6, raw_data_type_rtk_solution = 123
}
 
enum  eRTKConfigBits {
  RTK_CFG_BITS_ROVER_MODE_RTK_POSITIONING = (int)0x00000001, RTK_CFG_BITS_ROVER_MODE_RTK_POSITIONING_F9P = (int)0x00000002, RTK_CFG_BITS_ROVER_MODE_RTK_COMPASSING_F9P = (int)0x00000004, RTK_CFG_BITS_ROVER_MODE_RTK_COMPASSING = (int)0x00000008,
  RTK_CFG_BITS_ROVER_MODE_RTK_POSITIONING_MASK = (RTK_CFG_BITS_ROVER_MODE_RTK_POSITIONING|RTK_CFG_BITS_ROVER_MODE_RTK_POSITIONING_F9P), RTK_CFG_BITS_ROVER_MODE_RTK_COMPASSING_MASK = (RTK_CFG_BITS_ROVER_MODE_RTK_COMPASSING|RTK_CFG_BITS_ROVER_MODE_RTK_COMPASSING_F9P), RTK_CFG_BITS_ROVER_MODE_MASK = (int)0x0000000F, RTK_CFG_BITS_BASE_OUTPUT_GPS1_UBLOX_SER0 = (int)0x00000010,
  RTK_CFG_BITS_BASE_OUTPUT_GPS1_UBLOX_SER1 = (int)0x00000020, RTK_CFG_BITS_BASE_OUTPUT_GPS1_UBLOX_SER2 = (int)0x00000040, RTK_CFG_BITS_BASE_OUTPUT_GPS1_UBLOX_USB = (int)0x00000080, RTK_CFG_BITS_BASE_OUTPUT_GPS1_RTCM3_SER0 = (int)0x00000100,
  RTK_CFG_BITS_BASE_OUTPUT_GPS1_RTCM3_SER1 = (int)0x00000200, RTK_CFG_BITS_BASE_OUTPUT_GPS1_RTCM3_SER2 = (int)0x00000400, RTK_CFG_BITS_BASE_OUTPUT_GPS1_RTCM3_USB = (int)0x00000800, RTK_CFG_BITS_BASE_OUTPUT_GPS2_UBLOX_SER0 = (int)0x00001000,
  RTK_CFG_BITS_BASE_OUTPUT_GPS2_UBLOX_SER1 = (int)0x00002000, RTK_CFG_BITS_BASE_OUTPUT_GPS2_UBLOX_SER2 = (int)0x00004000, RTK_CFG_BITS_BASE_OUTPUT_GPS2_UBLOX_USB = (int)0x00008000, RTK_CFG_BITS_BASE_OUTPUT_GPS2_RTCM3_SER0 = (int)0x00010000,
  RTK_CFG_BITS_BASE_OUTPUT_GPS2_RTCM3_SER1 = (int)0x00020000, RTK_CFG_BITS_BASE_OUTPUT_GPS2_RTCM3_SER2 = (int)0x00040000, RTK_CFG_BITS_BASE_OUTPUT_GPS2_RTCM3_USB = (int)0x00080000, RTK_CFG_BITS_BASE_POS_MOVING = (int)0x00100000,
  RTK_CFG_BITS_RESERVED1 = (int)0x00200000, RTK_CFG_BITS_RTK_BASE_IS_IDENTICAL_TO_ROVER = (int)0x00400000, RTK_CFG_BITS_GPS_PORT_PASS_THROUGH = (int)0x00800000, RTK_CFG_BITS_BASE_MODE,
  RTK_CFG_BITS_RTK_BASE_SER0, RTK_CFG_BITS_RTK_BASE_SER1, RTK_CFG_BITS_RTK_BASE_SER2, RTK_CFG_BITS_RTK_BASE_OUTPUT_GPS1_UBLOX,
  RTK_CFG_BITS_RTK_BASE_OUTPUT_GPS2_UBLOX, RTK_CFG_BITS_RTK_BASE_OUTPUT_GPS1_RTCM, RTK_CFG_BITS_RTK_BASE_OUTPUT_GPS2_RTCM, RTK_CFG_BITS_ROVER_MODE_ONBOARD_MASK = (RTK_CFG_BITS_ROVER_MODE_RTK_POSITIONING | RTK_CFG_BITS_ROVER_MODE_RTK_COMPASSING),
  RTK_CFG_BITS_ALL_MODES_MASK = (RTK_CFG_BITS_ROVER_MODE_MASK | RTK_CFG_BITS_BASE_MODE)
}
 
enum  eRtkSolStatus {
  rtk_solution_status_none = 0, rtk_solution_status_fix = 1, rtk_solution_status_float = 2, rtk_solution_status_sbas = 3,
  rtk_solution_status_dgps = 4, rtk_solution_status_single = 5
}
 
enum  eRtosTask {
  TASK_SAMPLE = 0, TASK_NAV, TASK_COMMUNICATIONS, TASK_MAINTENANCE,
  TASK_IDLE, TASK_TIMER, UINS_RTOS_NUM_TASKS
}
 
enum  eSatSvFlags {
  SAT_SV_FLAGS_QUALITYIND_MASK = 0x00000007, SAT_SV_FLAGS_SV_USED = 0x00000008, SAT_SV_FLAGS_HEALTH_MASK = 0x00000030, NAV_SAT_FLAGS_HEALTH_OFFSET = 4,
  SAT_SV_FLAGS_DIFFCORR = 0x00000040, SAT_SV_FLAGS_SMOOTHED = 0x00000080, SAT_SV_FLAGS_ORBITSOURCE_MASK = 0x00000700, SAT_SV_FLAGS_ORBITSOURCE_OFFSET = 8,
  SAT_SV_FLAGS_EPHAVAIL = 0x00000800, SAT_SV_FLAGS_ALMAVAIL = 0x00001000, SAT_SV_FLAGS_ANOAVAIL = 0x00002000, SAT_SV_FLAGS_AOPAVAIL = 0x00004000,
  SAT_SV_FLAGS_RTK_SOL_FIX_STATUS_MASK = 0x03000000, SAT_SV_FLAGS_RTK_SOL_FIX_STATUS_OFFSET = 24, SAT_SV_FLAGS_RTK_SOL_FIX_STATUS_FLOAT = 1, SAT_SV_FLAGS_RTK_SOL_FIX_STATUS_FIX = 2,
  SAT_SV_FLAGS_RTK_SOL_FIX_STATUS_HOLD = 3
}
 
enum  eSensorConfig {
  SENSOR_CFG_GYR_FS_250 = (int)0x00000000, SENSOR_CFG_GYR_FS_500 = (int)0x00000001, SENSOR_CFG_GYR_FS_1000 = (int)0x00000002, SENSOR_CFG_GYR_FS_2000 = (int)0x00000003,
  SENSOR_CFG_GYR_FS_MASK = (int)0x00000003, SENSOR_CFG_GYR_FS_OFFSET = (int)0, SENSOR_CFG_ACC_FS_2G = (int)0x00000000, SENSOR_CFG_ACC_FS_4G = (int)0x00000001,
  SENSOR_CFG_ACC_FS_8G = (int)0x00000002, SENSOR_CFG_ACC_FS_16G = (int)0x00000003, SENSOR_CFG_ACC_FS_MASK = (int)0x00000003, SENSOR_CFG_ACC_FS_OFFSET = (int)2,
  SENSOR_CFG_GYR_DLPF_250HZ = (int)0x00000000, SENSOR_CFG_GYR_DLPF_184HZ = (int)0x00000001, SENSOR_CFG_GYR_DLPF_92HZ = (int)0x00000002, SENSOR_CFG_GYR_DLPF_41HZ = (int)0x00000003,
  SENSOR_CFG_GYR_DLPF_20HZ = (int)0x00000004, SENSOR_CFG_GYR_DLPF_10HZ = (int)0x00000005, SENSOR_CFG_GYR_DLPF_5HZ = (int)0x00000006, SENSOR_CFG_GYR_DLPF_MASK = (int)0x0000000F,
  SENSOR_CFG_GYR_DLPF_OFFSET = (int)8, SENSOR_CFG_ACC_DLPF_218HZ = (int)0x00000000, SENSOR_CFG_ACC_DLPF_218HZb = (int)0x00000001, SENSOR_CFG_ACC_DLPF_99HZ = (int)0x00000002,
  SENSOR_CFG_ACC_DLPF_45HZ = (int)0x00000003, SENSOR_CFG_ACC_DLPF_21HZ = (int)0x00000004, SENSOR_CFG_ACC_DLPF_10HZ = (int)0x00000005, SENSOR_CFG_ACC_DLPF_5HZ = (int)0x00000006,
  SENSOR_CFG_ACC_DLPF_MASK = (int)0x0000000F, SENSOR_CFG_ACC_DLPF_OFFSET = (int)12, SENSOR_CFG_SENSOR_ROTATION_MASK = (int)0x000000FF, SENSOR_CFG_SENSOR_ROTATION_OFFSET = (int)16,
  SENSOR_CFG_SENSOR_ROTATION_0_0_0 = (int)0, SENSOR_CFG_SENSOR_ROTATION_0_0_90 = (int)1, SENSOR_CFG_SENSOR_ROTATION_0_0_180 = (int)2, SENSOR_CFG_SENSOR_ROTATION_0_0_N90 = (int)3,
  SENSOR_CFG_SENSOR_ROTATION_90_0_0 = (int)4, SENSOR_CFG_SENSOR_ROTATION_90_0_90 = (int)5, SENSOR_CFG_SENSOR_ROTATION_90_0_180 = (int)6, SENSOR_CFG_SENSOR_ROTATION_90_0_N90 = (int)7,
  SENSOR_CFG_SENSOR_ROTATION_180_0_0 = (int)8, SENSOR_CFG_SENSOR_ROTATION_180_0_90 = (int)9, SENSOR_CFG_SENSOR_ROTATION_180_0_180 = (int)10, SENSOR_CFG_SENSOR_ROTATION_180_0_N90 = (int)11,
  SENSOR_CFG_SENSOR_ROTATION_N90_0_0 = (int)12, SENSOR_CFG_SENSOR_ROTATION_N90_0_90 = (int)13, SENSOR_CFG_SENSOR_ROTATION_N90_0_180 = (int)14, SENSOR_CFG_SENSOR_ROTATION_N90_0_N90 = (int)15,
  SENSOR_CFG_SENSOR_ROTATION_0_90_0 = (int)16, SENSOR_CFG_SENSOR_ROTATION_0_90_90 = (int)17, SENSOR_CFG_SENSOR_ROTATION_0_90_180 = (int)18, SENSOR_CFG_SENSOR_ROTATION_0_90_N90 = (int)19,
  SENSOR_CFG_SENSOR_ROTATION_0_N90_0 = (int)20, SENSOR_CFG_SENSOR_ROTATION_0_N90_90 = (int)21, SENSOR_CFG_SENSOR_ROTATION_0_N90_180 = (int)22, SENSOR_CFG_SENSOR_ROTATION_0_N90_N90 = (int)23
}
 
enum  eSurveyInStatus {
  SURVEY_IN_STATE_OFF = 0, SURVEY_IN_STATE_CANCEL = 1, SURVEY_IN_STATE_START_3D = 2, SURVEY_IN_STATE_START_FLOAT = 3,
  SURVEY_IN_STATE_START_FIX = 4, SURVEY_IN_STATE_RUNNING_3D = 8, SURVEY_IN_STATE_RUNNING_FLOAT = 9, SURVEY_IN_STATE_RUNNING_FIX = 10,
  SURVEY_IN_STATE_SAVE_POS = 19, SURVEY_IN_STATE_DONE = 20
}
 
enum  eSysConfigBits {
  UNUSED1 = (int)0x00000001, UNUSED2 = (int)0x00000002, SYS_CFG_BITS_AUTO_MAG_RECAL = (int)0x00000004, SYS_CFG_BITS_DISABLE_MAG_DECL_ESTIMATION = (int)0x00000008,
  SYS_CFG_BITS_DISABLE_LEDS = (int)0x00000010, SYS_CFG_BITS_MAG_RECAL_MODE_MASK = (int)0x00000700, SYS_CFG_BITS_MAG_RECAL_MODE_OFFSET = 8, SYS_CFG_BITS_DISABLE_MAGNETOMETER_FUSION = (int)0x00001000,
  SYS_CFG_BITS_DISABLE_BAROMETER_FUSION = (int)0x00002000, SYS_CFG_BITS_DISABLE_GPS1_FUSION = (int)0x00004000, SYS_CFG_BITS_DISABLE_GPS2_FUSION = (int)0x00008000, SYS_CFG_BITS_DISABLE_AUTO_ZERO_VELOCITY_UPDATES = (int)0x00010000,
  SYS_CFG_BITS_DISABLE_AUTO_ZERO_ANGULAR_RATE_UPDATES = (int)0x00020000, SYS_CFG_BITS_DISABLE_INS_EKF = (int)0x00040000, SYS_CFG_BITS_DISABLE_AUTO_BIT_ON_STARTUP = (int)0x00080000, SYS_CFG_BITS_DISABLE_PACKET_ENCODING = (int)0x00400000
}
 
enum  eSystemCommand {
  SYS_CMD_SAVE_PERSISTENT_MESSAGES = 1, SYS_CMD_ENABLE_BOOTLOADER_AND_RESET = 2, SYS_CMD_ENABLE_SENSOR_STATS = 3, SYS_CMD_ENABLE_RTOS_STATS = 4,
  SYS_CMD_ZERO_MOTION = 5, SYS_CMD_ENABLE_GPS_LOW_LEVEL_CONFIG = 10, SYS_CMD_SAVE_FLASH = 97, SYS_CMD_SAVE_GPS_ASSIST_TO_FLASH_RESET = 98,
  SYS_CMD_SOFTWARE_RESET = 99, SYS_CMD_MANF_UNLOCK = 1122334455, SYS_CMD_MANF_FACTORY_RESET = 1357924680, SYS_CMD_MANF_CHIP_ERASE = 1357924681
}
 
enum  eWheelCfgBits { WHEEL_CFG_BITS_ENABLE_KINEMATIC_CONST = (int)0x00000001, WHEEL_CFG_BITS_ENABLE_ENCODER = (int)0x00000002, WHEEL_CFG_BITS_ENABLE_MASK = (int)0x0000000F }
 

Functions

POP_PACK uint32_t checksum32 (const void *data, int count)
 
uint64_t didToRmcBit (uint32_t dataId, uint64_t defaultRmcBits)
 
uint32_t flashChecksum32 (const void *data, int size)
 
void flipDouble (void *ptr)
 
double flipDoubleCopy (double val)
 
void flipDoubles (uint8_t *data, int dataLength, int offset, uint16_t *offsets, uint16_t offsetsLength)
 
void flipEndianess32 (uint8_t *data, int dataLength)
 
void flipFloat (uint8_t *ptr)
 
float flipFloatCopy (float val)
 
void flipStrings (uint8_t *data, int dataLength, int offset, uint16_t *offsets, uint16_t offsetsLength)
 
uint16_t * getDoubleOffsets (eDataIDs dataId, uint16_t *offsetsLength)
 
uint16_t * getStringOffsetsLengths (eDataIDs dataId, uint16_t *offsetsLength)
 
double gpsToJulian (int32_t gpsWeek, int32_t gpsMilliseconds, int32_t leapSeconds)
 
int gpsToNmeaGGA (const gps_pos_t *gps, char *buffer, int bufferLength)
 
double gpsToUnix (uint32_t gpsWeek, uint32_t gpsTimeofWeekMS, uint8_t leapSeconds)
 
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)
 
int satNo (int sys, int prn)
 
int satNumCalc (int gnssID, int svID)
 
uint32_t serialNumChecksum32 (const void *data, int size)
 
int ubxSys (int gnssID)
 

Macro Definition Documentation

◆ BE_SWAP16

#define BE_SWAP16 (   _i)    (_i)

Definition at line 3657 of file data_sets.h.

◆ BE_SWAP32

#define BE_SWAP32 (   _i)    (_i)

Definition at line 3656 of file data_sets.h.

◆ BE_SWAP32F

#define BE_SWAP32F (   _i)    (_i)

Definition at line 3655 of file data_sets.h.

◆ BE_SWAP64F

#define BE_SWAP64F (   _i)    (_i)

Definition at line 3654 of file data_sets.h.

◆ CAL_BIT_MODE

#define CAL_BIT_MODE (   calBitStatus)    ((calBitStatus&CAL_BIT_MODE_MASK)>>CAL_BIT_MODE_OFFSET)

Definition at line 1461 of file data_sets.h.

◆ DEBUG_F_ARRAY_SIZE

#define DEBUG_F_ARRAY_SIZE   9

Definition at line 2099 of file data_sets.h.

◆ DEBUG_I_ARRAY_SIZE

#define DEBUG_I_ARRAY_SIZE   9

Definition at line 2098 of file data_sets.h.

◆ DEBUG_LF_ARRAY_SIZE

#define DEBUG_LF_ARRAY_SIZE   3

Definition at line 2100 of file data_sets.h.

◆ DEBUG_STRING_SIZE

#define DEBUG_STRING_SIZE   80

Definition at line 2110 of file data_sets.h.

◆ DEVINFO_ADDINFO_STRLEN

#define DEVINFO_ADDINFO_STRLEN   24

Definition at line 150 of file data_sets.h.

◆ DEVINFO_MANUFACTURER_STRLEN

#define DEVINFO_MANUFACTURER_STRLEN   24

Maximum length of device info manufacturer string (must be a multiple of 4)

Definition at line 149 of file data_sets.h.

◆ DID_ASCII_BCAST_PERIOD

#define DID_ASCII_BCAST_PERIOD   (eDataIDs)8 /** (ascii_msgs_t) Broadcast period for ASCII messages */

Definition at line 42 of file data_sets.h.

◆ DID_BAROMETER

#define DID_BAROMETER   (eDataIDs)53 /** (barometer_t) Barometric pressure sensor data */

Definition at line 87 of file data_sets.h.

◆ DID_BIT

#define DID_BIT   (eDataIDs)64 /** (bit_t) System built-in self-test */

Definition at line 98 of file data_sets.h.

◆ DID_CAL_SC

#define DID_CAL_SC   (eDataIDs)42 /** INTERNAL USE ONLY (sensor_cal_mem_t) */

Definition at line 76 of file data_sets.h.

◆ DID_CAL_SC1

#define DID_CAL_SC1   (eDataIDs)43 /** INTERNAL USE ONLY (sensor_cal_mpu_t) */

Definition at line 77 of file data_sets.h.

◆ DID_CAL_SC2

#define DID_CAL_SC2   (eDataIDs)44 /** INTERNAL USE ONLY (sensor_cal_mpu_t) */

Definition at line 78 of file data_sets.h.

◆ DID_CAL_SC_INFO

#define DID_CAL_SC_INFO   (eDataIDs)74 /** INTERNAL USE ONLY (sensor_cal_info_t) */

Definition at line 108 of file data_sets.h.

◆ DID_CAN_CONFIG

#define DID_CAN_CONFIG   (eDataIDs)90 /** (can_config_t) Addresses for CAN messages*/

Definition at line 124 of file data_sets.h.

◆ DID_COMMUNICATIONS_LOOPBACK

#define DID_COMMUNICATIONS_LOOPBACK   (eDataIDs)56 /** INTERNAL USE ONLY - Unit test for communications manager */

Definition at line 90 of file data_sets.h.

◆ DID_COUNT

#define DID_COUNT   (eDataIDs)96

Count of data ids (including null data id 0) - MUST BE MULTPLE OF 4 and larger than last DID number!

Definition at line 138 of file data_sets.h.

◆ DID_DEBUG_ARRAY

#define DID_DEBUG_ARRAY   (eDataIDs)39 /** INTERNAL USE ONLY (debug_array_t) */

Definition at line 73 of file data_sets.h.

◆ DID_DEBUG_STRING

#define DID_DEBUG_STRING   (eDataIDs)37 /** INTERNAL USE ONLY (debug_string_t) */

Definition at line 71 of file data_sets.h.

◆ DID_DEV_INFO

#define DID_DEV_INFO   (eDataIDs)1 /** (dev_info_t) Device information */

Definition at line 35 of file data_sets.h.

◆ DID_DIAGNOSTIC_MESSAGE

#define DID_DIAGNOSTIC_MESSAGE   (eDataIDs)72 /** (diag_msg_t) Diagnostic message */

Definition at line 106 of file data_sets.h.

◆ DID_DUAL_IMU

#define DID_DUAL_IMU   (eDataIDs)58 /** (dual_imu_t) Dual inertial measurement unit data down-sampled from 1KHz to navigation update rate (DID_FLASH_CONFIG.startupNavDtMs) as an anti-aliasing filter to reduce noise and preserve accuracy. Minimum data period is DID_FLASH_CONFIG.startupNavDtMs (1KHz max). */

Definition at line 92 of file data_sets.h.

◆ DID_DUAL_IMU_MAG

#define DID_DUAL_IMU_MAG   (eDataIDs)85 /** (imu_mag_t) DID_DUAL_IMU + DID_MAGNETOMETER + MAGNETOMETER_2 Only one of DID_DUAL_IMU_RAW_MAG, DID_DUAL_IMU_MAG, or DID_PREINTEGRATED_IMU_MAG should be streamed simultaneously. */

Definition at line 119 of file data_sets.h.

◆ DID_DUAL_IMU_RAW

#define DID_DUAL_IMU_RAW   (eDataIDs)57 /** (dual_imu_t) Dual inertial measurement unit data directly from IMU. We recommend use of DID_DUAL_IMU or DID_PREINTEGRATED_IMU. Minimum data period is DID_FLASH_CONFIG.startupImuDtMs or 4, whichever is larger (250Hz max). */

Definition at line 91 of file data_sets.h.

◆ DID_DUAL_IMU_RAW_MAG

#define DID_DUAL_IMU_RAW_MAG   (eDataIDs)84 /** (imu_mag_t) DID_DUAL_IMU_RAW + DID_MAGNETOMETER + MAGNETOMETER_2 Only one of DID_DUAL_IMU_RAW_MAG, DID_DUAL_IMU_MAG, or DID_PREINTEGRATED_IMU_MAG should be streamed simultaneously. */

Definition at line 118 of file data_sets.h.

◆ DID_EVB_DEBUG_ARRAY

#define DID_EVB_DEBUG_ARRAY   (eDataIDs)82 /** INTERNAL USE ONLY (debug_array_t) */

Definition at line 116 of file data_sets.h.

◆ DID_EVB_DEV_INFO

#define DID_EVB_DEV_INFO   (eDataIDs)93 /** (dev_info_t) EVB device information */

Definition at line 127 of file data_sets.h.

◆ DID_EVB_FLASH_CFG

#define DID_EVB_FLASH_CFG   (eDataIDs)81 /** (evb_flash_cfg_t) EVB configuration. */

Definition at line 115 of file data_sets.h.

◆ DID_EVB_RTOS_INFO

#define DID_EVB_RTOS_INFO   (eDataIDs)83 /** (evb_rtos_info_t) EVB-2 RTOS information. */

Definition at line 117 of file data_sets.h.

◆ DID_EVB_STATUS

#define DID_EVB_STATUS   (eDataIDs)80 /** (evb_status_t) EVB monitor and log control interface. */

Definition at line 114 of file data_sets.h.

◆ DID_FEATURE_BITS

#define DID_FEATURE_BITS   (eDataIDs)23 /** INTERNAL USE ONLY (feature_bits_t) */

Definition at line 57 of file data_sets.h.

◆ DID_FLASH_CONFIG

#define DID_FLASH_CONFIG   (eDataIDs)12 /** (nvm_flash_cfg_t) Flash memory configuration */

Definition at line 46 of file data_sets.h.

◆ DID_GPS1_POS

#define DID_GPS1_POS   (eDataIDs)13 /** (gps_pos_t) GPS 1 position data. This comes from DID_GPS1_UBX_POS or DID_GPS1_RTK_POS, depending on whichever is more accurate. */

Definition at line 47 of file data_sets.h.

◆ DID_GPS1_RAW

#define DID_GPS1_RAW   (eDataIDs)69 /** (gps_raw_t) GPS raw data for rover (observation, ephemeris, etc.) - requires little endian CPU. The contents of data can vary for this message and are determined by dataType field. RTK positioning or RTK compassing must be enabled to stream this message. */

Definition at line 103 of file data_sets.h.

◆ DID_GPS1_RTK_POS

#define DID_GPS1_RTK_POS   (eDataIDs)54 /** (gps_pos_t) GPS RTK position data */

Definition at line 88 of file data_sets.h.

◆ DID_GPS1_RTK_POS_MISC

#define DID_GPS1_RTK_POS_MISC   (eDataIDs)22 /** (gps_rtk_misc_t) RTK precision position related data. */

Definition at line 56 of file data_sets.h.

◆ DID_GPS1_RTK_POS_REL

#define DID_GPS1_RTK_POS_REL   (eDataIDs)21 /** (gps_rtk_rel_t) RTK precision position base to rover relative info. */

Definition at line 55 of file data_sets.h.

◆ DID_GPS1_SAT

#define DID_GPS1_SAT   (eDataIDs)15 /** (gps_sat_t) GPS 1 GNSS and sat identifiers, carrier to noise ratio (signal strength), elevation and azimuth angles, pseudo range residual. */

Definition at line 49 of file data_sets.h.

◆ DID_GPS1_UBX_POS

#define DID_GPS1_UBX_POS   (eDataIDs)6 /** (gps_pos_t) GPS 1 position data from ublox receiver. */

Definition at line 40 of file data_sets.h.

◆ DID_GPS1_VEL

#define DID_GPS1_VEL   (eDataIDs)30 /** (gps_vel_t) GPS 1 velocity data */

Definition at line 64 of file data_sets.h.

◆ DID_GPS1_VERSION

#define DID_GPS1_VERSION   (eDataIDs)17 /** (gps_version_t) GPS 1 version info */

Definition at line 51 of file data_sets.h.

◆ DID_GPS2_POS

#define DID_GPS2_POS   (eDataIDs)14 /** (gps_pos_t) GPS 2 position data */

Definition at line 48 of file data_sets.h.

◆ DID_GPS2_RAW

#define DID_GPS2_RAW   (eDataIDs)70 /** (gps_raw_t) GPS raw data for rover (observation, ephemeris, etc.) - requires little endian CPU. The contents of data can vary for this message and are determined by dataType field. RTK positioning or RTK compassing must be enabled to stream this message. */

Definition at line 104 of file data_sets.h.

◆ DID_GPS2_RTK_CMP_MISC

#define DID_GPS2_RTK_CMP_MISC   (eDataIDs)92 /** (gps_rtk_misc_t) RTK Dual GNSS RTK compassing related data. */

Definition at line 126 of file data_sets.h.

◆ DID_GPS2_RTK_CMP_REL

#define DID_GPS2_RTK_CMP_REL   (eDataIDs)91 /** (gps_rtk_rel_t) Dual GNSS RTK compassing / moving base to rover (GPS 1 to GPS 2) relative info. */

Definition at line 125 of file data_sets.h.

◆ DID_GPS2_SAT

#define DID_GPS2_SAT   (eDataIDs)16 /** (gps_sat_t) GPS 2 GNSS and sat identifiers, carrier to noise ratio (signal strength), elevation and azimuth angles, pseudo range residual. */

Definition at line 50 of file data_sets.h.

◆ DID_GPS2_VEL

#define DID_GPS2_VEL   (eDataIDs)31 /** (gps_vel_t) GPS 2 velocity data */

Definition at line 65 of file data_sets.h.

◆ DID_GPS2_VERSION

#define DID_GPS2_VERSION   (eDataIDs)18 /** (gps_version_t) GPS 2 version info */

Definition at line 52 of file data_sets.h.

◆ DID_GPS_BASE_RAW

#define DID_GPS_BASE_RAW   (eDataIDs)60 /** (gps_raw_t) GPS raw data for base station (observation, ephemeris, etc.) - requires little endian CPU. The contents of data can vary for this message and are determined by dataType field. RTK positioning or RTK compassing must be enabled to stream this message. */

Definition at line 94 of file data_sets.h.

◆ DID_GPS_RTK_OPT

#define DID_GPS_RTK_OPT   (eDataIDs)61 /** (gps_rtk_opt_t) RTK options - requires little endian CPU. */

Definition at line 95 of file data_sets.h.

◆ DID_HDW_PARAMS

#define DID_HDW_PARAMS   (eDataIDs)32 /** INTERNAL USE ONLY (hdw_params_t) */

Definition at line 66 of file data_sets.h.

◆ DID_INL2_COVARIANCE_LD

#define DID_INL2_COVARIANCE_LD   (eDataIDs)49 /** (INL2_COVARIANCE_LD_ARRAY_SIZE) */

Definition at line 83 of file data_sets.h.

◆ DID_INL2_MAG_OBS_INFO

#define DID_INL2_MAG_OBS_INFO   (eDataIDs)59 /** (inl2_mag_obs_info_t) INL2 magnetometer calibration information. */

Definition at line 93 of file data_sets.h.

◆ DID_INL2_MISC

#define DID_INL2_MISC   (eDataIDs)51 /** (inl2_misc_t) */

Definition at line 85 of file data_sets.h.

◆ DID_INL2_NED_SIGMA

#define DID_INL2_NED_SIGMA   (eDataIDs)67 /** (inl2_ned_sigma_t) INL2 standard deviation in the NED frame */

Definition at line 101 of file data_sets.h.

◆ DID_INL2_STATES

#define DID_INL2_STATES   (eDataIDs)48 /** (inl2_states_t) */

Definition at line 82 of file data_sets.h.

◆ DID_INL2_STATUS

#define DID_INL2_STATUS   (eDataIDs)50 /** (inl2_status_t) */

Definition at line 84 of file data_sets.h.

◆ DID_INS_1

#define DID_INS_1   (eDataIDs)4 /** (ins_1_t) INS output: euler rotation w/ respect to NED, NED position from reference LLA. */

Definition at line 38 of file data_sets.h.

◆ DID_INS_2

#define DID_INS_2   (eDataIDs)5 /** (ins_2_t) INS output: quaternion rotation w/ respect to NED, ellipsoid altitude */

Definition at line 39 of file data_sets.h.

◆ DID_INS_3

#define DID_INS_3   (eDataIDs)65 /** (ins_3_t) Inertial navigation data with quaternion NED to body rotation and ECEF position. */

Definition at line 99 of file data_sets.h.

◆ DID_INS_4

#define DID_INS_4   (eDataIDs)66 /** (ins_4_t) INS output: quaternion rotation w/ respect to ECEF, ECEF position. */

Definition at line 100 of file data_sets.h.

◆ DID_INS_DEV_1

#define DID_INS_DEV_1   (eDataIDs)47 /** INTERNAL USE ONLY (ins_dev_1_t) */

Definition at line 81 of file data_sets.h.

◆ DID_INTERNAL_DIAGNOSTIC

#define DID_INTERNAL_DIAGNOSTIC   (eDataIDs)20 /** INTERNAL USE ONLY (internal_diagnostic_t) Internal diagnostic info */

Definition at line 54 of file data_sets.h.

◆ DID_IO

#define DID_IO   (eDataIDs)27 /** (io_t) I/O */

Definition at line 61 of file data_sets.h.

◆ DID_MAG_CAL

#define DID_MAG_CAL   (eDataIDs)19 /** (mag_cal_t) Magnetometer calibration */

Definition at line 53 of file data_sets.h.

◆ DID_MAGNETOMETER_1

#define DID_MAGNETOMETER_1   (eDataIDs)52 /** (magnetometer_t) Magnetometer sensor 1 output */

Definition at line 86 of file data_sets.h.

◆ DID_MAGNETOMETER_2

#define DID_MAGNETOMETER_2   (eDataIDs)55 /** (magnetometer_t) 2nd magnetometer sensor data */

Definition at line 89 of file data_sets.h.

◆ DID_MANUFACTURING_INFO

#define DID_MANUFACTURING_INFO   (eDataIDs)63 /** INTERNAL USE ONLY (manufacturing_info_t) Manufacturing info */

Definition at line 97 of file data_sets.h.

◆ DID_MAX_COUNT

#define DID_MAX_COUNT   256

Maximum number of data ids

Definition at line 141 of file data_sets.h.

◆ DID_NULL

#define DID_NULL   (eDataIDs)0 /** NULL (INVALID) */

Definition at line 34 of file data_sets.h.

◆ DID_NVR_MANAGE_USERPAGE

#define DID_NVR_MANAGE_USERPAGE   (eDataIDs)33 /** INTERNAL USE ONLY (nvr_manage_t) */

Definition at line 67 of file data_sets.h.

◆ DID_NVR_USERPAGE_G0

#define DID_NVR_USERPAGE_G0   (eDataIDs)35 /** INTERNAL USE ONLY (nvm_group_0_t) */

Definition at line 69 of file data_sets.h.

◆ DID_NVR_USERPAGE_G1

#define DID_NVR_USERPAGE_G1   (eDataIDs)36 /** INTERNAL USE ONLY (nvm_group_1_t) */

Definition at line 70 of file data_sets.h.

◆ DID_NVR_USERPAGE_INTERNAL

#define DID_NVR_USERPAGE_INTERNAL   (eDataIDs)62 /** (internal) Internal user page data */

Definition at line 96 of file data_sets.h.

◆ DID_NVR_USERPAGE_SN

#define DID_NVR_USERPAGE_SN   (eDataIDs)34 /** INTERNAL USE ONLY (nvm_group_sn_t) */

Definition at line 68 of file data_sets.h.

◆ DID_PORT_MONITOR

#define DID_PORT_MONITOR   (eDataIDs)75 /** (port_monitor_t) Data rate and status monitoring for each communications port. */

Definition at line 109 of file data_sets.h.

◆ DID_POSITION_MEASUREMENT

#define DID_POSITION_MEASUREMENT   (eDataIDs)88 /** (pos_measurement_t) External position estimate*/

Definition at line 122 of file data_sets.h.

◆ DID_PREINTEGRATED_IMU

#define DID_PREINTEGRATED_IMU   (eDataIDs)3 /** (preintegrated_imu_t) Coning and sculling integral in body/IMU frame. Updated at IMU rate. Also know as Delta Theta Delta Velocity, or Integrated IMU. For clarification, we use the name "Preintegrated IMU" through the User Manual. This data is integrated from the IMU data at the IMU update rate (startupImuDtMs, default 1ms). The integration period (dt) and output data rate are the same as the NAV rate (startupNavDtMs, default 4ms) and cannot be output at any other rate. If a different output data rate is desired, DID_DUAL_IMU which is derived from DID_PREINTEGRATED_IMU can be used instead. Preintegrated IMU data acts as a form of compression, adding the benefit of higher integration rates for slower output data rates, preserving the IMU data without adding filter delay and addresses antialiasing. It is most effective for systems that have higher dynamics and lower communications data rates. The minimum data period is DID_FLASH_CONFIG.startupImuDtMs or 4, whichever is larger (250Hz max). */

Definition at line 37 of file data_sets.h.

◆ DID_PREINTEGRATED_IMU_MAG

#define DID_PREINTEGRATED_IMU_MAG   (eDataIDs)86 /** (pimu_mag_t) DID_PREINTEGRATED_IMU + DID_MAGNETOMETER + MAGNETOMETER_2 Only one of DID_DUAL_IMU_RAW_MAG, DID_DUAL_IMU_MAG, or DID_PREINTEGRATED_IMU_MAG should be streamed simultaneously. */

Definition at line 120 of file data_sets.h.

◆ DID_RMC

#define DID_RMC   (eDataIDs)9 /** (rmc_t) Realtime Message Controller (RMC). The data sets available through RMC are driven by the availability of the data. The RMC provides updates from various data sources (i.e. sensors) as soon as possible with minimal latency. Several of the data sources (sensors) output data at different data rates that do not all correspond. The RMC is provided so that broadcast of sensor data is done as soon as it becomes available. All RMC messages can be enabled using the standard Get Data packet format. */

Definition at line 43 of file data_sets.h.

◆ DID_RTK_CODE_RESIDUAL

#define DID_RTK_CODE_RESIDUAL   (eDataIDs)78 /** INTERNAL USE ONLY (rtk_residual_t) */

Definition at line 112 of file data_sets.h.

◆ DID_RTK_DEBUG

#define DID_RTK_DEBUG   (eDataIDs)79 /** INTERNAL USE ONLY (rtk_debug_t) */

Definition at line 113 of file data_sets.h.

◆ DID_RTK_DEBUG_2

#define DID_RTK_DEBUG_2   (eDataIDs)89 /** INTERNAL USE ONLY (rtk_debug_2_t) */

Definition at line 123 of file data_sets.h.

◆ DID_RTK_PHASE_RESIDUAL

#define DID_RTK_PHASE_RESIDUAL   (eDataIDs)77 /** INTERNAL USE ONLY (rtk_residual_t) */

Definition at line 111 of file data_sets.h.

◆ DID_RTK_STATE

#define DID_RTK_STATE   (eDataIDs)76 /** INTERNAL USE ONLY (rtk_state_t) */

Definition at line 110 of file data_sets.h.

◆ DID_RTOS_INFO

#define DID_RTOS_INFO   (eDataIDs)38 /** (rtos_info_t) RTOS information. */

Definition at line 72 of file data_sets.h.

◆ DID_SCOMP

#define DID_SCOMP   (eDataIDs)29 /** INTERNAL USE ONLY (sensor_compensation_t) */

Definition at line 63 of file data_sets.h.

◆ DID_SENSORS_ADC

#define DID_SENSORS_ADC   (eDataIDs)28 /** INTERNAL USE ONLY (sys_sensors_adc_t) */

Definition at line 62 of file data_sets.h.

◆ DID_SENSORS_ADC_SIGMA

#define DID_SENSORS_ADC_SIGMA   (eDataIDs)46 /** INTERNAL USE ONLY (sys_sensors_adc_t) */

Definition at line 80 of file data_sets.h.

◆ DID_SENSORS_CAL1

#define DID_SENSORS_CAL1   (eDataIDs)40 /** INTERNAL USE ONLY (sensors_mpu_w_temp_t) */

Definition at line 74 of file data_sets.h.

◆ DID_SENSORS_CAL2

#define DID_SENSORS_CAL2   (eDataIDs)41 /** INTERNAL USE ONLY (sensors_mpu_w_temp_t) */

Definition at line 75 of file data_sets.h.

◆ DID_SENSORS_IS1

#define DID_SENSORS_IS1   (eDataIDs)24 /** INTERNAL USE ONLY (sensors_w_temp_t) Cross-axis aligned w/ scale factor */

Definition at line 58 of file data_sets.h.

◆ DID_SENSORS_IS2

#define DID_SENSORS_IS2   (eDataIDs)25 /** INTERNAL USE ONLY (sensors_w_temp_t) Temperature compensated */

Definition at line 59 of file data_sets.h.

◆ DID_SENSORS_TC_BIAS

#define DID_SENSORS_TC_BIAS   (eDataIDs)26 /** INTERNAL USE ONLY (sensors_t) */

Definition at line 60 of file data_sets.h.

◆ DID_STROBE_IN_TIME

#define DID_STROBE_IN_TIME   (eDataIDs)68 /** (strobe_in_time_t) Timestamp for input strobe. */

Definition at line 102 of file data_sets.h.

◆ DID_SURVEY_IN

#define DID_SURVEY_IN   (eDataIDs)73 /** (survey_in_t) Survey in, used to determine position for RTK base station. Base correction output cannot run during a survey and will be automatically disabled if a survey is started. */

Definition at line 107 of file data_sets.h.

◆ DID_SYS_CMD

#define DID_SYS_CMD   (eDataIDs)7 /** (system_command_t) System commands. Both the command and invCommand fields must be set at the same time for a command to take effect. */

Definition at line 41 of file data_sets.h.

◆ DID_SYS_FAULT

#define DID_SYS_FAULT   (eDataIDs)2 /** (system_fault_t) System fault information */

Definition at line 36 of file data_sets.h.

◆ DID_SYS_PARAMS

#define DID_SYS_PARAMS   (eDataIDs)10 /** (sys_params_t) System parameters / info */

Definition at line 44 of file data_sets.h.

◆ DID_SYS_SENSORS

#define DID_SYS_SENSORS   (eDataIDs)11 /** (sys_sensors_t) System sensor information */

Definition at line 45 of file data_sets.h.

◆ DID_SYS_SENSORS_SIGMA

#define DID_SYS_SENSORS_SIGMA   (eDataIDs)45 /** INTERNAL USE ONLY (sys_sensors_t) */

Definition at line 79 of file data_sets.h.

◆ DID_WHEEL_CONFIG

#define DID_WHEEL_CONFIG   (eDataIDs)87 /** (wheel_config_t) [NOT SUPPORTED, INTERNAL USE ONLY] Static configuration for wheel encoder measurements. */

Definition at line 121 of file data_sets.h.

◆ DID_WHEEL_ENCODER

#define DID_WHEEL_ENCODER   (eDataIDs)71 /** (wheel_encoder_t) [NOT SUPPORTED, INTERNAL USE ONLY] Wheel encoder data to be fused with GPS-INS measurements, set DID_WHEEL_CONFIG for configuration before sending this message */

Definition at line 105 of file data_sets.h.

◆ ENAGAL

#define ENAGAL

Definition at line 3737 of file data_sets.h.

◆ ENAGLO

#define ENAGLO

Definition at line 3734 of file data_sets.h.

◆ ENASBS

#define ENASBS

Definition at line 3743 of file data_sets.h.

◆ EVB2_CB_PRESET_DEFAULT

#define EVB2_CB_PRESET_DEFAULT   EVB2_CB_PRESET_RS232

Definition at line 3236 of file data_sets.h.

◆ EVB_CFG_BITS_IDX_SERVER

#define EVB_CFG_BITS_IDX_SERVER (   bits)    ((bits&EVB_CFG_BITS_SERVER_SELECT_MASK)>>EVB_CFG_BITS_SERVER_SELECT_OFFSET)

Definition at line 3125 of file data_sets.h.

◆ EVB_CFG_BITS_IDX_WIFI

#define EVB_CFG_BITS_IDX_WIFI (   bits)    ((bits&EVB_CFG_BITS_WIFI_SELECT_MASK)>>EVB_CFG_BITS_WIFI_SELECT_OFFSET)

Definition at line 3124 of file data_sets.h.

◆ EVB_CFG_BITS_SET_IDX_SERVER

#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);}

Definition at line 3123 of file data_sets.h.

◆ EVB_CFG_BITS_SET_IDX_WIFI

#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);}

Definition at line 3122 of file data_sets.h.

◆ GPS_RAW_MESSAGE_BUF_SIZE

#define GPS_RAW_MESSAGE_BUF_SIZE   1000

Definition at line 2417 of file data_sets.h.

◆ GPS_TO_UNIX_OFFSET

#define GPS_TO_UNIX_OFFSET   315964800

Definition at line 3690 of file data_sets.h.

◆ HALF_MAXOBS

#define HALF_MAXOBS   (MAXOBS/2)

Definition at line 3773 of file data_sets.h.

◆ HDW_BIT_MODE

#define HDW_BIT_MODE (   hdwBitStatus)    ((hdwBitStatus&HDW_BIT_MODE_MASK)>>HDW_BIT_MODE_OFFSET)

Definition at line 1441 of file data_sets.h.

◆ HDW_STATUS_COM_PARSE_ERROR_COUNT

#define HDW_STATUS_COM_PARSE_ERROR_COUNT (   hdwStatus)    ((hdwStatus&HDW_STATUS_COM_PARSE_ERR_COUNT_MASK)>>HDW_STATUS_COM_PARSE_ERR_COUNT_OFFSET)

Definition at line 330 of file data_sets.h.

◆ INS_STATUS_NAV_FIX_STATUS

#define INS_STATUS_NAV_FIX_STATUS (   insStatus)    ((insStatus&INS_STATUS_GPS_NAV_FIX_MASK)>>INS_STATUS_GPS_NAV_FIX_OFFSET)

Definition at line 237 of file data_sets.h.

◆ INS_STATUS_SOLUTION

#define INS_STATUS_SOLUTION (   insStatus)    ((insStatus&INS_STATUS_SOLUTION_MASK)>>INS_STATUS_SOLUTION_OFFSET)

Definition at line 213 of file data_sets.h.

◆ IO_CFG_GPS_TIMEPUSE_SOURCE

#define IO_CFG_GPS_TIMEPUSE_SOURCE (   ioConfig)    ((ioConfig>>IO_CFG_GPS_TIMEPUSE_SOURCE_OFFSET)&IO_CFG_GPS_TIMEPUSE_SOURCE_MASK)

Definition at line 1835 of file data_sets.h.

◆ IO_CONFIG_GPS1_SOURCE

#define IO_CONFIG_GPS1_SOURCE (   ioConfig)    ((ioConfig>>IO_CONFIG_GPS1_SOURCE_OFFSET)&IO_CONFIG_GPS_SOURCE_MASK)

Definition at line 1870 of file data_sets.h.

◆ IO_CONFIG_GPS1_TYPE

#define IO_CONFIG_GPS1_TYPE (   ioConfig)    ((ioConfig>>IO_CONFIG_GPS1_TYPE_OFFSET)&IO_CONFIG_GPS_TYPE_MASK)

Definition at line 1872 of file data_sets.h.

◆ IO_CONFIG_GPS2_SOURCE

#define IO_CONFIG_GPS2_SOURCE (   ioConfig)    ((ioConfig>>IO_CONFIG_GPS2_SOURCE_OFFSET)&IO_CONFIG_GPS_SOURCE_MASK)

Definition at line 1871 of file data_sets.h.

◆ IO_CONFIG_GPS2_TYPE

#define IO_CONFIG_GPS2_TYPE (   ioConfig)    ((ioConfig>>IO_CONFIG_GPS2_TYPE_OFFSET)&IO_CONFIG_GPS_TYPE_MASK)

Definition at line 1873 of file data_sets.h.

◆ LE_SWAP16

#define LE_SWAP16 (   _i)    (SWAP16(_i))

Definition at line 3661 of file data_sets.h.

◆ LE_SWAP32

#define LE_SWAP32 (   _i)    (SWAP32(_i))

Definition at line 3660 of file data_sets.h.

◆ LE_SWAP32F

#define LE_SWAP32F (   _i)    flipFloatCopy(_i)

Definition at line 3659 of file data_sets.h.

◆ LE_SWAP64F

#define LE_SWAP64F (   _i)    flipDoubleCopy(_i)

Definition at line 3658 of file data_sets.h.

◆ MAX_NUM_SAT_CHANNELS

#define MAX_NUM_SAT_CHANNELS   50

Maximum number of satellite channels

Definition at line 146 of file data_sets.h.

◆ MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE

#define MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE   (GPS_RAW_MESSAGE_BUF_SIZE / sizeof(obsd_t))

Definition at line 2418 of file data_sets.h.

◆ MAX_TASK_NAME_LEN

#define MAX_TASK_NAME_LEN   12

Max task name length - do not change

Definition at line 3408 of file data_sets.h.

◆ MAXERRMSG

#define MAXERRMSG   0

Definition at line 3779 of file data_sets.h.

◆ MAXOBS

#define MAXOBS   56

Definition at line 3772 of file data_sets.h.

◆ MAXPRNCMP

#define MAXPRNCMP   0

Definition at line 3855 of file data_sets.h.

◆ MAXPRNGAL

#define MAXPRNGAL   30 /* max satellite PRN number of Galileo */

Definition at line 3824 of file data_sets.h.

◆ MAXPRNGLO

#define MAXPRNGLO   27 /* max satellite slot number of GLONASS */

Definition at line 3813 of file data_sets.h.

◆ MAXPRNGPS

#define MAXPRNGPS   32 /* max satellite PRN number of GPS */

Definition at line 3807 of file data_sets.h.

◆ MAXPRNIRN

#define MAXPRNIRN   0

Definition at line 3866 of file data_sets.h.

◆ MAXPRNLEO

#define MAXPRNLEO   0

Definition at line 3877 of file data_sets.h.

◆ MAXPRNQZS

#define MAXPRNQZS   0

Definition at line 3842 of file data_sets.h.

◆ MAXPRNQZS_S

#define MAXPRNQZS_S   0

Definition at line 3844 of file data_sets.h.

◆ MAXPRNSBS

#define MAXPRNSBS   138 /* max satellite PRN number of SBAS */

Definition at line 3788 of file data_sets.h.

◆ MAXRAWLEN

#define MAXRAWLEN   2048

Definition at line 3749 of file data_sets.h.

◆ MAXSUBFRMLEN

#define MAXSUBFRMLEN   152

Definition at line 3746 of file data_sets.h.

◆ MINPRNCMP

#define MINPRNCMP   0

Definition at line 3854 of file data_sets.h.

◆ MINPRNGAL

#define MINPRNGAL   1 /* min satellite PRN number of Galileo */

Definition at line 3823 of file data_sets.h.

◆ MINPRNGLO

#define MINPRNGLO   1 /* min satellite slot number of GLONASS */

Definition at line 3812 of file data_sets.h.

◆ MINPRNGPS

#define MINPRNGPS   1 /* min satellite PRN number of GPS */

Definition at line 3806 of file data_sets.h.

◆ MINPRNIRN

#define MINPRNIRN   0

Definition at line 3865 of file data_sets.h.

◆ MINPRNLEO

#define MINPRNLEO   0

Definition at line 3876 of file data_sets.h.

◆ MINPRNQZS

#define MINPRNQZS   0

Definition at line 3841 of file data_sets.h.

◆ MINPRNQZS_S

#define MINPRNQZS_S   0

Definition at line 3843 of file data_sets.h.

◆ MINPRNSBS

#define MINPRNSBS   133 /* min satellite PRN number of SBAS */

Definition at line 3785 of file data_sets.h.

◆ NEXOBS

#define NEXOBS   0

Definition at line 3769 of file data_sets.h.

◆ NFREQ

#define NFREQ   1

Definition at line 3752 of file data_sets.h.

◆ NFREQGAL

#define NFREQGAL   1

Definition at line 3763 of file data_sets.h.

◆ NFREQGLO

#define NFREQGLO   1

Definition at line 3756 of file data_sets.h.

◆ NSATCMP

#define NSATCMP   0

Definition at line 3856 of file data_sets.h.

◆ NSATGAL

#define NSATGAL   (MAXPRNGAL-MINPRNGAL+1) /* number of Galileo satellites */

Definition at line 3825 of file data_sets.h.

◆ NSATGLO

#define NSATGLO   (MAXPRNGLO-MINPRNGLO+1) /* number of GLONASS satellites */

Definition at line 3814 of file data_sets.h.

◆ NSATGPS

#define NSATGPS   (MAXPRNGPS-MINPRNGPS+1) /* number of GPS satellites */

Definition at line 3808 of file data_sets.h.

◆ NSATIRN

#define NSATIRN   0

Definition at line 3867 of file data_sets.h.

◆ NSATLEO

#define NSATLEO   0

Definition at line 3878 of file data_sets.h.

◆ NSATQZS

#define NSATQZS   0

Definition at line 3845 of file data_sets.h.

◆ NSATSBS

#define NSATSBS   (MAXPRNSBS - MINPRNSBS + 1) /* number of SBAS satellites */

Definition at line 3791 of file data_sets.h.

◆ NSYS

#define NSYS   (NSYSGPS+NSYSGLO+NSYSGAL+NSYSQZS+NSYSCMP+NSYSIRN+NSYSLEO) /* number of systems */

Definition at line 3881 of file data_sets.h.

◆ NSYSCMP

#define NSYSCMP   0

Definition at line 3857 of file data_sets.h.

◆ NSYSGAL

#define NSYSGAL   1

Definition at line 3826 of file data_sets.h.

◆ NSYSGLO

#define NSYSGLO   1

Definition at line 3815 of file data_sets.h.

◆ NSYSGPS

#define NSYSGPS   1

Definition at line 3809 of file data_sets.h.

◆ NSYSIRN

#define NSYSIRN   0

Definition at line 3868 of file data_sets.h.

◆ NSYSLEO

#define NSYSLEO   0

Definition at line 3879 of file data_sets.h.

◆ NSYSQZS

#define NSYSQZS   0

Definition at line 3846 of file data_sets.h.

◆ NUM_ANA_CHANNELS

#define NUM_ANA_CHANNELS   4

Definition at line 1245 of file data_sets.h.

◆ NUM_COM_PORTS

#define NUM_COM_PORTS   4

Definition at line 1256 of file data_sets.h.

◆ NUM_IMU_DEVICES

#define NUM_IMU_DEVICES   2

Definition at line 164 of file data_sets.h.

◆ NUM_SERIAL_PORTS

#define NUM_SERIAL_PORTS   6

Definition at line 1258 of file data_sets.h.

◆ NUM_WIFI_PRESETS

#define NUM_WIFI_PRESETS   3

Definition at line 3121 of file data_sets.h.

◆ NUMSATSOL

#define NUMSATSOL   22

Definition at line 3776 of file data_sets.h.

◆ PROTOCOL_VERSION_CHAR2

#define PROTOCOL_VERSION_CHAR2   (0x000000FF&DID_COUNT)

Defines the 4 parts to the communications version. Major changes involve changes to the com manager. Minor changes involve additions to data structures

Definition at line 156 of file data_sets.h.

◆ PROTOCOL_VERSION_CHAR3

#define PROTOCOL_VERSION_CHAR3   8

Definition at line 157 of file data_sets.h.

◆ RECEIVER_INDEX_EXTERNAL_BASE

#define RECEIVER_INDEX_EXTERNAL_BASE   2

Definition at line 161 of file data_sets.h.

◆ RECEIVER_INDEX_GPS1

#define RECEIVER_INDEX_GPS1   1

Rtk rover receiver index

Definition at line 160 of file data_sets.h.

◆ RECEIVER_INDEX_GPS2

#define RECEIVER_INDEX_GPS2   3

Definition at line 162 of file data_sets.h.

◆ RMC_BITS_BAROMETER

#define RMC_BITS_BAROMETER   0x0000000000000040

Definition at line 1285 of file data_sets.h.

◆ RMC_BITS_DIAGNOSTIC_MESSAGE

#define RMC_BITS_DIAGNOSTIC_MESSAGE   0x0000000000040000

Definition at line 1297 of file data_sets.h.

◆ RMC_BITS_DUAL_IMU

#define RMC_BITS_DUAL_IMU   0x0000000000000010

Definition at line 1283 of file data_sets.h.

◆ RMC_BITS_DUAL_IMU_MAG

#define RMC_BITS_DUAL_IMU_MAG   0x0000000400000000

Definition at line 1312 of file data_sets.h.

◆ RMC_BITS_DUAL_IMU_MAG_RAW

#define RMC_BITS_DUAL_IMU_MAG_RAW   0x0000000200000000

Definition at line 1311 of file data_sets.h.

◆ RMC_BITS_DUAL_IMU_RAW

#define RMC_BITS_DUAL_IMU_RAW   0x0000000000080000

Definition at line 1298 of file data_sets.h.

◆ RMC_BITS_GPS1_POS

#define RMC_BITS_GPS1_POS   0x0000000000000400

Definition at line 1289 of file data_sets.h.

◆ RMC_BITS_GPS1_RAW

#define RMC_BITS_GPS1_RAW   0x0000000000001000

Definition at line 1291 of file data_sets.h.

◆ RMC_BITS_GPS1_RTK_HDG_MISC

#define RMC_BITS_GPS1_RTK_HDG_MISC   0x0000002000000000

Definition at line 1315 of file data_sets.h.

◆ RMC_BITS_GPS1_RTK_HDG_REL

#define RMC_BITS_GPS1_RTK_HDG_REL   0x0000001000000000

Definition at line 1314 of file data_sets.h.

◆ RMC_BITS_GPS1_RTK_POS

#define RMC_BITS_GPS1_RTK_POS   0x0000000000800000

Definition at line 1302 of file data_sets.h.

◆ RMC_BITS_GPS1_RTK_POS_MISC

#define RMC_BITS_GPS1_RTK_POS_MISC   0x0000000004000000

Definition at line 1304 of file data_sets.h.

◆ RMC_BITS_GPS1_RTK_POS_REL

#define RMC_BITS_GPS1_RTK_POS_REL   0x0000000001000000

Definition at line 1303 of file data_sets.h.

◆ RMC_BITS_GPS1_SAT

#define RMC_BITS_GPS1_SAT   0x0000000000004000

Definition at line 1293 of file data_sets.h.

◆ RMC_BITS_GPS1_UBX_POS

#define RMC_BITS_GPS1_UBX_POS   0x0000000000400000

Definition at line 1301 of file data_sets.h.

◆ RMC_BITS_GPS1_VEL

#define RMC_BITS_GPS1_VEL   0x0000000000100000

Definition at line 1299 of file data_sets.h.

◆ RMC_BITS_GPS2_POS

#define RMC_BITS_GPS2_POS   0x0000000000000800

Definition at line 1290 of file data_sets.h.

◆ RMC_BITS_GPS2_RAW

#define RMC_BITS_GPS2_RAW   0x0000000000002000

Definition at line 1292 of file data_sets.h.

◆ RMC_BITS_GPS2_SAT

#define RMC_BITS_GPS2_SAT   0x0000000000008000

Definition at line 1294 of file data_sets.h.

◆ RMC_BITS_GPS2_VEL

#define RMC_BITS_GPS2_VEL   0x0000000000200000

Definition at line 1300 of file data_sets.h.

◆ RMC_BITS_GPS_BASE_RAW

#define RMC_BITS_GPS_BASE_RAW   0x0000000000010000

Definition at line 1295 of file data_sets.h.

◆ RMC_BITS_INL2_NED_SIGMA

#define RMC_BITS_INL2_NED_SIGMA   0x0000000008000000

Definition at line 1305 of file data_sets.h.

◆ RMC_BITS_INS1

#define RMC_BITS_INS1   0x0000000000000001

Definition at line 1279 of file data_sets.h.

◆ RMC_BITS_INS2

#define RMC_BITS_INS2   0x0000000000000002

Definition at line 1280 of file data_sets.h.

◆ RMC_BITS_INS3

#define RMC_BITS_INS3   0x0000000000000004

Definition at line 1281 of file data_sets.h.

◆ RMC_BITS_INS4

#define RMC_BITS_INS4   0x0000000000000008

Definition at line 1282 of file data_sets.h.

◆ RMC_BITS_INTERNAL_PPD

#define RMC_BITS_INTERNAL_PPD   0x4000000000000000

Definition at line 1317 of file data_sets.h.

◆ RMC_BITS_MAGNETOMETER1

#define RMC_BITS_MAGNETOMETER1   0x0000000000000080

Definition at line 1286 of file data_sets.h.

◆ RMC_BITS_MAGNETOMETER2

#define RMC_BITS_MAGNETOMETER2   0x0000000000000100

Definition at line 1287 of file data_sets.h.

◆ RMC_BITS_MASK

#define RMC_BITS_MASK   0x0FFFFFFFFFFFFFFF

Definition at line 1316 of file data_sets.h.

◆ RMC_BITS_PREINTEGRATED_IMU

#define RMC_BITS_PREINTEGRATED_IMU   0x0000000000000020

Definition at line 1284 of file data_sets.h.

◆ RMC_BITS_PREINTEGRATED_IMU_MAG

#define RMC_BITS_PREINTEGRATED_IMU_MAG   0x0000000800000000

Definition at line 1313 of file data_sets.h.

◆ RMC_BITS_PRESET

#define RMC_BITS_PRESET   0x8000000000000000

Definition at line 1318 of file data_sets.h.

◆ RMC_BITS_RTK_CODE_RESIDUAL

#define RMC_BITS_RTK_CODE_RESIDUAL   0x0000000020000000

Definition at line 1307 of file data_sets.h.

◆ RMC_BITS_RTK_PHASE_RESIDUAL

#define RMC_BITS_RTK_PHASE_RESIDUAL   0x0000000040000000

Definition at line 1308 of file data_sets.h.

◆ RMC_BITS_RTK_STATE

#define RMC_BITS_RTK_STATE   0x0000000010000000

Definition at line 1306 of file data_sets.h.

◆ RMC_BITS_STROBE_IN_TIME

#define RMC_BITS_STROBE_IN_TIME   0x0000000000020000

Definition at line 1296 of file data_sets.h.

◆ RMC_BITS_WHEEL_CONFIG

#define RMC_BITS_WHEEL_CONFIG   0x0000000100000000

Definition at line 1310 of file data_sets.h.

◆ RMC_BITS_WHEEL_ENCODER

#define RMC_BITS_WHEEL_ENCODER   0x0000000080000000

Definition at line 1309 of file data_sets.h.

◆ RMC_OPTIONS_PERSISTENT

#define RMC_OPTIONS_PERSISTENT   0x00000200

Definition at line 1276 of file data_sets.h.

◆ RMC_OPTIONS_PORT_ALL

#define RMC_OPTIONS_PORT_ALL   (RMC_OPTIONS_PORT_MASK)

Definition at line 1269 of file data_sets.h.

◆ RMC_OPTIONS_PORT_CURRENT

#define RMC_OPTIONS_PORT_CURRENT   0x00000000

Definition at line 1270 of file data_sets.h.

◆ RMC_OPTIONS_PORT_MASK

#define RMC_OPTIONS_PORT_MASK   0x000000FF

Realtime Message Controller (used in rmc_t). The data sets available through RMC are broadcast at the availability of the data. A goal of RMC is to provide updates from each onboard sensor as fast as possible with minimal latency. The RMC is provided so that broadcast of sensor data is done as soon as it becomes available. The exception to this rule is the INS output data, which has a configurable output data rate according to DID_RMC.insPeriodMs.

Definition at line 1268 of file data_sets.h.

◆ RMC_OPTIONS_PORT_SER0

#define RMC_OPTIONS_PORT_SER0   0x00000001

Definition at line 1271 of file data_sets.h.

◆ RMC_OPTIONS_PORT_SER1

#define RMC_OPTIONS_PORT_SER1   0x00000002

Definition at line 1272 of file data_sets.h.

◆ RMC_OPTIONS_PORT_SER2

#define RMC_OPTIONS_PORT_SER2   0x00000004

Definition at line 1273 of file data_sets.h.

◆ RMC_OPTIONS_PORT_USB

#define RMC_OPTIONS_PORT_USB   0x00000008

Definition at line 1274 of file data_sets.h.

◆ RMC_OPTIONS_PRESERVE_CTRL

#define RMC_OPTIONS_PRESERVE_CTRL   0x00000100

Definition at line 1275 of file data_sets.h.

◆ RMC_PRESET_INS_BITS

#define RMC_PRESET_INS_BITS
Value:
#define RMC_BITS_GPS1_POS
Definition: data_sets.h:1289
#define RMC_BITS_PRESET
Definition: data_sets.h:1318
#define RMC_BITS_INS2
Definition: data_sets.h:1280

Definition at line 1342 of file data_sets.h.

◆ RMC_PRESET_INS_NAV_PERIOD_MULT

#define RMC_PRESET_INS_NAV_PERIOD_MULT   1

Definition at line 1321 of file data_sets.h.

◆ RMC_PRESET_PPD_BITS

#define RMC_PRESET_PPD_BITS
Value:
#define RMC_PRESET_PPD_BITS_NO_IMU
Definition: data_sets.h:1324
#define RMC_BITS_PREINTEGRATED_IMU
Definition: data_sets.h:1284

Definition at line 1340 of file data_sets.h.

◆ RMC_PRESET_PPD_BITS_NO_IMU

#define RMC_PRESET_PPD_BITS_NO_IMU
Value:
#define RMC_BITS_GPS1_POS
Definition: data_sets.h:1289
#define RMC_BITS_GPS1_RTK_POS_REL
Definition: data_sets.h:1303
#define RMC_BITS_GPS2_RAW
Definition: data_sets.h:1292
#define RMC_BITS_GPS1_RAW
Definition: data_sets.h:1291
#define RMC_BITS_GPS2_POS
Definition: data_sets.h:1290
#define RMC_BITS_GPS1_RTK_HDG_REL
Definition: data_sets.h:1314
#define RMC_BITS_GPS2_VEL
Definition: data_sets.h:1300
#define RMC_BITS_MAGNETOMETER2
Definition: data_sets.h:1287
#define RMC_BITS_GPS_BASE_RAW
Definition: data_sets.h:1295
#define RMC_BITS_PRESET
Definition: data_sets.h:1318
#define RMC_BITS_GPS1_VEL
Definition: data_sets.h:1299
#define RMC_BITS_MAGNETOMETER1
Definition: data_sets.h:1286
#define RMC_BITS_BAROMETER
Definition: data_sets.h:1285
#define RMC_BITS_INTERNAL_PPD
Definition: data_sets.h:1317
#define RMC_BITS_INS2
Definition: data_sets.h:1280
#define RMC_BITS_DIAGNOSTIC_MESSAGE
Definition: data_sets.h:1297

Definition at line 1324 of file data_sets.h.

◆ RMC_PRESET_PPD_BITS_RAW_IMU

#define RMC_PRESET_PPD_BITS_RAW_IMU
Value:
#define RMC_BITS_DUAL_IMU_RAW
Definition: data_sets.h:1298
#define RMC_PRESET_PPD_BITS_NO_IMU
Definition: data_sets.h:1324

Definition at line 1345 of file data_sets.h.

◆ RMC_PRESET_PPD_BITS_RTK_DBG

#define RMC_PRESET_PPD_BITS_RTK_DBG
Value:
#define RMC_BITS_RTK_STATE
Definition: data_sets.h:1306
#define RMC_BITS_RTK_PHASE_RESIDUAL
Definition: data_sets.h:1308
#define RMC_PRESET_PPD_BITS
Definition: data_sets.h:1340
#define RMC_BITS_RTK_CODE_RESIDUAL
Definition: data_sets.h:1307

Definition at line 1347 of file data_sets.h.

◆ RMC_PRESET_PPD_NAV_PERIOD_MULT

#define RMC_PRESET_PPD_NAV_PERIOD_MULT   25

Definition at line 1320 of file data_sets.h.

◆ RMC_PRESET_PPD_ROBOT

#define RMC_PRESET_PPD_ROBOT
Value:
#define RMC_BITS_WHEEL_CONFIG
Definition: data_sets.h:1310
#define RMC_BITS_WHEEL_ENCODER
Definition: data_sets.h:1309
#define RMC_PRESET_PPD_BITS
Definition: data_sets.h:1340

Definition at line 1351 of file data_sets.h.

◆ SBAS_EPHEMERIS_ARRAY_SIZE

#define SBAS_EPHEMERIS_ARRAY_SIZE   NSATSBS

Definition at line 3793 of file data_sets.h.

◆ SECONDS_PER_DAY

#define SECONDS_PER_DAY   86400

Definition at line 3689 of file data_sets.h.

◆ SECONDS_PER_WEEK

#define SECONDS_PER_WEEK   604800

Definition at line 3688 of file data_sets.h.

◆ SET_STATUS_OFFSET_MASK

#define SET_STATUS_OFFSET_MASK (   result,
  val,
  offset,
  mask 
)    { (result) &= ~((mask)<<(offset)); (result) |= ((val)<<(offset)); }

Definition at line 1833 of file data_sets.h.

◆ SYS_ALL

#define SYS_ALL   0xFF /* navigation system: all */

Definition at line 3720 of file data_sets.h.

◆ SYS_CFG_BITS_MAG_RECAL_MODE

#define SYS_CFG_BITS_MAG_RECAL_MODE (   sysCfgBits)    ((sysCfgBits&SYS_CFG_BITS_MAG_RECAL_MODE_MASK)>>SYS_CFG_BITS_MAG_RECAL_MODE_OFFSET)

Definition at line 1536 of file data_sets.h.

◆ SYS_CMP

#define SYS_CMP   0x20 /* navigation system: BeiDou */

Definition at line 3717 of file data_sets.h.

◆ SYS_FAULT_STATUS_BUS_FAULT

#define SYS_FAULT_STATUS_BUS_FAULT   0x00080000

Definition at line 3296 of file data_sets.h.

◆ SYS_FAULT_STATUS_ENABLE_BOOTLOADER

#define SYS_FAULT_STATUS_ENABLE_BOOTLOADER   0x00000002

Definition at line 3285 of file data_sets.h.

◆ SYS_FAULT_STATUS_FLASH_MIGRATION_COMPLETED

#define SYS_FAULT_STATUS_FLASH_MIGRATION_COMPLETED   0x00000040

Definition at line 3289 of file data_sets.h.

◆ SYS_FAULT_STATUS_FLASH_MIGRATION_EVENT

#define SYS_FAULT_STATUS_FLASH_MIGRATION_EVENT   0x00000020

Definition at line 3288 of file data_sets.h.

◆ SYS_FAULT_STATUS_FLASH_MIGRATION_MARKER_UPDATED

#define SYS_FAULT_STATUS_FLASH_MIGRATION_MARKER_UPDATED   0x00800000

Definition at line 3300 of file data_sets.h.

◆ SYS_FAULT_STATUS_HARD_FAULT

#define SYS_FAULT_STATUS_HARD_FAULT   0x00010000

Definition at line 3293 of file data_sets.h.

◆ SYS_FAULT_STATUS_HARDWARE_DETECTION

#define SYS_FAULT_STATUS_HARDWARE_DETECTION   0x08000000

Definition at line 3304 of file data_sets.h.

◆ SYS_FAULT_STATUS_HARDWARE_RESET

#define SYS_FAULT_STATUS_HARDWARE_RESET   0x00000000

(DID_SYS_FAULT) System Fault Information NOTE: If you modify these, please update crash_info_special_values in IS-src/python/src/ci_hdw/data_sets.py

Definition at line 3283 of file data_sets.h.

◆ SYS_FAULT_STATUS_INVALID_CODE_OPERATION

#define SYS_FAULT_STATUS_INVALID_CODE_OPERATION   0x00400000

Definition at line 3299 of file data_sets.h.

◆ SYS_FAULT_STATUS_MALLOC_FAILED

#define SYS_FAULT_STATUS_MALLOC_FAILED   0x00100000

Definition at line 3297 of file data_sets.h.

◆ SYS_FAULT_STATUS_MASK_CRITICAL_ERROR

#define SYS_FAULT_STATUS_MASK_CRITICAL_ERROR   0xFFFF0000

Definition at line 3305 of file data_sets.h.

◆ SYS_FAULT_STATUS_MASK_GENERAL_ERROR

#define SYS_FAULT_STATUS_MASK_GENERAL_ERROR   0xFFFFFFF0

Definition at line 3291 of file data_sets.h.

◆ SYS_FAULT_STATUS_MEM_MANGE

#define SYS_FAULT_STATUS_MEM_MANGE   0x00040000

Definition at line 3295 of file data_sets.h.

◆ SYS_FAULT_STATUS_RTK_BUFFER_LIMIT

#define SYS_FAULT_STATUS_RTK_BUFFER_LIMIT   0x02000000

Definition at line 3302 of file data_sets.h.

◆ SYS_FAULT_STATUS_RTK_MISC_ERROR

#define SYS_FAULT_STATUS_RTK_MISC_ERROR   0x00000080

Definition at line 3290 of file data_sets.h.

◆ SYS_FAULT_STATUS_SENSOR_CALIBRATION

#define SYS_FAULT_STATUS_SENSOR_CALIBRATION   0x04000000

Definition at line 3303 of file data_sets.h.

◆ SYS_FAULT_STATUS_SOFT_RESET

#define SYS_FAULT_STATUS_SOFT_RESET   0x00000010

Definition at line 3287 of file data_sets.h.

◆ SYS_FAULT_STATUS_STACK_OVERFLOW

#define SYS_FAULT_STATUS_STACK_OVERFLOW   0x00200000

Definition at line 3298 of file data_sets.h.

◆ SYS_FAULT_STATUS_USAGE_FAULT

#define SYS_FAULT_STATUS_USAGE_FAULT   0x00020000

Definition at line 3294 of file data_sets.h.

◆ SYS_FAULT_STATUS_USER_RESET

#define SYS_FAULT_STATUS_USER_RESET   0x00000001

Definition at line 3284 of file data_sets.h.

◆ SYS_FAULT_STATUS_WATCHDOG_RESET

#define SYS_FAULT_STATUS_WATCHDOG_RESET   0x01000000

Definition at line 3301 of file data_sets.h.

◆ SYS_GAL

#define SYS_GAL   0x08 /* navigation system: Galileo */

Definition at line 3715 of file data_sets.h.

◆ SYS_GLO

#define SYS_GLO   0x04 /* navigation system: GLONASS */

Definition at line 3714 of file data_sets.h.

◆ SYS_GPS

#define SYS_GPS   0x01 /* navigation system: GPS */

Definition at line 3712 of file data_sets.h.

◆ SYS_IRN

#define SYS_IRN   0x40 /* navigation system: IRNS */

Definition at line 3718 of file data_sets.h.

◆ SYS_LEO

#define SYS_LEO   0x80 /* navigation system: LEO */

Definition at line 3719 of file data_sets.h.

◆ SYS_NONE

#define SYS_NONE   0x00 /* navigation system: none */

Definition at line 3711 of file data_sets.h.

◆ SYS_QZS

#define SYS_QZS   0x10 /* navigation system: QZSS */

Definition at line 3716 of file data_sets.h.

◆ SYS_SBS

#define SYS_SBS   0x02 /* navigation system: SBAS */

Definition at line 3713 of file data_sets.h.

◆ WIFI_SSID_PSK_SIZE

#define WIFI_SSID_PSK_SIZE   40

Definition at line 3085 of file data_sets.h.

Typedef Documentation

◆ ascii_msgs_t

typedef struct PACKED ascii_msgs_t

(DID_ASCII_BCAST_PERIOD) ASCII broadcast periods. This data structure (when it is included in the sCommData struct) is zeroed out on stop_all_broadcasts

◆ ascii_msgs_u32_t

typedef struct PACKED ascii_msgs_u32_t

(DID_ASCII_BCAST_PERIOD) ASCII broadcast periods. This data structure (when it is included in the sCommData struct) is zeroed out on stop_all_broadcasts

◆ barometer_t

typedef struct PACKED barometer_t

(DID_BAROMETER) Barometric pressure sensor data

◆ bit_t

typedef struct PACKED bit_t

(DID_BIT) Built-in self-test parameters

◆ can_config_t

typedef struct PACKED can_config_t

(DID_CAN_BCAST_PERIOD) Broadcast period of CAN messages

◆ debug_array_t

typedef struct PACKED debug_array_t

◆ debug_string_t

typedef struct PACKED debug_string_t

◆ dev_info_t

typedef struct PACKED dev_info_t

(DID_DEV_INFO) Device information

◆ dual_imu_ok_t

typedef struct PACKED dual_imu_ok_t

Dual Inertial Measurement Units (IMUs) data valid flags

◆ dual_imu_t

typedef struct PACKED dual_imu_t

(DID_DUAL_IMU) Dual Inertial Measurement Units (IMUs) data

◆ eDataIDs

typedef uint32_t eDataIDs

Data identifiers - these are unsigned int and #define because enum are signed according to C standard

Definition at line 32 of file data_sets.h.

◆ evb_rtos_info_t

typedef struct PACKED evb_rtos_info_t

(DID_EVB_RTOS_INFO)

◆ gen_1axis_sensor_t

typedef struct PACKED gen_1axis_sensor_t

Generic 1 axis sensor

◆ gen_3axis_sensor_t

typedef struct PACKED gen_3axis_sensor_t

Generic 3 axis sensor

◆ gen_3axis_sensord_t

typedef struct PACKED gen_3axis_sensord_t

Generic 3 axis sensor

◆ gen_dual_3axis_sensor_t

Generic dual 3 axis sensor

◆ gps_pos_t

typedef struct PACKED gps_pos_t

(DID_GPS1_POS, DID_GPS1_UBX_POS, DID_GPS2_POS) GPS position data

◆ gps_raw_t

typedef struct PACKED gps_raw_t

Message wrapper for DID_GPS1_RAW, DID_GPS2_RAW, and DID_GPS_BASE_RAW. The contents of data can vary for this message and are determined by dataType field.

◆ gps_rtk_misc_t

typedef struct PACKED gps_rtk_misc_t

(DID_GPS1_RTK_POS_MISC, DID_GPS2_RTK_CMP_MISC) - requires little endian CPU

◆ gps_rtk_opt_t

Definition at line 2375 of file data_sets.h.

◆ gps_rtk_rel_t

typedef struct PACKED gps_rtk_rel_t

(DID_GPS1_RTK_POS_REL, DID_GPS2_RTK_CMP_REL) - RTK and Dual GNSS heading base to rover relative info.

◆ gps_sat_sv_t

typedef struct PACKED gps_sat_sv_t

GPS Satellite information

◆ gps_sat_t

typedef struct PACKED gps_sat_t

(DID_GPS1_SAT) GPS satellite signal strength

◆ gps_vel_t

typedef struct PACKED gps_vel_t

(DID_GPS1_VEL, DID_GPS2_VEL) GPS velocity data

◆ gps_version_t

typedef struct PACKED gps_version_t

(DID_GPS1_VERSION) GPS version strings

◆ imu_mag_t

typedef struct PACKED imu_mag_t

DID_DUAL_IMU_RAW_MAG, DID_DUAL_IMU_MAG, dual imu + mag1 + mag2

◆ imu_t

typedef struct PACKED imu_t

Inertial Measurement Unit (IMU) data

◆ imus_t

typedef struct PACKED imus_t

Inertial Measurement Unit (IMU) data

◆ inl2_mag_obs_info_t

typedef struct PACKED inl2_mag_obs_info_t

◆ inl2_ned_sigma_t

typedef struct PACKED inl2_ned_sigma_t

INL2 - Estimate error variances

◆ inl2_states_t

typedef struct PACKED inl2_states_t

◆ inl2_status_t

typedef struct PACKED inl2_status_t

◆ ins_1_t

typedef struct PACKED ins_1_t

(DID_INS_1) INS output: euler rotation w/ respect to NED, NED position from reference LLA

◆ ins_2_t

typedef struct PACKED ins_2_t

(DID_INS_2) INS output: quaternion rotation w/ respect to NED, ellipsoid altitude

◆ ins_3_t

typedef struct PACKED ins_3_t

(DID_INS_3) INS output: quaternion rotation w/ respect to NED, msl altitude

◆ ins_4_t

typedef struct PACKED ins_4_t

(DID_INS_4) INS output: quaternion rotation w/ respect to ECEF, ECEF position

◆ ins_output_t

typedef struct PACKED ins_output_t

INS output

◆ io_t

typedef struct PACKED io_t

(DID_IO) Input/Output

◆ mag_cal_t

typedef struct PACKED mag_cal_t

(DID_MAG_CAL) Magnetometer Calibration

◆ magnetometer_t

typedef struct PACKED magnetometer_t

(DID_MAGNETOMETER_1, DID_MAGNETOMETER_2) Magnetometer sensor data

◆ manufacturing_info_t

typedef struct PACKED manufacturing_info_t

(DID_MANUFACTURING_INFO) Manufacturing info

◆ nvm_flash_cfg_t

typedef struct PACKED nvm_flash_cfg_t

(DID_FLASH_CONFIG) Configuration data IMPORTANT! These fields should not be deleted, they can be deprecated and marked as reserved, or new fields added to the end.

◆ obsd_t

typedef struct PACKED obsd_t

Raw satellite observation data

◆ pimu_mag_t

typedef struct PACKED pimu_mag_t

DID DID_PREINTEGRATED_IMU_MAG, dual pre-integrated imu + mag1 + mag2

◆ pos_measurement_t

(DID_POSITION_MEASUREMENT) External position estimate

◆ preintegrated_imu_t

typedef struct PACKED preintegrated_imu_t

(DID_PREINTEGRATED_IMU) Coning and sculling integral in body/IMU frame.

◆ rmc_t

typedef struct PACKED rmc_t

(DID_RMC) Realtime message controller (RMC).

◆ rtk_debug_t

typedef struct PACKED rtk_debug_t

◆ rtk_residual_t

typedef struct PACKED rtk_residual_t

◆ rtk_state_t

typedef struct PACKED rtk_state_t

◆ rtos_info_t

typedef struct PACKED rtos_info_t

(DID_RTOS_INFO)

◆ rtos_task_t

typedef struct PACKED rtos_task_t

RTOS task info

◆ sensors_mpu_w_temp_t

typedef struct PACKED sensors_mpu_w_temp_t

◆ strobe_in_time_t

typedef struct PACKED strobe_in_time_t

(DID_STROBE_IN_TIME) Timestamp for input strobe.

◆ sys_params_t

typedef struct PACKED sys_params_t

(DID_SYS_PARAMS) System parameters

◆ sys_sensors_adc_t

typedef struct PACKED sys_sensors_adc_t

◆ sys_sensors_t

typedef struct PACKED sys_sensors_t

(DID_SYS_SENSORS) Output from system sensors

◆ system_command_t

typedef struct PACKED system_command_t

(DID_SYS_CMD) System Commands

◆ uDatasets

typedef union PACKED uDatasets

Union of datasets

◆ uGpsRawData

typedef union PACKED uGpsRawData

◆ uInsOutDatasets

typedef union PACKED uInsOutDatasets

Union of INS output datasets

◆ wheel_config_t

typedef struct PACKED wheel_config_t

(DID_WHEEL_CONFIG) [NOT SUPPORTED, INTERNAL USE ONLY] Configuration of wheel encoders and kinematic constraints.

◆ wheel_encoder_t

typedef struct PACKED wheel_encoder_t

(DID_WHEEL_ENCODER) [NOT SUPPORTED, INTERNAL USE ONLY] Message to communicate wheel encoder measurements to GPS-INS

Enumeration Type Documentation

◆ anonymous enum

anonymous enum
Enumerator
CID_INS_TIME 
CID_INS_STATUS 
CID_INS_EULER 
CID_INS_QUATN2B 
CID_INS_QUATE2B 
CID_INS_UVW 
CID_INS_VE 
CID_INS_LAT 
CID_INS_LON 
CID_INS_ALT 
CID_INS_NORTH_EAST 
CID_INS_DOWN 
CID_INS_ECEF_X 
CID_INS_ECEF_Y 
CID_INS_ECEF_Z 
CID_INS_MSL 
CID_PREINT_PX 
CID_PREINT_QY 
CID_PREINT_RZ 
CID_DUAL_PX 
CID_DUAL_QY 
CID_DUAL_RZ 
CID_GPS1_POS 
CID_GPS1_RTK_REL 
CID_ROLL_ROLLRATE 
NUM_CIDS 

Definition at line 3477 of file data_sets.h.

◆ eBitState

enum eBitState

Built-in test state

Enumerator
BIT_STATE_OFF 
BIT_STATE_DONE 
BIT_STATE_CMD_FULL_STATIONARY 
BIT_STATE_CMD_BASIC_MOVING 
BIT_STATE_RESERVED_1 
BIT_STATE_RESERVED_2 
BIT_STATE_RUNNING 
BIT_STATE_FINISH 
BIT_STATE_COMMAND_OFF 

Definition at line 1420 of file data_sets.h.

◆ eCalBitStatusFlags

Calibration built-in test flags

Enumerator
CAL_BIT_PASSED_MASK 
CAL_BIT_PASSED_ALL 
CAL_BIT_MODE_MASK 
CAL_BIT_MODE_OFFSET 
CAL_BIT_FAILED_MASK 
CAL_BIT_FAULT_TCAL_EMPTY 
CAL_BIT_FAULT_TCAL_TSPAN 
CAL_BIT_FAULT_TCAL_INCONSISTENT 
CAL_BIT_FAULT_TCAL_CORRUPT 
CAL_BIT_FAULT_TCAL_PQR_BIAS 
CAL_BIT_FAULT_TCAL_PQR_SLOPE 
CAL_BIT_FAULT_TCAL_PQR_LIN 
CAL_BIT_FAULT_TCAL_ACC_BIAS 
CAL_BIT_FAULT_TCAL_ACC_SLOPE 
CAL_BIT_FAULT_TCAL_ACC_LIN 
CAL_BIT_FAULT_CAL_SERIAL_NUM 
CAL_BIT_FAULT_ORTO_EMPTY 
CAL_BIT_FAULT_ORTO_INVALID 
CAL_BIT_FAULT_MOTION_PQR 
CAL_BIT_FAULT_MOTION_ACC 

Definition at line 1455 of file data_sets.h.

◆ eEvb2ComBridgeOptions

EVB-2 Communications Bridge Options

Enumerator
EVB2_CB_OPTIONS_TRISTATE_UINS_IO 
EVB2_CB_OPTIONS_SP330_RS422 
EVB2_CB_OPTIONS_XBEE_ENABLE 
EVB2_CB_OPTIONS_WIFI_ENABLE 
EVB2_CB_OPTIONS_BLE_ENABLE 
EVB2_CB_OPTIONS_SPI_ENABLE 
EVB2_CB_OPTIONS_CAN_ENABLE 
EVB2_CB_OPTIONS_I2C_ENABLE 

Definition at line 3036 of file data_sets.h.

◆ eEvb2ComBridgePreset

EVB-2 communications bridge configuration.

Enumerator
EVB2_CB_PRESET_NA 

No change. Sending this value causes no effect.

EVB2_CB_PRESET_ALL_OFF 

No connections. Off: XBee, WiFi

EVB2_CB_PRESET_RS232 

[uINS Hub] LED-GRN (uINS-COM): USB, RS232, H8. (uINS-AUX): XRadio. Off: XBee, WiFi

EVB2_CB_PRESET_RS232_XBEE 

[uINS Hub] LED-BLU (uINS-COM): USB, RS232, H8. (uINS-AUX): XBee, XRadio. Off: WiFi

EVB2_CB_PRESET_RS422_WIFI 

[uINS Hub] LED-PUR (uINS-COM): USB, RS422, H8. (uINS-AUX): WiFi, XRadio. Off: XBee

EVB2_CB_PRESET_SPI_RS232 

[uINS Hub] LED-CYA (uINS-SER1 SPI): USB, RS423, H8. Off: WiFi, XBee

EVB2_CB_PRESET_USB_HUB_RS232 

[USB Hub] LED-YEL (USB): RS232, H8, XBee, XRadio.

EVB2_CB_PRESET_USB_HUB_RS422 

[USB Hub] LED-WHT (USB): RS485/RS422, H8, XRadio.

EVB2_CB_PRESET_COUNT 

Number of bridge configuration presets

Definition at line 3205 of file data_sets.h.

◆ eEvb2CommPorts

EVB-2 communications ports.

Enumerator
EVB2_PORT_UINS0 
EVB2_PORT_UINS1 
EVB2_PORT_XBEE 
EVB2_PORT_XRADIO 
EVB2_PORT_BLE 
EVB2_PORT_SP330 
EVB2_PORT_GPIO_H8 
EVB2_PORT_USB 
EVB2_PORT_WIFI 
EVB2_PORT_CAN 
EVB2_PORT_COUNT 

Definition at line 3020 of file data_sets.h.

◆ eEvb2LoggerMode

Data logger control. Values labeled CMD

Enumerator
EVB2_LOG_NA 

Do not change. Sending this value causes no effect.

EVB2_LOG_CMD_START 

Start new log

EVB2_LOG_CMD_STOP 

Stop logging

EVB2_LOG_CMD_PURGE 

Purge all data logs from drive

Definition at line 3239 of file data_sets.h.

◆ eEvb2PortOptions

Enumerator
EVB2_PORT_OPTIONS_RADIO_RTK_FILTER 
EVB2_PORT_OPTIONS_DEFAULT 

Definition at line 3048 of file data_sets.h.

◆ eEvbFlashCfgBits

Enumerator
EVB_CFG_BITS_WIFI_SELECT_MASK 
EVB_CFG_BITS_WIFI_SELECT_OFFSET 
EVB_CFG_BITS_SERVER_SELECT_MASK 
EVB_CFG_BITS_SERVER_SELECT_OFFSET 
EVB_CFG_BITS_NO_STREAM_PPD_ON_LOG_BUTTON 
EVB_CFG_BITS_ENABLE_WHEEL_ENCODER 
EVB_CFG_BITS_ENABLE_ADC 

Definition at line 3110 of file data_sets.h.

◆ eEvbRtosTask

EVB RTOS tasks

Enumerator
EVB_TASK_COMMUNICATIONS 

Task 0: Communications

EVB_TASK_LOGGER 

Task 1: Logger

EVB_TASK_WIFI 

Task 2: WiFi

EVB_TASK_MAINTENANCE 

Task 3: Maintenance

EVB_TASK_IDLE 

Task 4: Idle

EVB_TASK_TIMER 

Task 5: Timer

EVB_TASK_SPI_UINS_COM 

Task 6: SPI to uINS

EVB_RTOS_NUM_TASKS 

Number of RTOS tasks

Definition at line 3380 of file data_sets.h.

◆ eEvbStatus

enum eEvbStatus
Enumerator
EVB_STATUS_SD_CARD_READY 

SD card logger: card ready

EVB_STATUS_SD_LOG_ENABLED 

SD card Logger: running

EVB_STATUS_SD_ERR_CARD_FAULT 

SD card error: card file system

EVB_STATUS_SD_ERR_CARD_FULL 

SD card error: card full

EVB_STATUS_SD_ERR_CARD_MASK 

SD card error: mask

EVB_STATUS_WIFI_ENABLED 

WiFi: enabled

EVB_STATUS_WIFI_CONNECTED 

WiFi: connected to access point (hot spot) or another device

EVB_STATUS_XBEE_ENABLED 

XBee: enabled

EVB_STATUS_XBEE_CONNECTED 

XBee: connected

EVB_STATUS_XBEE_CONFIGURED 

XBee: configured

EVB_STATUS_XBEE_CONFIG_FAILURE 

XBee: failed to configure

Definition at line 2982 of file data_sets.h.

◆ eGenFaultCodes

General Fault Code descriptor

Enumerator
GFC_INS_STATE_ORUN_UVW 

INS state limit overrun - UVW

GFC_INS_STATE_ORUN_LAT 

INS state limit overrun - Latitude

GFC_INS_STATE_ORUN_ALT 

INS state limit overrun - Altitude

GFC_UNHANDLED_INTERRUPT 

Unhandled interrupt

GFC_INIT_SENSORS 

Fault: sensor initialization

GFC_INIT_SPI 

Fault: SPI initialization

GFC_CONFIG_SPI 

Fault: SPI configuration

GFC_INIT_GPS1 

Fault: GPS1 init

GFC_INIT_GPS2 

Fault: GPS2 init

GFC_FLASH_INVALID_VALUES 

Flash failed to load valid values

GFC_FLASH_CHECKSUM_FAILURE 

Flash checksum failure

GFC_FLASH_WRITE_FAILURE 

Flash write failure

GFC_SYS_FAULT_GENERAL 

System Fault: general

GFC_SYS_FAULT_CRITICAL 

System Fault: CRITICAL system fault (see DID_SYS_FAULT)

GFC_SENSOR_SATURATION 

Sensor(s) saturated

Definition at line 1083 of file data_sets.h.

◆ eGnssSatSigConst

GNSS satellite system signal constellation (used with DID_FLASH_CONFIG.gnssSatSigConst)

Enumerator
GNSS_SAT_SIG_CONST_GPS 

GPS

GNSS_SAT_SIG_CONST_QZSS 

QZSS

GNSS_SAT_SIG_CONST_GAL 

Galileo

GNSS_SAT_SIG_CONST_BDS 

BeiDou

GNSS_SAT_SIG_CONST_GLO 

GLONASS

GNSS_SAT_SIG_CONST_SBAS 

SBAS

GNSS_SAT_SIG_CONST_DEFAULT 

GNSS default

Definition at line 1561 of file data_sets.h.

◆ eGpsNavFixStatus

GPS navigation fix type

Enumerator
GPS_NAV_FIX_NONE 
GPS_NAV_FIX_POSITIONING_3D 
GPS_NAV_FIX_POSITIONING_RTK_FLOAT 
GPS_NAV_FIX_POSITIONING_RTK_FIX 

Definition at line 268 of file data_sets.h.

◆ eGpsStatus

enum eGpsStatus

GPS Status

Enumerator
GPS_STATUS_NUM_SATS_USED_MASK 
GPS_STATUS_FIX_NONE 

Fix

GPS_STATUS_FIX_DEAD_RECKONING_ONLY 
GPS_STATUS_FIX_2D 
GPS_STATUS_FIX_3D 
GPS_STATUS_FIX_GPS_PLUS_DEAD_RECK 
GPS_STATUS_FIX_TIME_ONLY 
GPS_STATUS_FIX_UNUSED1 
GPS_STATUS_FIX_UNUSED2 
GPS_STATUS_FIX_DGPS 
GPS_STATUS_FIX_SBAS 
GPS_STATUS_FIX_RTK_SINGLE 
GPS_STATUS_FIX_RTK_FLOAT 
GPS_STATUS_FIX_RTK_FIX 
GPS_STATUS_FIX_MASK 
GPS_STATUS_FIX_BIT_OFFSET 
GPS_STATUS_FLAGS_FIX_OK 

Flags

GPS_STATUS_FLAGS_DGPS_USED 
GPS_STATUS_FLAGS_RTK_FIX_AND_HOLD 
GPS_STATUS_FLAGS_RTK_POSITION_ENABLED 
GPS_STATUS_FLAGS_STATIC_MODE 
GPS_STATUS_FLAGS_RTK_COMPASSING_ENABLED 
GPS_STATUS_FLAGS_RTK_RAW_GPS_DATA_ERROR 
GPS_STATUS_FLAGS_RTK_BASE_DATA_MISSING 
GPS_STATUS_FLAGS_RTK_BASE_POSITION_MOVING 
GPS_STATUS_FLAGS_RTK_BASE_POSITION_INVALID 
GPS_STATUS_FLAGS_RTK_BASE_POSITION_MASK 
GPS_STATUS_FLAGS_ERROR_MASK 
GPS_STATUS_FLAGS_RTK_POSITION_VALID 
GPS_STATUS_FLAGS_RTK_COMPASSING_VALID 
GPS_STATUS_FLAGS_RTK_COMPASSING_BASELINE_BAD 
GPS_STATUS_FLAGS_RTK_COMPASSING_BASELINE_UNSET 
GPS_STATUS_FLAGS_RTK_COMPASSING_MASK 
GPS_STATUS_FLAGS_GPS_NMEA_DATA 
GPS_STATUS_FLAGS_MASK 
GPS_STATUS_FLAGS_BIT_OFFSET 

Definition at line 360 of file data_sets.h.

◆ eHdwBitStatusFlags

Hardware built-in test flags

Enumerator
HDW_BIT_PASSED_MASK 
HDW_BIT_PASSED_ALL 
HDW_BIT_PASSED_NO_GPS 
HDW_BIT_MODE_MASK 
HDW_BIT_MODE_OFFSET 
HDW_BIT_FAILED_MASK 
HDW_BIT_FAILED_AHRS_MASK 
HDW_BIT_FAULT_NOISE_PQR 
HDW_BIT_FAULT_NOISE_ACC 
HDW_BIT_FAULT_MAGNETOMETER 
HDW_BIT_FAULT_BAROMETER 
HDW_BIT_FAULT_GPS_NO_COM 
HDW_BIT_FAULT_GPS_POOR_CNO 
HDW_BIT_FAULT_GPS_POOR_ACCURACY 
HDW_BIT_FAULT_GPS_NOISE 

Definition at line 1434 of file data_sets.h.

◆ eHdwStatusFlags

Hardware status flags

Enumerator
HDW_STATUS_MOTION_GYR_SIG 

Gyro motion detected sigma

HDW_STATUS_MOTION_ACC_SIG 

Accelerometer motion detected sigma

HDW_STATUS_MOTION_SIG_MASK 

Unit is moving and NOT stationary

HDW_STATUS_MOTION_GYR_DEV 

Gyro motion detected deviation

HDW_STATUS_MOTION_ACC_DEV 

Accelerometer motion detected deviation

HDW_STATUS_MOTION_MASK 

Motion mask

HDW_STATUS_GPS_SATELLITE_RX 

GPS satellite signals are being received (antenna and cable are good)

HDW_STATUS_STROBE_IN_EVENT 

Event occurred on strobe input pin

HDW_STATUS_GPS_TIME_OF_WEEK_VALID 

GPS time of week is valid and reported. Otherwise the timeOfWeek is local system time.

HDW_STATUS_UNUSED_1 
HDW_STATUS_SATURATION_GYR 

Sensor saturation on gyro

HDW_STATUS_SATURATION_ACC 

Sensor saturation on accelerometer

HDW_STATUS_SATURATION_MAG 

Sensor saturation on magnetometer

HDW_STATUS_SATURATION_BARO 

Sensor saturation on barometric pressure

HDW_STATUS_SATURATION_MASK 

Sensor saturation mask

HDW_STATUS_SATURATION_OFFSET 

Sensor saturation offset

HDW_STATUS_SYSTEM_RESET_REQUIRED 

System Reset is Required for proper function

HDW_STATUS_UNUSED_3 
HDW_STATUS_UNUSED_4 
HDW_STATUS_UNUSED_5 
HDW_STATUS_ERR_COM_TX_LIMITED 

Communications Tx buffer limited

HDW_STATUS_ERR_COM_RX_OVERRUN 

Communications Rx buffer overrun

HDW_STATUS_COM_PARSE_ERR_COUNT_MASK 

Communications parse error count

HDW_STATUS_COM_PARSE_ERR_COUNT_OFFSET 
HDW_STATUS_BIT_FAULT 

Built-in self-test failure

HDW_STATUS_ERR_TEMPERATURE 

Temperature outside spec'd operating range

HDW_STATUS_UNUSED_6 

Vibrations effecting accuracy

HDW_STATUS_FAULT_RESET_MASK 

Fault reset cause

HDW_STATUS_FAULT_RESET_BACKUP_MODE 

Reset from Backup mode (low-power state w/ CPU off)

HDW_STATUS_FAULT_RESET_WATCHDOG 

Reset from Watchdog

HDW_STATUS_FAULT_RESET_SOFT 

Reset from Software

HDW_STATUS_FAULT_RESET_HDW 

Reset from Hardware (NRST pin low)

HDW_STATUS_FAULT_SYS_CRITICAL 

Critical System Fault - CPU error

HDW_STATUS_OUTPUT_RESET_MASK 

Output reset mask - these bits are cleared on output

Definition at line 277 of file data_sets.h.

◆ eImuStatus

enum eImuStatus

IMU Status

Enumerator
IMU_STATUS_SATURATION_IMU1_GYR 

Sensor saturation on IMU1 gyro

IMU_STATUS_SATURATION_IMU2_GYR 

Sensor saturation on IMU2 gyro

IMU_STATUS_SATURATION_IMU1_ACC 

Sensor saturation on IMU1 accelerometer

IMU_STATUS_SATURATION_IMU2_ACC 

Sensor saturation on IMU2 accelerometer

IMU_STATUS_RESERVED1 

Reserved

IMU_STATUS_RESERVED2 

Reserved

Definition at line 730 of file data_sets.h.

◆ eInsDynModel

Enumerator
DYN_PORTABLE 
DYN_STATIONARY 
DYN_PEDESTRIAN 
DYN_AUTOMOTIVE 
DYN_MARINE 
DYN_AIRBORNE_1G 
DYN_AIRBORNE_2G 
DYN_AIRBORNE_4G 
DYN_WRIST 

Definition at line 1941 of file data_sets.h.

◆ eInsStatusFlags

INS status flags

Enumerator
INS_STATUS_ATT_ALIGN_COARSE 

Attitude estimate is usable but outside spec (COARSE)

INS_STATUS_VEL_ALIGN_COARSE 

Velocity estimate is usable but outside spec (COARSE)

INS_STATUS_POS_ALIGN_COARSE 

Position estimate is usable but outside spec (COARSE)

INS_STATUS_ALIGN_COARSE_MASK 

Estimate is COARSE mask (usable but outside spec)

INS_STATUS_UNUSED_1 
INS_STATUS_ATT_ALIGN_FINE 

Attitude estimate is within spec (FINE)

INS_STATUS_VEL_ALIGN_FINE 

Velocity estimate is within spec (FINE)

INS_STATUS_POS_ALIGN_FINE 

Position estimate is within spec (FINE)

INS_STATUS_ALIGN_FINE_MASK 

Estimate is FINE mask

INS_STATUS_GPS_AIDING_HEADING 

Heading aided by GPS

INS_STATUS_GPS_AIDING_POS_VEL 

Position and velocity aided by GPS

INS_STATUS_GPS_UPDATE_IN_SOLUTION 

GPS update event occurred in solution, potentially causing discontinuity in position path

INS_STATUS_RESERVED_1 

Reserved for internal purpose

INS_STATUS_MAG_AIDING_HEADING 

Heading aided by magnetic heading

INS_STATUS_NAV_MODE 

Nav mode (set) = estimating velocity and position. AHRS mode (cleared) = NOT estimating velocity and position

INS_STATUS_DO_NOT_MOVE 

User should not move (keep system motionless) to assist on-board processing.

INS_STATUS_UNUSED_3 
INS_STATUS_UNUSED_4 
INS_STATUS_SOLUTION_MASK 

INS/AHRS Solution Status

INS_STATUS_SOLUTION_OFFSET 
INS_STATUS_SOLUTION_OFF 
INS_STATUS_SOLUTION_ALIGNING 
INS_STATUS_SOLUTION_ALIGNMENT_COMPLETE 
INS_STATUS_SOLUTION_NAV 
INS_STATUS_SOLUTION_NAV_HIGH_VARIANCE 
INS_STATUS_SOLUTION_AHRS 
INS_STATUS_SOLUTION_AHRS_HIGH_VARIANCE 
INS_STATUS_RTK_COMPASSING_BASELINE_UNSET 

GPS compassing antenna offsets are not set in flashCfg.

INS_STATUS_RTK_COMPASSING_BASELINE_BAD 

GPS antenna baseline specified in flashCfg and measured by GPS do not match.

INS_STATUS_RTK_COMPASSING_MASK 
INS_STATUS_MAG_RECALIBRATING 

Magnetometer is being recalibrated. Device requires rotation to complete the calibration process.

INS_STATUS_MAG_INTERFERENCE_OR_BAD_CAL 

Magnetometer is experiencing interference or calibration is bad. Attention may be required to remove interference (move the device) or recalibrate the magnetometer.

INS_STATUS_GPS_NAV_FIX_MASK 

GPS navigation fix type (see eGpsNavFixStatus)

INS_STATUS_GPS_NAV_FIX_OFFSET 
INS_STATUS_RTK_COMPASSING_VALID 

RTK compassing heading is accurate. (RTK fix and hold status)

INS_STATUS_RTK_RAW_GPS_DATA_ERROR 

RTK error: Observations invalid or not received (i.e. RTK differential corrections)

INS_STATUS_RTK_ERR_BASE_DATA_MISSING 

RTK error: Either base observations or antenna position have not been received

INS_STATUS_RTK_ERR_BASE_POSITION_MOVING 

RTK error: base position moved when it should be stationary

INS_STATUS_RTK_ERR_BASE_POSITION_INVALID 

RTK error: base position invalid or not surveyed

INS_STATUS_RTK_ERR_BASE_MASK 

RTK error: NO base position received

INS_STATUS_RTK_ERROR_MASK 

GPS base mask

INS_STATUS_RTOS_TASK_PERIOD_OVERRUN 

RTOS task ran longer than allotted period

INS_STATUS_GENERAL_FAULT 

General fault (eGenFaultCodes)

INS_STATUS_OUTPUT_RESET_MASK 

Output reset mask - these bits are cleared on output

Definition at line 167 of file data_sets.h.

◆ eIoConfig

enum eIoConfig

IO configuration (used with DID_FLASH_CONFIG.ioConfig)

Enumerator
IO_CONFIG_INPUT_STROBE_TRIGGER_HIGH 

Input strobe trigger on rising edge (0 = falling edge)

IO_CONFIG_INPUT_STROBE_G2_ENABLE 

Input strobe - enable on G2

IO_CONFIG_INPUT_STROBE_G5_ENABLE 

Input strobe - enable on G5

IO_CONFIG_INPUT_STROBE_G8_ENABLE 

Input strobe - enable on G8

IO_CONFIG_INPUT_STROBE_G9_ENABLE 

Input strobe - enable on G9

IO_CONFIG_OUTPUT_STROBE_NAV_G9_ENABLE 

Output strobe - enable Nav update strobe output pulse on G9 (uINS pin 10) indicating preintegrated IMU and nav updates

IO_CFG_GPS_TIMEPUSE_SOURCE_BITMASK 

External GPS TIMEPULSE source

IO_CFG_GPS_TIMEPUSE_SOURCE_OFFSET 

0 = internal, 1 = disabled, 2 = G2_PIN6, 3 = G5_PIN9, 4 = G8_PIN12, 5 = G9_PIN13

IO_CFG_GPS_TIMEPUSE_SOURCE_MASK 
IO_CFG_GPS_TIMEPUSE_SOURCE_DISABLED 
IO_CFG_GPS_TIMEPUSE_SOURCE_ONBOARD_1 
IO_CFG_GPS_TIMEPUSE_SOURCE_ONBOARD_2 
IO_CFG_GPS_TIMEPUSE_SOURCE_STROBE_G2_PIN6 
IO_CFG_GPS_TIMEPUSE_SOURCE_STROBE_G5_PIN9 
IO_CFG_GPS_TIMEPUSE_SOURCE_STROBE_G8_PIN12 
IO_CFG_GPS_TIMEPUSE_SOURCE_STROBE_G9_PIN13 
IO_CONFIG_GPS1_SOURCE_OFFSET 

GPS 1 source OFFSET

IO_CONFIG_GPS2_SOURCE_OFFSET 

GPS 2 source OFFSET

IO_CONFIG_GPS1_TYPE_OFFSET 

GPS 1 type OFFSET

IO_CONFIG_GPS2_TYPE_OFFSET 

GPS 2 type OFFSET

IO_CONFIG_GPS_SOURCE_MASK 

GPS source MASK

IO_CONFIG_GPS_SOURCE_DISABLE 

GPS source - Disable

IO_CONFIG_GPS_SOURCE_ONBOARD_1 

GPS source - GNSS receiver 1 onboard uINS

IO_CONFIG_GPS_SOURCE_ONBOARD_2 

GPS source - GNSS receiver 2 onboard uINS

IO_CONFIG_GPS_SOURCE_SER0 

GPS source - Serial 0

IO_CONFIG_GPS_SOURCE_SER1 

GPS source - Serial 1

IO_CONFIG_GPS_SOURCE_SER2 

GPS source - Serial 2

IO_CONFIG_GPS_TYPE_MASK 

GPS type MASK

IO_CONFIG_GPS_TYPE_UBX_M8 

GPS type - ublox M8

IO_CONFIG_GPS_TYPE_UBX_F9P 

GPS type - ublox ZED-F9P w/ RTK

IO_CONFIG_GPS_TYPE_NMEA 

GPS type - NMEA

IO_CONFIG_IMU_1_DISABLE 

IMU 1 disable

IO_CONFIG_IMU_2_DISABLE 

IMU 2 disable

IO_CONFIG_CAN_BUS_ENABLE 

CAN Bus Enable

Definition at line 1805 of file data_sets.h.

◆ eMagRecalMode

Enumerator
MAG_RECAL_CMD_DO_NOTHING 
MAG_RECAL_CMD_MULTI_AXIS 
MAG_RECAL_CMD_SINGLE_AXIS 
MAG_RECAL_CMD_ABORT 

Definition at line 1378 of file data_sets.h.

◆ eRawDataType

RAW data types for DID_GPS_BASE_RAW and DID_GPS2_RAW

Enumerator
raw_data_type_observation 

obsd_t

raw_data_type_ephemeris 

eph_t

raw_data_type_glonass_ephemeris 

geph_t

raw_data_type_sbas 

sbsmsg_t

raw_data_type_base_station_antenna_position 

sta_t

raw_data_type_ionosphere_model_utc_alm 

ion_model_utc_alm_t

raw_data_type_rtk_solution 

gps_rtk_misc_t

Definition at line 2856 of file data_sets.h.

◆ eRTKConfigBits

RTK Configuration

Enumerator
RTK_CFG_BITS_ROVER_MODE_RTK_POSITIONING 

Enable RTK GNSS precision positioning (GPS1)

RTK_CFG_BITS_ROVER_MODE_RTK_POSITIONING_F9P 

Enable RTK GNSS positioning on uBlox F9P (GPS1)

RTK_CFG_BITS_ROVER_MODE_RTK_COMPASSING_F9P 

Enable RTK GNSS compassing on uBlox F9P (GPS2)

RTK_CFG_BITS_ROVER_MODE_RTK_COMPASSING 

Enable dual GNSS RTK compassing (GPS2 to GPS1)

RTK_CFG_BITS_ROVER_MODE_RTK_POSITIONING_MASK 

Mask of RTK GNSS positioning types

RTK_CFG_BITS_ROVER_MODE_RTK_COMPASSING_MASK 

Mask of dual GNSS RTK compassing types

RTK_CFG_BITS_ROVER_MODE_MASK 

Mask of RTK position, heading, and base modes

RTK_CFG_BITS_BASE_OUTPUT_GPS1_UBLOX_SER0 

Enable RTK base and output ublox data from GPS 1 on serial port 0

RTK_CFG_BITS_BASE_OUTPUT_GPS1_UBLOX_SER1 

Enable RTK base and output ublox data from GPS 1 on serial port 1

RTK_CFG_BITS_BASE_OUTPUT_GPS1_UBLOX_SER2 

Enable RTK base and output ublox data from GPS 1 on serial port 2

RTK_CFG_BITS_BASE_OUTPUT_GPS1_UBLOX_USB 

Enable RTK base and output ublox data from GPS 1 on USB port

RTK_CFG_BITS_BASE_OUTPUT_GPS1_RTCM3_SER0 

Enable RTK base and output RTCM3 data from GPS 1 on serial port 0

RTK_CFG_BITS_BASE_OUTPUT_GPS1_RTCM3_SER1 

Enable RTK base and output RTCM3 data from GPS 1 on serial port 1

RTK_CFG_BITS_BASE_OUTPUT_GPS1_RTCM3_SER2 

Enable RTK base and output RTCM3 data from GPS 1 on serial port 2

RTK_CFG_BITS_BASE_OUTPUT_GPS1_RTCM3_USB 

Enable RTK base and output RTCM3 data from GPS 1 on USB port

RTK_CFG_BITS_BASE_OUTPUT_GPS2_UBLOX_SER0 

Enable RTK base and output ublox data from GPS 2 on serial port 0

RTK_CFG_BITS_BASE_OUTPUT_GPS2_UBLOX_SER1 

Enable RTK base and output ublox data from GPS 2 on serial port 1

RTK_CFG_BITS_BASE_OUTPUT_GPS2_UBLOX_SER2 

Enable RTK base and output ublox data from GPS 2 on serial port 2

RTK_CFG_BITS_BASE_OUTPUT_GPS2_UBLOX_USB 

Enable RTK base and output ublox data from GPS 2 on USB port

RTK_CFG_BITS_BASE_OUTPUT_GPS2_RTCM3_SER0 

Enable RTK base and output RTCM3 data from GPS 2 on serial port 0

RTK_CFG_BITS_BASE_OUTPUT_GPS2_RTCM3_SER1 

Enable RTK base and output RTCM3 data from GPS 2 on serial port 1

RTK_CFG_BITS_BASE_OUTPUT_GPS2_RTCM3_SER2 

Enable RTK base and output RTCM3 data from GPS 2 on serial port 2

RTK_CFG_BITS_BASE_OUTPUT_GPS2_RTCM3_USB 

Enable RTK base and output RTCM3 data from GPS 2 on USB port

RTK_CFG_BITS_BASE_POS_MOVING 

Enable base mode moving position. (For future use. Not implemented. This bit should always be 0 for now.) TODO: Implement moving base.

RTK_CFG_BITS_RESERVED1 

Reserved for future use

RTK_CFG_BITS_RTK_BASE_IS_IDENTICAL_TO_ROVER 

When using RTK, specifies whether the base station is identical hardware to this rover. If so, there are optimizations enabled to get fix faster.

RTK_CFG_BITS_GPS_PORT_PASS_THROUGH 

Forward all messages between the selected GPS and serial port. Disable for RTK base use (to forward only GPS raw messages and use the surveyed location refLLA instead of current GPS position).

RTK_CFG_BITS_BASE_MODE 

All base station bits

RTK_CFG_BITS_RTK_BASE_SER0 

Base station bits enabled on Ser0

RTK_CFG_BITS_RTK_BASE_SER1 

Base station bits enabled on Ser1

RTK_CFG_BITS_RTK_BASE_SER2 

Base station bits enabled on Ser2

RTK_CFG_BITS_RTK_BASE_OUTPUT_GPS1_UBLOX 

Base station bits for GPS1 Ublox

RTK_CFG_BITS_RTK_BASE_OUTPUT_GPS2_UBLOX 

Base station bits for GPS2 Ublox

RTK_CFG_BITS_RTK_BASE_OUTPUT_GPS1_RTCM 

Base station bits for GPS1 RTCM

RTK_CFG_BITS_RTK_BASE_OUTPUT_GPS2_RTCM 

Base station bits for GPS2 RTCM

RTK_CFG_BITS_ROVER_MODE_ONBOARD_MASK 

Rover on-board RTK engine used

RTK_CFG_BITS_ALL_MODES_MASK 

Mask of Rover, Compassing, and Base modes

Definition at line 1586 of file data_sets.h.

◆ eRtkSolStatus

RTK solution status

Enumerator
rtk_solution_status_none 

No status

rtk_solution_status_fix 

RTK fix

rtk_solution_status_float 

RTK float

rtk_solution_status_sbas 

RTK SBAS

rtk_solution_status_dgps 

RTK DGPS

rtk_solution_status_single 

RTK SINGLE

Definition at line 2695 of file data_sets.h.

◆ eRtosTask

enum eRtosTask

RTOS tasks

Enumerator
TASK_SAMPLE 

Task 0: Sample

TASK_NAV 

Task 1: Nav

TASK_COMMUNICATIONS 

Task 2: Communications

TASK_MAINTENANCE 

Task 3: Maintenance

TASK_IDLE 

Task 4: Idle

TASK_TIMER 

Task 5: Timer

UINS_RTOS_NUM_TASKS 

Number of RTOS tasks

Definition at line 3355 of file data_sets.h.

◆ eSatSvFlags

GPS Status

Enumerator
SAT_SV_FLAGS_QUALITYIND_MASK 
SAT_SV_FLAGS_SV_USED 
SAT_SV_FLAGS_HEALTH_MASK 
NAV_SAT_FLAGS_HEALTH_OFFSET 
SAT_SV_FLAGS_DIFFCORR 
SAT_SV_FLAGS_SMOOTHED 
SAT_SV_FLAGS_ORBITSOURCE_MASK 
SAT_SV_FLAGS_ORBITSOURCE_OFFSET 
SAT_SV_FLAGS_EPHAVAIL 
SAT_SV_FLAGS_ALMAVAIL 
SAT_SV_FLAGS_ANOAVAIL 
SAT_SV_FLAGS_AOPAVAIL 
SAT_SV_FLAGS_RTK_SOL_FIX_STATUS_MASK 
SAT_SV_FLAGS_RTK_SOL_FIX_STATUS_OFFSET 
SAT_SV_FLAGS_RTK_SOL_FIX_STATUS_FLOAT 
SAT_SV_FLAGS_RTK_SOL_FIX_STATUS_FIX 
SAT_SV_FLAGS_RTK_SOL_FIX_STATUS_HOLD 

Definition at line 843 of file data_sets.h.

◆ eSensorConfig

Sensor Configuration

Enumerator
SENSOR_CFG_GYR_FS_250 

Gyro full-scale sensing range selection: +- 250, 500, 1000, 2000 deg/s

SENSOR_CFG_GYR_FS_500 
SENSOR_CFG_GYR_FS_1000 
SENSOR_CFG_GYR_FS_2000 
SENSOR_CFG_GYR_FS_MASK 
SENSOR_CFG_GYR_FS_OFFSET 
SENSOR_CFG_ACC_FS_2G 

Accelerometer full-scale sensing range selection: +- 2, 4, 8, 16 m/s^2

SENSOR_CFG_ACC_FS_4G 
SENSOR_CFG_ACC_FS_8G 
SENSOR_CFG_ACC_FS_16G 
SENSOR_CFG_ACC_FS_MASK 
SENSOR_CFG_ACC_FS_OFFSET 
SENSOR_CFG_GYR_DLPF_250HZ 

Gyro digital low-pass filter (DLPF) is set automatically based on the IMU sample rate. The following bit values can be used to override the bandwidth (frequency) to: 250, 184, 92, 41, 20, 10, 5 Hz

SENSOR_CFG_GYR_DLPF_184HZ 
SENSOR_CFG_GYR_DLPF_92HZ 
SENSOR_CFG_GYR_DLPF_41HZ 
SENSOR_CFG_GYR_DLPF_20HZ 
SENSOR_CFG_GYR_DLPF_10HZ 
SENSOR_CFG_GYR_DLPF_5HZ 
SENSOR_CFG_GYR_DLPF_MASK 
SENSOR_CFG_GYR_DLPF_OFFSET 
SENSOR_CFG_ACC_DLPF_218HZ 

Accelerometer digital low-pass filter (DLPF) is set automatically based on the IMU sample rate. The following bit values can be used to override the bandwidth (frequency) to: 218, 218, 99, 45, 21, 10, 5 Hz

SENSOR_CFG_ACC_DLPF_218HZb 
SENSOR_CFG_ACC_DLPF_99HZ 
SENSOR_CFG_ACC_DLPF_45HZ 
SENSOR_CFG_ACC_DLPF_21HZ 
SENSOR_CFG_ACC_DLPF_10HZ 
SENSOR_CFG_ACC_DLPF_5HZ 
SENSOR_CFG_ACC_DLPF_MASK 
SENSOR_CFG_ACC_DLPF_OFFSET 
SENSOR_CFG_SENSOR_ROTATION_MASK 

Euler rotation of IMU and magnetometer from sensor frame to output frame. Rotation applied in the order of yaw, pitch, roll from the sensor frame (labeled on uINS).

SENSOR_CFG_SENSOR_ROTATION_OFFSET 
SENSOR_CFG_SENSOR_ROTATION_0_0_0 
SENSOR_CFG_SENSOR_ROTATION_0_0_90 
SENSOR_CFG_SENSOR_ROTATION_0_0_180 
SENSOR_CFG_SENSOR_ROTATION_0_0_N90 
SENSOR_CFG_SENSOR_ROTATION_90_0_0 
SENSOR_CFG_SENSOR_ROTATION_90_0_90 
SENSOR_CFG_SENSOR_ROTATION_90_0_180 
SENSOR_CFG_SENSOR_ROTATION_90_0_N90 
SENSOR_CFG_SENSOR_ROTATION_180_0_0 
SENSOR_CFG_SENSOR_ROTATION_180_0_90 
SENSOR_CFG_SENSOR_ROTATION_180_0_180 
SENSOR_CFG_SENSOR_ROTATION_180_0_N90 
SENSOR_CFG_SENSOR_ROTATION_N90_0_0 
SENSOR_CFG_SENSOR_ROTATION_N90_0_90 
SENSOR_CFG_SENSOR_ROTATION_N90_0_180 
SENSOR_CFG_SENSOR_ROTATION_N90_0_N90 
SENSOR_CFG_SENSOR_ROTATION_0_90_0 
SENSOR_CFG_SENSOR_ROTATION_0_90_90 
SENSOR_CFG_SENSOR_ROTATION_0_90_180 
SENSOR_CFG_SENSOR_ROTATION_0_90_N90 
SENSOR_CFG_SENSOR_ROTATION_0_N90_0 
SENSOR_CFG_SENSOR_ROTATION_0_N90_90 
SENSOR_CFG_SENSOR_ROTATION_0_N90_180 
SENSOR_CFG_SENSOR_ROTATION_0_N90_N90 

Definition at line 1732 of file data_sets.h.

◆ eSurveyInStatus

Enumerator
SURVEY_IN_STATE_OFF 
SURVEY_IN_STATE_CANCEL 
SURVEY_IN_STATE_START_3D 
SURVEY_IN_STATE_START_FLOAT 
SURVEY_IN_STATE_START_FIX 
SURVEY_IN_STATE_RUNNING_3D 
SURVEY_IN_STATE_RUNNING_FLOAT 
SURVEY_IN_STATE_RUNNING_FIX 
SURVEY_IN_STATE_SAVE_POS 
SURVEY_IN_STATE_DONE 

Definition at line 2938 of file data_sets.h.

◆ eSysConfigBits

System Configuration (used with DID_FLASH_CONFIG.sysCfgBits)

Enumerator
UNUSED1 
UNUSED2 
SYS_CFG_BITS_AUTO_MAG_RECAL 

Enable automatic mag recalibration

SYS_CFG_BITS_DISABLE_MAG_DECL_ESTIMATION 

Disable mag declination estimation

SYS_CFG_BITS_DISABLE_LEDS 

Disable LEDs

SYS_CFG_BITS_MAG_RECAL_MODE_MASK 

Magnetometer recalibration. 0 = multi-axis, 1 = single-axis

SYS_CFG_BITS_MAG_RECAL_MODE_OFFSET 
SYS_CFG_BITS_DISABLE_MAGNETOMETER_FUSION 

Disable magnetometer fusion

SYS_CFG_BITS_DISABLE_BAROMETER_FUSION 

Disable barometer fusion

SYS_CFG_BITS_DISABLE_GPS1_FUSION 

Disable GPS 1 fusion

SYS_CFG_BITS_DISABLE_GPS2_FUSION 

Disable GPS 2 fusion

SYS_CFG_BITS_DISABLE_AUTO_ZERO_VELOCITY_UPDATES 

Disable automatic Zero Velocity Updates (ZUPT). Disabling automatic ZUPT is useful for degraded GPS environments or applications with very slow velocities.

SYS_CFG_BITS_DISABLE_AUTO_ZERO_ANGULAR_RATE_UPDATES 

Disable automatic Zero Angular Rate Updates (ZARU). Disabling automatic ZARU is useful for applications with small/slow angular rates.

SYS_CFG_BITS_DISABLE_INS_EKF 

Disable INS EKF updates

SYS_CFG_BITS_DISABLE_AUTO_BIT_ON_STARTUP 

Prevent built-in test (BIT) from running automatically on startup

SYS_CFG_BITS_DISABLE_PACKET_ENCODING 

Disable packet encoding, binary data will have all bytes as is

Definition at line 1521 of file data_sets.h.

◆ eSystemCommand

Enumerator
SYS_CMD_SAVE_PERSISTENT_MESSAGES 
SYS_CMD_ENABLE_BOOTLOADER_AND_RESET 
SYS_CMD_ENABLE_SENSOR_STATS 
SYS_CMD_ENABLE_RTOS_STATS 
SYS_CMD_ZERO_MOTION 
SYS_CMD_ENABLE_GPS_LOW_LEVEL_CONFIG 
SYS_CMD_SAVE_FLASH 
SYS_CMD_SAVE_GPS_ASSIST_TO_FLASH_RESET 
SYS_CMD_SOFTWARE_RESET 
SYS_CMD_MANF_UNLOCK 
SYS_CMD_MANF_FACTORY_RESET 
SYS_CMD_MANF_CHIP_ERASE 

Definition at line 1129 of file data_sets.h.

◆ eWheelCfgBits

Enumerator
WHEEL_CFG_BITS_ENABLE_KINEMATIC_CONST 
WHEEL_CFG_BITS_ENABLE_ENCODER 
WHEEL_CFG_BITS_ENABLE_MASK 

Definition at line 1914 of file data_sets.h.

Function Documentation

◆ checksum32()

POP_PACK uint32_t checksum32 ( const void *  data,
int  count 
)

Creates a 32 bit checksum from data

Parameters
datathe data to create a checksum for
countthe number of bytes in data
Returns
the 32 bit checksum for data

Definition at line 531 of file data_sets.c.

◆ didToRmcBit()

uint64_t didToRmcBit ( uint32_t  dataId,
uint64_t  defaultRmcBits 
)

Convert DID to realtime message bits

Definition at line 563 of file data_sets.c.

◆ flashChecksum32()

uint32_t flashChecksum32 ( const void *  data,
int  size 
)

Definition at line 557 of file data_sets.c.

◆ flipDouble()

void flipDouble ( void *  ptr)

Flip the bytes of a double in place (8 bytes) - ptr is assumed to be at least 8 bytes Only flips each 4 byte pair, does not flip the individual bytes within the pair

Parameters
ptrthe double to flip

Definition at line 47 of file data_sets.c.

◆ flipDoubleCopy()

double flipDoubleCopy ( double  val)

Flip the bytes of a double in place (8 bytes) Unlike flipDouble, this also flips the individual bytes in each 4 byte pair

Parameters
valthe double to flip
Returns
the flipped double

Definition at line 60 of file data_sets.c.

◆ flipDoubles()

void flipDoubles ( uint8_t *  data,
int  dataLength,
int  offset,
uint16_t *  offsets,
uint16_t  offsetsLength 
)

Flip double (64 bit) floating point values in data

Parameters
datathe data to flip doubles in
dataLengththe number of bytes in data
offsetoffset into data to start flipping at
offsetsa list of offsets of all doubles in data, starting at position 0
offsetsLengththe number of items in offsets

Definition at line 91 of file data_sets.c.

◆ flipEndianess32()

void flipEndianess32 ( uint8_t *  data,
int  dataLength 
)

Flip the endianess of 32 bit values in data

Parameters
datathe data to flip 32 bit values in
dataLengththe number of bytes in data

Definition at line 73 of file data_sets.c.

◆ flipFloat()

void flipFloat ( uint8_t *  ptr)

Flip the bytes of a float in place (4 bytes) - ptr is assumed to be at least 4 bytes

Parameters
ptrthe float to flip

Definition at line 19 of file data_sets.c.

◆ flipFloatCopy()

float flipFloatCopy ( float  val)

Flip the bytes of a float (4 bytes) - ptr is assumed to be at least 4 bytes

Parameters
valthe float to flip
Returns
the flipped float

Definition at line 31 of file data_sets.c.

◆ flipStrings()

void flipStrings ( uint8_t *  data,
int  dataLength,
int  offset,
uint16_t *  offsets,
uint16_t  offsetsLength 
)

Flip string values in data - this compensates for the fact that flipEndianess32 is called on all the data

Parameters
datathe data to flip string values in
dataLengththe number of bytes in data
offsetthe offset into data to start flipping strings at
offsetsa list of offsets and byte lengths into data where strings start at
offsetsLengththe number of items in offsets, should be 2 times the string count

Definition at line 117 of file data_sets.c.

◆ getDoubleOffsets()

uint16_t* getDoubleOffsets ( eDataIDs  dataId,
uint16_t *  offsetsLength 
)

Get the offsets of double / int64 (64 bit) values given a data id

Parameters
dataIdthe data id to get double offsets for
offsetsLengthreceives the number of double offsets
Returns
a list of offets of doubles or 0 if none, offset will have high bit set if it is an int64 instead of a double

Definition at line 141 of file data_sets.c.

◆ getStringOffsetsLengths()

uint16_t* getStringOffsetsLengths ( eDataIDs  dataId,
uint16_t *  offsetsLength 
)

Gets the offsets and lengths of strings given a data id

Parameters
dataIdthe data id to get string offsets and lengths for
offsetsLengthreceives the number of items in the return value
Returns
a list of offsets and lengths of strings for the data id or 0 if none

Definition at line 382 of file data_sets.c.

◆ gpsToJulian()

double gpsToJulian ( int32_t  gpsWeek,
int32_t  gpsMilliseconds,
int32_t  leapSeconds 
)

Convert GPS Week and Seconds to Julian Date. Leap seconds are the GPS-UTC offset (18 seconds as of December 31, 2016).

Definition at line 708 of file data_sets.c.

◆ gpsToNmeaGGA()

int gpsToNmeaGGA ( const gps_pos_t gps,
char *  buffer,
int  bufferLength 
)

Definition at line 745 of file data_sets.c.

◆ gpsToUnix()

double gpsToUnix ( uint32_t  gpsWeek,
uint32_t  gpsTimeofWeekMS,
uint8_t  leapSeconds 
)

Convert GPS Week and Ms and leapSeconds to Unix seconds

Definition at line 699 of file data_sets.c.

◆ julianToDate()

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 
)

Convert Julian Date to calendar date.

Definition at line 607 of file data_sets.c.

◆ satNo()

int satNo ( int  sys,
int  prn 
)

Definition at line 868 of file data_sets.c.

◆ satNumCalc()

int satNumCalc ( int  gnssID,
int  svID 
)

Definition at line 908 of file data_sets.c.

◆ serialNumChecksum32()

uint32_t serialNumChecksum32 ( const void *  data,
int  size 
)

Definition at line 551 of file data_sets.c.

◆ ubxSys()

int ubxSys ( int  gnssID)

Definition at line 849 of file data_sets.c.



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