#include <stdint.h>
#include <stdlib.h>
#include <time.h>
#include <string.h>
#include "ISConstants.h"
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 |
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) |
#define BE_SWAP16 | ( | _i | ) | (_i) |
Definition at line 3657 of file data_sets.h.
#define BE_SWAP32 | ( | _i | ) | (_i) |
Definition at line 3656 of file data_sets.h.
#define BE_SWAP32F | ( | _i | ) | (_i) |
Definition at line 3655 of file data_sets.h.
#define BE_SWAP64F | ( | _i | ) | (_i) |
Definition at line 3654 of file data_sets.h.
#define CAL_BIT_MODE | ( | calBitStatus | ) | ((calBitStatus&CAL_BIT_MODE_MASK)>>CAL_BIT_MODE_OFFSET) |
Definition at line 1461 of file data_sets.h.
#define DEBUG_F_ARRAY_SIZE 9 |
Definition at line 2099 of file data_sets.h.
#define DEBUG_I_ARRAY_SIZE 9 |
Definition at line 2098 of file data_sets.h.
#define DEBUG_LF_ARRAY_SIZE 3 |
Definition at line 2100 of file data_sets.h.
#define DEBUG_STRING_SIZE 80 |
Definition at line 2110 of file data_sets.h.
#define DEVINFO_ADDINFO_STRLEN 24 |
Definition at line 150 of file data_sets.h.
#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.
#define DID_ASCII_BCAST_PERIOD (eDataIDs)8 /** (ascii_msgs_t) Broadcast period for ASCII messages */ |
Definition at line 42 of file data_sets.h.
#define DID_BAROMETER (eDataIDs)53 /** (barometer_t) Barometric pressure sensor data */ |
Definition at line 87 of file data_sets.h.
Definition at line 98 of file data_sets.h.
#define DID_CAL_SC (eDataIDs)42 /** INTERNAL USE ONLY (sensor_cal_mem_t) */ |
Definition at line 76 of file data_sets.h.
#define DID_CAL_SC1 (eDataIDs)43 /** INTERNAL USE ONLY (sensor_cal_mpu_t) */ |
Definition at line 77 of file data_sets.h.
#define DID_CAL_SC2 (eDataIDs)44 /** INTERNAL USE ONLY (sensor_cal_mpu_t) */ |
Definition at line 78 of file data_sets.h.
#define DID_CAL_SC_INFO (eDataIDs)74 /** INTERNAL USE ONLY (sensor_cal_info_t) */ |
Definition at line 108 of file data_sets.h.
#define DID_CAN_CONFIG (eDataIDs)90 /** (can_config_t) Addresses for CAN messages*/ |
Definition at line 124 of file data_sets.h.
#define DID_COMMUNICATIONS_LOOPBACK (eDataIDs)56 /** INTERNAL USE ONLY - Unit test for communications manager */ |
Definition at line 90 of file data_sets.h.
#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.
#define DID_DEBUG_ARRAY (eDataIDs)39 /** INTERNAL USE ONLY (debug_array_t) */ |
Definition at line 73 of file data_sets.h.
#define DID_DEBUG_STRING (eDataIDs)37 /** INTERNAL USE ONLY (debug_string_t) */ |
Definition at line 71 of file data_sets.h.
#define DID_DEV_INFO (eDataIDs)1 /** (dev_info_t) Device information */ |
Definition at line 35 of file data_sets.h.
#define DID_DIAGNOSTIC_MESSAGE (eDataIDs)72 /** (diag_msg_t) Diagnostic message */ |
Definition at line 106 of file data_sets.h.
#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.
#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.
#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.
#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.
#define DID_EVB_DEBUG_ARRAY (eDataIDs)82 /** INTERNAL USE ONLY (debug_array_t) */ |
Definition at line 116 of file data_sets.h.
#define DID_EVB_DEV_INFO (eDataIDs)93 /** (dev_info_t) EVB device information */ |
Definition at line 127 of file data_sets.h.
#define DID_EVB_FLASH_CFG (eDataIDs)81 /** (evb_flash_cfg_t) EVB configuration. */ |
Definition at line 115 of file data_sets.h.
#define DID_EVB_RTOS_INFO (eDataIDs)83 /** (evb_rtos_info_t) EVB-2 RTOS information. */ |
Definition at line 117 of file data_sets.h.
#define DID_EVB_STATUS (eDataIDs)80 /** (evb_status_t) EVB monitor and log control interface. */ |
Definition at line 114 of file data_sets.h.
#define DID_FEATURE_BITS (eDataIDs)23 /** INTERNAL USE ONLY (feature_bits_t) */ |
Definition at line 57 of file data_sets.h.
#define DID_FLASH_CONFIG (eDataIDs)12 /** (nvm_flash_cfg_t) Flash memory configuration */ |
Definition at line 46 of file data_sets.h.
#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.
#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.
Definition at line 88 of file data_sets.h.
#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.
#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.
#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.
Definition at line 40 of file data_sets.h.
Definition at line 64 of file data_sets.h.
#define DID_GPS1_VERSION (eDataIDs)17 /** (gps_version_t) GPS 1 version info */ |
Definition at line 51 of file data_sets.h.
Definition at line 48 of file data_sets.h.
#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.
#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.
#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.
#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.
Definition at line 65 of file data_sets.h.
#define DID_GPS2_VERSION (eDataIDs)18 /** (gps_version_t) GPS 2 version info */ |
Definition at line 52 of file data_sets.h.
#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.
#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.
#define DID_HDW_PARAMS (eDataIDs)32 /** INTERNAL USE ONLY (hdw_params_t) */ |
Definition at line 66 of file data_sets.h.
#define DID_INL2_COVARIANCE_LD (eDataIDs)49 /** (INL2_COVARIANCE_LD_ARRAY_SIZE) */ |
Definition at line 83 of file data_sets.h.
#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.
#define DID_INL2_MISC (eDataIDs)51 /** (inl2_misc_t) */ |
Definition at line 85 of file data_sets.h.
#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.
#define DID_INL2_STATES (eDataIDs)48 /** (inl2_states_t) */ |
Definition at line 82 of file data_sets.h.
#define DID_INL2_STATUS (eDataIDs)50 /** (inl2_status_t) */ |
Definition at line 84 of file data_sets.h.
#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.
#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.
#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.
#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.
#define DID_INS_DEV_1 (eDataIDs)47 /** INTERNAL USE ONLY (ins_dev_1_t) */ |
Definition at line 81 of file data_sets.h.
#define DID_INTERNAL_DIAGNOSTIC (eDataIDs)20 /** INTERNAL USE ONLY (internal_diagnostic_t) Internal diagnostic info */ |
Definition at line 54 of file data_sets.h.
Definition at line 61 of file data_sets.h.
Definition at line 53 of file data_sets.h.
#define DID_MAGNETOMETER_1 (eDataIDs)52 /** (magnetometer_t) Magnetometer sensor 1 output */ |
Definition at line 86 of file data_sets.h.
#define DID_MAGNETOMETER_2 (eDataIDs)55 /** (magnetometer_t) 2nd magnetometer sensor data */ |
Definition at line 89 of file data_sets.h.
#define DID_MANUFACTURING_INFO (eDataIDs)63 /** INTERNAL USE ONLY (manufacturing_info_t) Manufacturing info */ |
Definition at line 97 of file data_sets.h.
#define DID_MAX_COUNT 256 |
Maximum number of data ids
Definition at line 141 of file data_sets.h.
Definition at line 34 of file data_sets.h.
#define DID_NVR_MANAGE_USERPAGE (eDataIDs)33 /** INTERNAL USE ONLY (nvr_manage_t) */ |
Definition at line 67 of file data_sets.h.
#define DID_NVR_USERPAGE_G0 (eDataIDs)35 /** INTERNAL USE ONLY (nvm_group_0_t) */ |
Definition at line 69 of file data_sets.h.
#define DID_NVR_USERPAGE_G1 (eDataIDs)36 /** INTERNAL USE ONLY (nvm_group_1_t) */ |
Definition at line 70 of file data_sets.h.
Definition at line 96 of file data_sets.h.
#define DID_NVR_USERPAGE_SN (eDataIDs)34 /** INTERNAL USE ONLY (nvm_group_sn_t) */ |
Definition at line 68 of file data_sets.h.
#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.
#define DID_POSITION_MEASUREMENT (eDataIDs)88 /** (pos_measurement_t) External position estimate*/ |
Definition at line 122 of file data_sets.h.
#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.
#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.
#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.
#define DID_RTK_CODE_RESIDUAL (eDataIDs)78 /** INTERNAL USE ONLY (rtk_residual_t) */ |
Definition at line 112 of file data_sets.h.
#define DID_RTK_DEBUG (eDataIDs)79 /** INTERNAL USE ONLY (rtk_debug_t) */ |
Definition at line 113 of file data_sets.h.
#define DID_RTK_DEBUG_2 (eDataIDs)89 /** INTERNAL USE ONLY (rtk_debug_2_t) */ |
Definition at line 123 of file data_sets.h.
#define DID_RTK_PHASE_RESIDUAL (eDataIDs)77 /** INTERNAL USE ONLY (rtk_residual_t) */ |
Definition at line 111 of file data_sets.h.
#define DID_RTK_STATE (eDataIDs)76 /** INTERNAL USE ONLY (rtk_state_t) */ |
Definition at line 110 of file data_sets.h.
#define DID_RTOS_INFO (eDataIDs)38 /** (rtos_info_t) RTOS information. */ |
Definition at line 72 of file data_sets.h.
#define DID_SCOMP (eDataIDs)29 /** INTERNAL USE ONLY (sensor_compensation_t) */ |
Definition at line 63 of file data_sets.h.
#define DID_SENSORS_ADC (eDataIDs)28 /** INTERNAL USE ONLY (sys_sensors_adc_t) */ |
Definition at line 62 of file data_sets.h.
#define DID_SENSORS_ADC_SIGMA (eDataIDs)46 /** INTERNAL USE ONLY (sys_sensors_adc_t) */ |
Definition at line 80 of file data_sets.h.
#define DID_SENSORS_CAL1 (eDataIDs)40 /** INTERNAL USE ONLY (sensors_mpu_w_temp_t) */ |
Definition at line 74 of file data_sets.h.
#define DID_SENSORS_CAL2 (eDataIDs)41 /** INTERNAL USE ONLY (sensors_mpu_w_temp_t) */ |
Definition at line 75 of file data_sets.h.
#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.
#define DID_SENSORS_IS2 (eDataIDs)25 /** INTERNAL USE ONLY (sensors_w_temp_t) Temperature compensated */ |
Definition at line 59 of file data_sets.h.
#define DID_SENSORS_TC_BIAS (eDataIDs)26 /** INTERNAL USE ONLY (sensors_t) */ |
Definition at line 60 of file data_sets.h.
#define DID_STROBE_IN_TIME (eDataIDs)68 /** (strobe_in_time_t) Timestamp for input strobe. */ |
Definition at line 102 of file data_sets.h.
#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.
#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.
#define DID_SYS_FAULT (eDataIDs)2 /** (system_fault_t) System fault information */ |
Definition at line 36 of file data_sets.h.
#define DID_SYS_PARAMS (eDataIDs)10 /** (sys_params_t) System parameters / info */ |
Definition at line 44 of file data_sets.h.
#define DID_SYS_SENSORS (eDataIDs)11 /** (sys_sensors_t) System sensor information */ |
Definition at line 45 of file data_sets.h.
#define DID_SYS_SENSORS_SIGMA (eDataIDs)45 /** INTERNAL USE ONLY (sys_sensors_t) */ |
Definition at line 79 of file data_sets.h.
#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.
#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.
#define ENAGAL |
Definition at line 3737 of file data_sets.h.
#define ENAGLO |
Definition at line 3734 of file data_sets.h.
#define ENASBS |
Definition at line 3743 of file data_sets.h.
#define EVB2_CB_PRESET_DEFAULT EVB2_CB_PRESET_RS232 |
Definition at line 3236 of file data_sets.h.
#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.
#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.
#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.
#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.
#define GPS_RAW_MESSAGE_BUF_SIZE 1000 |
Definition at line 2417 of file data_sets.h.
#define GPS_TO_UNIX_OFFSET 315964800 |
Definition at line 3690 of file data_sets.h.
#define HALF_MAXOBS (MAXOBS/2) |
Definition at line 3773 of file data_sets.h.
#define HDW_BIT_MODE | ( | hdwBitStatus | ) | ((hdwBitStatus&HDW_BIT_MODE_MASK)>>HDW_BIT_MODE_OFFSET) |
Definition at line 1441 of file data_sets.h.
#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.
#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.
#define INS_STATUS_SOLUTION | ( | insStatus | ) | ((insStatus&INS_STATUS_SOLUTION_MASK)>>INS_STATUS_SOLUTION_OFFSET) |
Definition at line 213 of file data_sets.h.
#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.
#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.
#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.
#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.
#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.
#define LE_SWAP16 | ( | _i | ) | (SWAP16(_i)) |
Definition at line 3661 of file data_sets.h.
#define LE_SWAP32 | ( | _i | ) | (SWAP32(_i)) |
Definition at line 3660 of file data_sets.h.
#define LE_SWAP32F | ( | _i | ) | flipFloatCopy(_i) |
Definition at line 3659 of file data_sets.h.
#define LE_SWAP64F | ( | _i | ) | flipDoubleCopy(_i) |
Definition at line 3658 of file data_sets.h.
#define MAX_NUM_SAT_CHANNELS 50 |
Maximum number of satellite channels
Definition at line 146 of file data_sets.h.
#define MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE (GPS_RAW_MESSAGE_BUF_SIZE / sizeof(obsd_t)) |
Definition at line 2418 of file data_sets.h.
#define MAX_TASK_NAME_LEN 12 |
Max task name length - do not change
Definition at line 3408 of file data_sets.h.
#define MAXERRMSG 0 |
Definition at line 3779 of file data_sets.h.
#define MAXOBS 56 |
Definition at line 3772 of file data_sets.h.
#define MAXPRNCMP 0 |
Definition at line 3855 of file data_sets.h.
#define MAXPRNGAL 30 /* max satellite PRN number of Galileo */ |
Definition at line 3824 of file data_sets.h.
#define MAXPRNGLO 27 /* max satellite slot number of GLONASS */ |
Definition at line 3813 of file data_sets.h.
#define MAXPRNGPS 32 /* max satellite PRN number of GPS */ |
Definition at line 3807 of file data_sets.h.
#define MAXPRNIRN 0 |
Definition at line 3866 of file data_sets.h.
#define MAXPRNLEO 0 |
Definition at line 3877 of file data_sets.h.
#define MAXPRNQZS 0 |
Definition at line 3842 of file data_sets.h.
#define MAXPRNQZS_S 0 |
Definition at line 3844 of file data_sets.h.
#define MAXPRNSBS 138 /* max satellite PRN number of SBAS */ |
Definition at line 3788 of file data_sets.h.
#define MAXRAWLEN 2048 |
Definition at line 3749 of file data_sets.h.
#define MAXSUBFRMLEN 152 |
Definition at line 3746 of file data_sets.h.
#define MINPRNCMP 0 |
Definition at line 3854 of file data_sets.h.
#define MINPRNGAL 1 /* min satellite PRN number of Galileo */ |
Definition at line 3823 of file data_sets.h.
#define MINPRNGLO 1 /* min satellite slot number of GLONASS */ |
Definition at line 3812 of file data_sets.h.
#define MINPRNGPS 1 /* min satellite PRN number of GPS */ |
Definition at line 3806 of file data_sets.h.
#define MINPRNIRN 0 |
Definition at line 3865 of file data_sets.h.
#define MINPRNLEO 0 |
Definition at line 3876 of file data_sets.h.
#define MINPRNQZS 0 |
Definition at line 3841 of file data_sets.h.
#define MINPRNQZS_S 0 |
Definition at line 3843 of file data_sets.h.
#define MINPRNSBS 133 /* min satellite PRN number of SBAS */ |
Definition at line 3785 of file data_sets.h.
#define NEXOBS 0 |
Definition at line 3769 of file data_sets.h.
#define NFREQ 1 |
Definition at line 3752 of file data_sets.h.
#define NFREQGAL 1 |
Definition at line 3763 of file data_sets.h.
#define NFREQGLO 1 |
Definition at line 3756 of file data_sets.h.
#define NSATCMP 0 |
Definition at line 3856 of file data_sets.h.
Definition at line 3825 of file data_sets.h.
Definition at line 3814 of file data_sets.h.
Definition at line 3808 of file data_sets.h.
#define NSATIRN 0 |
Definition at line 3867 of file data_sets.h.
#define NSATLEO 0 |
Definition at line 3878 of file data_sets.h.
#define NSATQZS 0 |
Definition at line 3845 of file data_sets.h.
Definition at line 3791 of file data_sets.h.
Definition at line 3881 of file data_sets.h.
#define NSYSCMP 0 |
Definition at line 3857 of file data_sets.h.
#define NSYSGAL 1 |
Definition at line 3826 of file data_sets.h.
#define NSYSGLO 1 |
Definition at line 3815 of file data_sets.h.
#define NSYSGPS 1 |
Definition at line 3809 of file data_sets.h.
#define NSYSIRN 0 |
Definition at line 3868 of file data_sets.h.
#define NSYSLEO 0 |
Definition at line 3879 of file data_sets.h.
#define NSYSQZS 0 |
Definition at line 3846 of file data_sets.h.
#define NUM_ANA_CHANNELS 4 |
Definition at line 1245 of file data_sets.h.
#define NUM_COM_PORTS 4 |
Definition at line 1256 of file data_sets.h.
#define NUM_IMU_DEVICES 2 |
Definition at line 164 of file data_sets.h.
#define NUM_SERIAL_PORTS 6 |
Definition at line 1258 of file data_sets.h.
#define NUM_WIFI_PRESETS 3 |
Definition at line 3121 of file data_sets.h.
#define NUMSATSOL 22 |
Definition at line 3776 of file data_sets.h.
#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.
#define PROTOCOL_VERSION_CHAR3 8 |
Definition at line 157 of file data_sets.h.
#define RECEIVER_INDEX_EXTERNAL_BASE 2 |
Definition at line 161 of file data_sets.h.
#define RECEIVER_INDEX_GPS1 1 |
Rtk rover receiver index
Definition at line 160 of file data_sets.h.
#define RECEIVER_INDEX_GPS2 3 |
Definition at line 162 of file data_sets.h.
#define RMC_BITS_BAROMETER 0x0000000000000040 |
Definition at line 1285 of file data_sets.h.
#define RMC_BITS_DIAGNOSTIC_MESSAGE 0x0000000000040000 |
Definition at line 1297 of file data_sets.h.
#define RMC_BITS_DUAL_IMU 0x0000000000000010 |
Definition at line 1283 of file data_sets.h.
#define RMC_BITS_DUAL_IMU_MAG 0x0000000400000000 |
Definition at line 1312 of file data_sets.h.
#define RMC_BITS_DUAL_IMU_MAG_RAW 0x0000000200000000 |
Definition at line 1311 of file data_sets.h.
#define RMC_BITS_DUAL_IMU_RAW 0x0000000000080000 |
Definition at line 1298 of file data_sets.h.
#define RMC_BITS_GPS1_POS 0x0000000000000400 |
Definition at line 1289 of file data_sets.h.
#define RMC_BITS_GPS1_RAW 0x0000000000001000 |
Definition at line 1291 of file data_sets.h.
#define RMC_BITS_GPS1_RTK_HDG_MISC 0x0000002000000000 |
Definition at line 1315 of file data_sets.h.
#define RMC_BITS_GPS1_RTK_HDG_REL 0x0000001000000000 |
Definition at line 1314 of file data_sets.h.
#define RMC_BITS_GPS1_RTK_POS 0x0000000000800000 |
Definition at line 1302 of file data_sets.h.
#define RMC_BITS_GPS1_RTK_POS_MISC 0x0000000004000000 |
Definition at line 1304 of file data_sets.h.
#define RMC_BITS_GPS1_RTK_POS_REL 0x0000000001000000 |
Definition at line 1303 of file data_sets.h.
#define RMC_BITS_GPS1_SAT 0x0000000000004000 |
Definition at line 1293 of file data_sets.h.
#define RMC_BITS_GPS1_UBX_POS 0x0000000000400000 |
Definition at line 1301 of file data_sets.h.
#define RMC_BITS_GPS1_VEL 0x0000000000100000 |
Definition at line 1299 of file data_sets.h.
#define RMC_BITS_GPS2_POS 0x0000000000000800 |
Definition at line 1290 of file data_sets.h.
#define RMC_BITS_GPS2_RAW 0x0000000000002000 |
Definition at line 1292 of file data_sets.h.
#define RMC_BITS_GPS2_SAT 0x0000000000008000 |
Definition at line 1294 of file data_sets.h.
#define RMC_BITS_GPS2_VEL 0x0000000000200000 |
Definition at line 1300 of file data_sets.h.
#define RMC_BITS_GPS_BASE_RAW 0x0000000000010000 |
Definition at line 1295 of file data_sets.h.
#define RMC_BITS_INL2_NED_SIGMA 0x0000000008000000 |
Definition at line 1305 of file data_sets.h.
#define RMC_BITS_INS1 0x0000000000000001 |
Definition at line 1279 of file data_sets.h.
#define RMC_BITS_INS2 0x0000000000000002 |
Definition at line 1280 of file data_sets.h.
#define RMC_BITS_INS3 0x0000000000000004 |
Definition at line 1281 of file data_sets.h.
#define RMC_BITS_INS4 0x0000000000000008 |
Definition at line 1282 of file data_sets.h.
#define RMC_BITS_INTERNAL_PPD 0x4000000000000000 |
Definition at line 1317 of file data_sets.h.
#define RMC_BITS_MAGNETOMETER1 0x0000000000000080 |
Definition at line 1286 of file data_sets.h.
#define RMC_BITS_MAGNETOMETER2 0x0000000000000100 |
Definition at line 1287 of file data_sets.h.
#define RMC_BITS_MASK 0x0FFFFFFFFFFFFFFF |
Definition at line 1316 of file data_sets.h.
#define RMC_BITS_PREINTEGRATED_IMU 0x0000000000000020 |
Definition at line 1284 of file data_sets.h.
#define RMC_BITS_PREINTEGRATED_IMU_MAG 0x0000000800000000 |
Definition at line 1313 of file data_sets.h.
#define RMC_BITS_PRESET 0x8000000000000000 |
Definition at line 1318 of file data_sets.h.
#define RMC_BITS_RTK_CODE_RESIDUAL 0x0000000020000000 |
Definition at line 1307 of file data_sets.h.
#define RMC_BITS_RTK_PHASE_RESIDUAL 0x0000000040000000 |
Definition at line 1308 of file data_sets.h.
#define RMC_BITS_RTK_STATE 0x0000000010000000 |
Definition at line 1306 of file data_sets.h.
#define RMC_BITS_STROBE_IN_TIME 0x0000000000020000 |
Definition at line 1296 of file data_sets.h.
#define RMC_BITS_WHEEL_CONFIG 0x0000000100000000 |
Definition at line 1310 of file data_sets.h.
#define RMC_BITS_WHEEL_ENCODER 0x0000000080000000 |
Definition at line 1309 of file data_sets.h.
#define RMC_OPTIONS_PERSISTENT 0x00000200 |
Definition at line 1276 of file data_sets.h.
#define RMC_OPTIONS_PORT_ALL (RMC_OPTIONS_PORT_MASK) |
Definition at line 1269 of file data_sets.h.
#define RMC_OPTIONS_PORT_CURRENT 0x00000000 |
Definition at line 1270 of file data_sets.h.
#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.
#define RMC_OPTIONS_PORT_SER0 0x00000001 |
Definition at line 1271 of file data_sets.h.
#define RMC_OPTIONS_PORT_SER1 0x00000002 |
Definition at line 1272 of file data_sets.h.
#define RMC_OPTIONS_PORT_SER2 0x00000004 |
Definition at line 1273 of file data_sets.h.
#define RMC_OPTIONS_PORT_USB 0x00000008 |
Definition at line 1274 of file data_sets.h.
#define RMC_OPTIONS_PRESERVE_CTRL 0x00000100 |
Definition at line 1275 of file data_sets.h.
#define RMC_PRESET_INS_BITS |
Definition at line 1342 of file data_sets.h.
#define RMC_PRESET_INS_NAV_PERIOD_MULT 1 |
Definition at line 1321 of file data_sets.h.
#define RMC_PRESET_PPD_BITS |
Definition at line 1340 of file data_sets.h.
#define RMC_PRESET_PPD_BITS_NO_IMU |
Definition at line 1324 of file data_sets.h.
#define RMC_PRESET_PPD_BITS_RAW_IMU |
Definition at line 1345 of file data_sets.h.
#define RMC_PRESET_PPD_BITS_RTK_DBG |
Definition at line 1347 of file data_sets.h.
#define RMC_PRESET_PPD_NAV_PERIOD_MULT 25 |
Definition at line 1320 of file data_sets.h.
#define RMC_PRESET_PPD_ROBOT |
Definition at line 1351 of file data_sets.h.
#define SBAS_EPHEMERIS_ARRAY_SIZE NSATSBS |
Definition at line 3793 of file data_sets.h.
#define SECONDS_PER_DAY 86400 |
Definition at line 3689 of file data_sets.h.
#define SECONDS_PER_WEEK 604800 |
Definition at line 3688 of file data_sets.h.
#define SET_STATUS_OFFSET_MASK | ( | result, | |
val, | |||
offset, | |||
mask | |||
) | { (result) &= ~((mask)<<(offset)); (result) |= ((val)<<(offset)); } |
Definition at line 1833 of file data_sets.h.
#define SYS_ALL 0xFF /* navigation system: all */ |
Definition at line 3720 of file data_sets.h.
#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.
#define SYS_CMP 0x20 /* navigation system: BeiDou */ |
Definition at line 3717 of file data_sets.h.
#define SYS_FAULT_STATUS_BUS_FAULT 0x00080000 |
Definition at line 3296 of file data_sets.h.
#define SYS_FAULT_STATUS_ENABLE_BOOTLOADER 0x00000002 |
Definition at line 3285 of file data_sets.h.
#define SYS_FAULT_STATUS_FLASH_MIGRATION_COMPLETED 0x00000040 |
Definition at line 3289 of file data_sets.h.
#define SYS_FAULT_STATUS_FLASH_MIGRATION_EVENT 0x00000020 |
Definition at line 3288 of file data_sets.h.
#define SYS_FAULT_STATUS_FLASH_MIGRATION_MARKER_UPDATED 0x00800000 |
Definition at line 3300 of file data_sets.h.
#define SYS_FAULT_STATUS_HARD_FAULT 0x00010000 |
Definition at line 3293 of file data_sets.h.
#define SYS_FAULT_STATUS_HARDWARE_DETECTION 0x08000000 |
Definition at line 3304 of file data_sets.h.
#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.
#define SYS_FAULT_STATUS_INVALID_CODE_OPERATION 0x00400000 |
Definition at line 3299 of file data_sets.h.
#define SYS_FAULT_STATUS_MALLOC_FAILED 0x00100000 |
Definition at line 3297 of file data_sets.h.
#define SYS_FAULT_STATUS_MASK_CRITICAL_ERROR 0xFFFF0000 |
Definition at line 3305 of file data_sets.h.
#define SYS_FAULT_STATUS_MASK_GENERAL_ERROR 0xFFFFFFF0 |
Definition at line 3291 of file data_sets.h.
#define SYS_FAULT_STATUS_MEM_MANGE 0x00040000 |
Definition at line 3295 of file data_sets.h.
#define SYS_FAULT_STATUS_RTK_BUFFER_LIMIT 0x02000000 |
Definition at line 3302 of file data_sets.h.
#define SYS_FAULT_STATUS_RTK_MISC_ERROR 0x00000080 |
Definition at line 3290 of file data_sets.h.
#define SYS_FAULT_STATUS_SENSOR_CALIBRATION 0x04000000 |
Definition at line 3303 of file data_sets.h.
#define SYS_FAULT_STATUS_SOFT_RESET 0x00000010 |
Definition at line 3287 of file data_sets.h.
#define SYS_FAULT_STATUS_STACK_OVERFLOW 0x00200000 |
Definition at line 3298 of file data_sets.h.
#define SYS_FAULT_STATUS_USAGE_FAULT 0x00020000 |
Definition at line 3294 of file data_sets.h.
#define SYS_FAULT_STATUS_USER_RESET 0x00000001 |
Definition at line 3284 of file data_sets.h.
#define SYS_FAULT_STATUS_WATCHDOG_RESET 0x01000000 |
Definition at line 3301 of file data_sets.h.
#define SYS_GAL 0x08 /* navigation system: Galileo */ |
Definition at line 3715 of file data_sets.h.
#define SYS_GLO 0x04 /* navigation system: GLONASS */ |
Definition at line 3714 of file data_sets.h.
#define SYS_GPS 0x01 /* navigation system: GPS */ |
Definition at line 3712 of file data_sets.h.
#define SYS_IRN 0x40 /* navigation system: IRNS */ |
Definition at line 3718 of file data_sets.h.
#define SYS_LEO 0x80 /* navigation system: LEO */ |
Definition at line 3719 of file data_sets.h.
#define SYS_NONE 0x00 /* navigation system: none */ |
Definition at line 3711 of file data_sets.h.
#define SYS_QZS 0x10 /* navigation system: QZSS */ |
Definition at line 3716 of file data_sets.h.
#define SYS_SBS 0x02 /* navigation system: SBAS */ |
Definition at line 3713 of file data_sets.h.
#define WIFI_SSID_PSK_SIZE 40 |
Definition at line 3085 of file data_sets.h.
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
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
typedef struct PACKED barometer_t |
(DID_BAROMETER) Barometric pressure sensor data
typedef struct PACKED can_config_t |
(DID_CAN_BCAST_PERIOD) Broadcast period of CAN messages
typedef struct PACKED debug_array_t |
typedef struct PACKED debug_string_t |
typedef struct PACKED dev_info_t |
(DID_DEV_INFO) Device information
typedef struct PACKED dual_imu_ok_t |
Dual Inertial Measurement Units (IMUs) data valid flags
typedef struct PACKED dual_imu_t |
(DID_DUAL_IMU) Dual Inertial Measurement Units (IMUs) data
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.
typedef struct PACKED evb_rtos_info_t |
(DID_EVB_RTOS_INFO)
typedef struct PACKED gen_1axis_sensor_t |
Generic 1 axis sensor
typedef struct PACKED gen_3axis_sensor_t |
Generic 3 axis sensor
typedef struct PACKED gen_3axis_sensord_t |
Generic 3 axis sensor
typedef struct PACKED gen_dual_3axis_sensor_t |
Generic dual 3 axis sensor
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.
typedef struct PACKED gps_rtk_misc_t |
(DID_GPS1_RTK_POS_MISC, DID_GPS2_RTK_CMP_MISC) - requires little endian CPU
typedef prcopt_t gps_rtk_opt_t |
Definition at line 2375 of file data_sets.h.
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.
typedef struct PACKED gps_sat_sv_t |
GPS Satellite information
typedef struct PACKED gps_version_t |
(DID_GPS1_VERSION) GPS version strings
typedef struct PACKED inl2_mag_obs_info_t |
typedef struct PACKED inl2_ned_sigma_t |
INL2 - Estimate error variances
typedef struct PACKED inl2_states_t |
typedef struct PACKED inl2_status_t |
(DID_INS_1) INS output: euler rotation w/ respect to NED, NED position from reference LLA
(DID_INS_2) INS output: quaternion rotation w/ respect to NED, ellipsoid altitude
(DID_INS_3) INS output: quaternion rotation w/ respect to NED, msl altitude
(DID_INS_4) INS output: quaternion rotation w/ respect to ECEF, ECEF position
typedef struct PACKED ins_output_t |
INS output
typedef struct PACKED magnetometer_t |
(DID_MAGNETOMETER_1, DID_MAGNETOMETER_2) Magnetometer sensor data
typedef struct PACKED manufacturing_info_t |
(DID_MANUFACTURING_INFO) Manufacturing info
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.
typedef struct PACKED pimu_mag_t |
DID DID_PREINTEGRATED_IMU_MAG, dual pre-integrated imu + mag1 + mag2
typedef PUSH_PACK_1 struct PACKED pos_measurement_t |
(DID_POSITION_MEASUREMENT) External position estimate
typedef struct PACKED preintegrated_imu_t |
(DID_PREINTEGRATED_IMU) Coning and sculling integral in body/IMU frame.
typedef struct PACKED rtk_debug_t |
typedef struct PACKED rtk_residual_t |
typedef struct PACKED rtk_state_t |
typedef struct PACKED rtos_info_t |
(DID_RTOS_INFO)
typedef struct PACKED rtos_task_t |
RTOS task info
typedef struct PACKED sensors_mpu_w_temp_t |
typedef struct PACKED strobe_in_time_t |
(DID_STROBE_IN_TIME) Timestamp for input strobe.
typedef struct PACKED sys_params_t |
(DID_SYS_PARAMS) System parameters
typedef struct PACKED sys_sensors_adc_t |
typedef struct PACKED sys_sensors_t |
(DID_SYS_SENSORS) Output from system sensors
typedef struct PACKED system_command_t |
(DID_SYS_CMD) System Commands
typedef union PACKED uGpsRawData |
typedef union PACKED uInsOutDatasets |
Union of INS output datasets
typedef struct PACKED wheel_config_t |
(DID_WHEEL_CONFIG) [NOT SUPPORTED, INTERNAL USE ONLY] Configuration of wheel encoders and kinematic constraints.
typedef struct PACKED wheel_encoder_t |
(DID_WHEEL_ENCODER) [NOT SUPPORTED, INTERNAL USE ONLY] Message to communicate wheel encoder measurements to GPS-INS
anonymous enum |
Definition at line 3477 of file data_sets.h.
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.
enum eCalBitStatusFlags |
Calibration built-in test flags
Definition at line 1455 of file data_sets.h.
EVB-2 Communications Bridge Options
Definition at line 3036 of file data_sets.h.
enum eEvb2ComBridgePreset |
EVB-2 communications bridge configuration.
Definition at line 3205 of file data_sets.h.
enum 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.
enum 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.
enum eEvb2PortOptions |
Enumerator | |
---|---|
EVB2_PORT_OPTIONS_RADIO_RTK_FILTER | |
EVB2_PORT_OPTIONS_DEFAULT |
Definition at line 3048 of file data_sets.h.
enum eEvbFlashCfgBits |
Definition at line 3110 of file data_sets.h.
enum eEvbRtosTask |
EVB RTOS tasks
Definition at line 3380 of file data_sets.h.
enum eEvbStatus |
Definition at line 2982 of file data_sets.h.
enum eGenFaultCodes |
General Fault Code descriptor
Definition at line 1083 of file data_sets.h.
enum eGnssSatSigConst |
GNSS satellite system signal constellation (used with DID_FLASH_CONFIG.gnssSatSigConst)
Definition at line 1561 of file data_sets.h.
enum 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.
enum eGpsStatus |
GPS Status
Definition at line 360 of file data_sets.h.
enum eHdwBitStatusFlags |
Hardware built-in test flags
Definition at line 1434 of file data_sets.h.
enum eHdwStatusFlags |
Hardware status flags
Definition at line 277 of file data_sets.h.
enum eImuStatus |
IMU Status
Definition at line 730 of file data_sets.h.
enum 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.
enum eInsStatusFlags |
INS status flags
Definition at line 167 of file data_sets.h.
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.
enum 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.
enum eRawDataType |
RAW data types for DID_GPS_BASE_RAW and DID_GPS2_RAW
Definition at line 2856 of file data_sets.h.
enum 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.
enum eRtkSolStatus |
RTK solution status
Definition at line 2695 of file data_sets.h.
enum eRtosTask |
RTOS tasks
Definition at line 3355 of file data_sets.h.
enum eSatSvFlags |
GPS Status
Definition at line 843 of file data_sets.h.
enum eSensorConfig |
Sensor Configuration
Definition at line 1732 of file data_sets.h.
enum eSurveyInStatus |
Definition at line 2938 of file data_sets.h.
enum eSysConfigBits |
System Configuration (used with DID_FLASH_CONFIG.sysCfgBits)
Definition at line 1521 of file data_sets.h.
enum eSystemCommand |
Definition at line 1129 of file data_sets.h.
enum 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.
POP_PACK uint32_t checksum32 | ( | const void * | data, |
int | count | ||
) |
Creates a 32 bit checksum from data
data | the data to create a checksum for |
count | the number of bytes in data |
Definition at line 531 of file data_sets.c.
uint64_t didToRmcBit | ( | uint32_t | dataId, |
uint64_t | defaultRmcBits | ||
) |
Convert DID to realtime message bits
Definition at line 563 of file data_sets.c.
uint32_t flashChecksum32 | ( | const void * | data, |
int | size | ||
) |
Definition at line 557 of file data_sets.c.
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
ptr | the double to flip |
Definition at line 47 of file data_sets.c.
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
val | the double to flip |
Definition at line 60 of file data_sets.c.
void flipDoubles | ( | uint8_t * | data, |
int | dataLength, | ||
int | offset, | ||
uint16_t * | offsets, | ||
uint16_t | offsetsLength | ||
) |
Flip double (64 bit) floating point values in data
data | the data to flip doubles in |
dataLength | the number of bytes in data |
offset | offset into data to start flipping at |
offsets | a list of offsets of all doubles in data, starting at position 0 |
offsetsLength | the number of items in offsets |
Definition at line 91 of file data_sets.c.
void flipEndianess32 | ( | uint8_t * | data, |
int | dataLength | ||
) |
Flip the endianess of 32 bit values in data
data | the data to flip 32 bit values in |
dataLength | the number of bytes in data |
Definition at line 73 of file data_sets.c.
void flipFloat | ( | uint8_t * | ptr | ) |
Flip the bytes of a float in place (4 bytes) - ptr is assumed to be at least 4 bytes
ptr | the float to flip |
Definition at line 19 of file data_sets.c.
float flipFloatCopy | ( | float | val | ) |
Flip the bytes of a float (4 bytes) - ptr is assumed to be at least 4 bytes
val | the float to flip |
Definition at line 31 of file data_sets.c.
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
data | the data to flip string values in |
dataLength | the number of bytes in data |
offset | the offset into data to start flipping strings at |
offsets | a list of offsets and byte lengths into data where strings start at |
offsetsLength | the number of items in offsets, should be 2 times the string count |
Definition at line 117 of file data_sets.c.
uint16_t* getDoubleOffsets | ( | eDataIDs | dataId, |
uint16_t * | offsetsLength | ||
) |
Get the offsets of double / int64 (64 bit) values given a data id
dataId | the data id to get double offsets for |
offsetsLength | receives the number of double offsets |
Definition at line 141 of file data_sets.c.
uint16_t* getStringOffsetsLengths | ( | eDataIDs | dataId, |
uint16_t * | offsetsLength | ||
) |
Gets the offsets and lengths of strings given a data id
dataId | the data id to get string offsets and lengths for |
offsetsLength | receives the number of items in the return value |
Definition at line 382 of file data_sets.c.
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.
int gpsToNmeaGGA | ( | const gps_pos_t * | gps, |
char * | buffer, | ||
int | bufferLength | ||
) |
Definition at line 745 of file data_sets.c.
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.
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.
int satNo | ( | int | sys, |
int | prn | ||
) |
Definition at line 868 of file data_sets.c.
int satNumCalc | ( | int | gnssID, |
int | svID | ||
) |
Definition at line 908 of file data_sets.c.
uint32_t serialNumChecksum32 | ( | const void * | data, |
int | size | ||
) |
Definition at line 551 of file data_sets.c.
int ubxSys | ( | int | gnssID | ) |
Definition at line 849 of file data_sets.c.