#include <communications.h>
Velocity in ECEF
WGS84 latitude (degrees)
WGS84 longitude (degrees)
WGS84 height above ellipsoid (meters)
North offset from reference LLA
Down offset from reference LLA
X Position in ECEF (earth-centered earth-fixed) frame in meters
Y Position in ECEF (earth-centered earth-fixed) frame in meters
Z Position in ECEF (earth-centered earth-fixed) frame in meters
Height above Mean Sea Level
Preintegrated IMU values delta theta and delta velocity (X axis), and Integral period in body/IMU frame of accelerometer 0.
Preintegrated IMU values delta theta and delta velocity (Y axis), and Integral period in body/IMU frame of accelerometer 0.
Preintegrated IMU values delta theta and delta velocity (Z axis), and Integral period in body/IMU frame of accelerometer 0.
(DID_POSITION_MEASUREMENT) External position estimate
(DID_DEV_INFO) Device information
(DID_MANUFACTURING_INFO) Manufacturing info
(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
Inertial Measurement Unit (IMU) data
(DID_DUAL_IMU) Dual Inertial Measurement Units (IMUs) data
Dual Inertial Measurement Units (IMUs) data valid flags
(DID_MAGNETOMETER_1, DID_MAGNETOMETER_2) Magnetometer sensor data
(DID_BAROMETER) Barometric pressure sensor data
(DID_PREINTEGRATED_IMU) Coning and sculling integral in body/IMU frame.
DID_DUAL_IMU_RAW_MAG, DID_DUAL_IMU_MAG, dual imu + mag1 + mag2
DID DID_PREINTEGRATED_IMU_MAG, dual pre-integrated imu + mag1 + mag2
(DID_GPS1_POS, DID_GPS1_UBX_POS, DID_GPS2_POS) GPS position data
(DID_GPS1_VEL, DID_GPS2_VEL) GPS velocity data
GPS Satellite information
(DID_GPS1_SAT) GPS satellite signal strength
(DID_GPS1_VERSION) GPS version strings
Generic 1 axis sensor
Generic 3 axis sensor
Generic dual 3 axis sensor
(DID_SYS_SENSORS) Output from system sensors
INS output
(DID_SYS_PARAMS) System parameters
(DID_SYS_CMD) System Commands
(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
(DID_RMC) Realtime message controller (RMC).
(DID_IO) Input/Output
(DID_MAG_CAL) Magnetometer Calibration
(DID_BIT) Built-in self-test parameters
(DID_WHEEL_ENCODER) [NOT SUPPORTED, INTERNAL USE ONLY] Message to communicate wheel encoder measurements to GPS-INS
(DID_WHEEL_CONFIG) [NOT SUPPORTED, INTERNAL USE ONLY] Configuration of wheel encoders and kinematic constraints.
(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.
INL2 - Estimate error variances
(DID_STROBE_IN_TIME) Timestamp for input strobe.
Raw satellite observation data
(DID_GPS1_RTK_POS_REL, DID_GPS2_RTK_CMP_REL) - RTK and Dual GNSS heading base to rover relative info.
(DID_GPS1_RTK_POS_MISC, DID_GPS2_RTK_CMP_MISC) - requires little endian CPU
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.
RTOS task info
(DID_RTOS_INFO)
(DID_EVB_RTOS_INFO)
(DID_CAN_BCAST_PERIOD) Broadcast period of CAN messages
Union of datasets
Union of INS output datasets
Definition at line 51 of file communications.h.
float PACKED::acc |
Acceleration X, Y, Z in meters / second squared
Accelerometers in meters / second squared
ACC motion w/ gravity removed (linear acceleration)
Definition at line 606 of file data_sets.h.
f_t PACKED::acc[3] |
Definition at line 1240 of file data_sets.h.
int PACKED::accel_motion |
Definition at line 926 of file data_sets.h.
float PACKED::accSigma |
Acceleration standard deviation
Definition at line 1515 of file data_sets.h.
float PACKED::accuracyCov[3] |
Accuracy - estimated standard deviations of the solution assuming a priori error model and error parameters by the positioning options. []: Absolute value of means square root of estimated covariance NE, EU, UN
Definition at line 2755 of file data_sets.h.
float PACKED::accuracyCovUD[6] |
The Upper Diagonal of accuracy covariance matrix
Definition at line 426 of file data_sets.h.
float PACKED::accuracyPos[3] |
Accuracy - estimated standard deviations of the solution assuming a priori error model and error parameters by the positioning options. []: standard deviations {ECEF - x,y,z} or {north, east, down} (meters)
Definition at line 2752 of file data_sets.h.
uint32_t PACKED::activeCalSet |
Definition at line 1413 of file data_sets.h.
char PACKED::addInfo[DEVINFO_ADDINFO_STRLEN] |
Additional info
Definition at line 469 of file data_sets.h.
uint32_t PACKED::address |
Definition at line 54 of file communications.h.
int PACKED::ahrs |
Definition at line 923 of file data_sets.h.
int PACKED::ahrs_gps_cnt |
Definition at line 929 of file data_sets.h.
float PACKED::alt |
WGS84 height above ellipsoid (meters)
Definition at line 112 of file CAN_comm.h.
is_can_ins_alt PACKED::alt |
Definition at line 261 of file CAN_comm.h.
f_t PACKED::ana[NUM_ANA_CHANNELS] |
Definition at line 1253 of file data_sets.h.
float PACKED::ana1 |
ADC analog input in volts. uINS pin 4, (G1/AN1).
Definition at line 1017 of file data_sets.h.
float PACKED::ana3 |
ADC analog input in volts. uINS pin 19 (G3/AN3).
Definition at line 1020 of file data_sets.h.
float PACKED::ana4 |
ADC analog input in volts. uINS pin 20 (G4/AN4).
Definition at line 1023 of file data_sets.h.
uint8_t PACKED::arRatio |
Ambiguity resolution ratio factor for validation
Definition at line 232 of file CAN_comm.h.
float PACKED::arRatio |
Ambiguity resolution ratio factor for validation
Definition at line 2726 of file data_sets.h.
float PACKED::arThreshold |
Ambiguity resolution threshold for validation
Definition at line 2758 of file data_sets.h.
int PACKED::att_aligned |
Definition at line 932 of file data_sets.h.
int PACKED::att_aligning |
Definition at line 933 of file data_sets.h.
int PACKED::att_coarse |
Definition at line 931 of file data_sets.h.
float PACKED::att_err |
Definition at line 930 of file data_sets.h.
uint32_t PACKED::auto_recal |
Definition at line 1405 of file data_sets.h.
float PACKED::averageRunTimeUs |
Rolling average over last 1000 executions
Definition at line 3432 of file data_sets.h.
int16_t PACKED::azim |
(deg) Azimuth (range: +/-180)
Definition at line 832 of file data_sets.h.
double PACKED::b[24] |
Definition at line 2141 of file data_sets.h.
uint8_t PACKED::bad_baseline_holdamb |
Definition at line 2167 of file data_sets.h.
float PACKED::bar |
Barometric pressure in kilopascals
Definition at line 666 of file data_sets.h.
f_t PACKED::bar |
Definition at line 1250 of file data_sets.h.
barometer_t PACKED::baro |
Definition at line 3536 of file data_sets.h.
float PACKED::baroTemp |
Baro temperature
Definition at line 1058 of file data_sets.h.
float PACKED::barTemp |
Temperature of barometric pressure sensor in Celsius
Definition at line 672 of file data_sets.h.
f_t PACKED::barTemp |
Definition at line 1251 of file data_sets.h.
uint8_t PACKED::base_position_error |
Definition at line 2168 of file data_sets.h.
uint8_t PACKED::base_position_update |
Definition at line 2175 of file data_sets.h.
uint32_t PACKED::baseAntennaCount |
Base station antenna position element counter
Definition at line 2842 of file data_sets.h.
uint32_t PACKED::baseBeidouEphemerisCount |
Base station beidou ephemeris element counter
Definition at line 2827 of file data_sets.h.
uint32_t PACKED::baseBeidouObservationCount |
Base station beidou observation element counter
Definition at line 2797 of file data_sets.h.
uint32_t PACKED::baseGalileoEphemerisCount |
Base station galileo ephemeris element counter
Definition at line 2821 of file data_sets.h.
uint32_t PACKED::baseGalileoObservationCount |
Base station galileo observation element counter
Definition at line 2791 of file data_sets.h.
uint32_t PACKED::baseGlonassEphemerisCount |
Base station glonass ephemeris element counter
Definition at line 2815 of file data_sets.h.
uint32_t PACKED::baseGlonassObservationCount |
Base station glonass observation element counter
Definition at line 2785 of file data_sets.h.
uint32_t PACKED::baseGpsEphemerisCount |
Base station gps ephemeris element counter
Definition at line 2809 of file data_sets.h.
uint32_t PACKED::baseGpsObservationCount |
Base station gps observation element counter
Definition at line 2779 of file data_sets.h.
double PACKED::baseLla[3] |
Base Position - latitude, longitude, height (degrees, meters)
Definition at line 2770 of file data_sets.h.
uint32_t PACKED::baseQzsEphemerisCount |
Base station qzs ephemeris element counter
Definition at line 2833 of file data_sets.h.
uint32_t PACKED::baseQzsObservationCount |
Base station qzs observation element counter
Definition at line 2803 of file data_sets.h.
uint32_t PACKED::baseSbasCount |
Base station sbas element counter
Definition at line 2839 of file data_sets.h.
float PACKED::baseToRoverDistance |
Distance from base to rover (m)
Definition at line 2732 of file data_sets.h.
float PACKED::baseToRoverHeading |
Angle from north to baseToRoverVector in local tangent plane. (rad)
Definition at line 2735 of file data_sets.h.
float PACKED::baseToRoverHeadingAcc |
Accuracy of baseToRoverHeading. (rad)
Definition at line 2738 of file data_sets.h.
float PACKED::baseToRoverVector[3] |
Vector from base to rover (m) in ECEF - If Compassing enabled, this is the 3-vector from antenna 2 to antenna 1
Definition at line 2729 of file data_sets.h.
float PACKED::bias_cal[3] |
Definition at line 1416 of file data_sets.h.
float PACKED::biasAcc[3] |
(m/s^2) Accelerometer bias
Definition at line 909 of file data_sets.h.
float PACKED::biasBaro |
(m) Barometer bias
Definition at line 912 of file data_sets.h.
float PACKED::biasPqr[3] |
(rad/s) Gyro bias
Definition at line 906 of file data_sets.h.
uint64_t PACKED::bits |
Data stream enable bits for the specified ports. (see RMC_BITS_...)
Definition at line 1359 of file data_sets.h.
uint32_t PACKED::bits |
Config bits (see eWheelCfgBits)
Definition at line 1925 of file data_sets.h.
double PACKED::bp_ecef[3] |
Definition at line 2138 of file data_sets.h.
uint8_t PACKED::buf[GPS_RAW_MESSAGE_BUF_SIZE] |
Byte buffer
Definition at line 2901 of file data_sets.h.
uint8_t PACKED::buildDate[4] |
Build date, little endian order: [0] = status ('r'=release, 'd'=debug), [1] = year-2000, [2] = month, [3] = day. Reversed byte order for big endian systems
Definition at line 463 of file data_sets.h.
uint32_t PACKED::buildNumber |
Build number
Definition at line 451 of file data_sets.h.
uint8_t PACKED::buildTime[4] |
Build date, little endian order: [0] = hour, [1] = minute, [2] = second, [3] = millisecond. Reversed byte order for big endian systems
Definition at line 466 of file data_sets.h.
double PACKED::bv_ecef[3] |
Definition at line 2139 of file data_sets.h.
uint32_t PACKED::calBitStatus |
Calibration BIT status (see eCalBitStatusFlags)
Definition at line 1491 of file data_sets.h.
uint32_t PACKED::calibrated |
Definition at line 1404 of file data_sets.h.
uint32_t PACKED::can_baudrate_kbps |
Baudrate (kbps)
Definition at line 3517 of file data_sets.h.
uint32_t PACKED::can_period_mult[NUM_CIDS] |
Broadcast period (ms) - CAN time message. 0 to disable.
Definition at line 3511 of file data_sets.h.
uint32_t PACKED::can_receive_address |
Receive address.
Definition at line 3520 of file data_sets.h.
uint32_t PACKED::can_transmit_address[NUM_CIDS] |
Transmit address.
Definition at line 3514 of file data_sets.h.
uint32_t PACKED::cBrdConfig |
Carrier board (i.e. eval board) configuration bits
Definition at line 2021 of file data_sets.h.
uint32_t PACKED::checksum |
Checksum, excluding size and checksum
Definition at line 1964 of file data_sets.h.
uint8_t PACKED::chi_square_error |
Definition at line 2193 of file data_sets.h.
uint8_t PACKED::cno |
(dBHz) Carrier to noise ratio (signal strength)
Definition at line 826 of file data_sets.h.
uint32_t PACKED::cnoMean |
Average of all satellite carrier to noise ratios (signal strengths) that non-zero in dBHz
Definition at line 226 of file CAN_comm.h.
float PACKED::cnoMean |
Average of all satellite carrier to noise ratios (signal strengths) that non-zero in dBHz
Definition at line 784 of file data_sets.h.
uint8_t PACKED::code[1] |
Code indicator: CODE_L1C (1) = L1C/A,G1C/A,E1C (GPS,GLO,GAL,QZS,SBS), CODE_L1X (12) = E1B+C,L1C(D+P) (GAL,QZS), CODE_L1I (47) = B1I (BeiDou)
Definition at line 2396 of file data_sets.h.
uint8_t PACKED::code_large_residual |
Definition at line 2163 of file data_sets.h.
uint8_t PACKED::code_outlier |
Definition at line 2161 of file data_sets.h.
uint32_t PACKED::command |
System commands (see eSystemCommand) 1=save current persistent messages, 5=zero motion, 97=save flash, 99=software reset. "invCommand" (following variable) must be set to bitwise inverse of this value for this command to be processed.
Definition at line 1122 of file data_sets.h.
uint32_t PACKED::correctionChecksumFailures |
Number of checksum failures from received corrections
Definition at line 2848 of file data_sets.h.
uint32_t PACKED::count |
Strobe serial index number
Definition at line 2095 of file data_sets.h.
float PACKED::cpuUsage |
Cpu usage percent
Definition at line 3438 of file data_sets.h.
uint32_t PACKED::cycle_slips |
Definition at line 2195 of file data_sets.h.
uint32_t PACKED::cycleSlipCount |
Cycle slip counter
Definition at line 2773 of file data_sets.h.
float PACKED::D[1] |
Observation data Doppler measurement (positive sign for approaching satellites) (Hz)
Definition at line 2414 of file data_sets.h.
uGpsRawData PACKED::data |
Interpret based on dataType (see eRawDataType)
Definition at line 2920 of file data_sets.h.
uint8_t PACKED::dataType |
Type of data (eRawDataType: 1=observations, 2=ephemeris, 3=glonassEphemeris, 4=SBAS, 5=baseAntenna, 6=IonosphereModel)
Definition at line 2911 of file data_sets.h.
char PACKED::date[16] |
Manufacturing date (YYYYMMDDHHMMSS)
Definition at line 482 of file data_sets.h.
uint8_t PACKED::debug[2] |
Definition at line 2213 of file data_sets.h.
float PACKED::declination |
Magnetic declination estimate
Definition at line 1396 of file data_sets.h.
dev_info_t PACKED::devInfo |
Definition at line 3527 of file data_sets.h.
float PACKED::diameter |
Estimate of wheel diameter
Definition at line 1937 of file data_sets.h.
uint8_t PACKED::diff_age_error |
Definition at line 2185 of file data_sets.h.
uint8_t PACKED::differentialAge |
Age of differential (seconds)
Definition at line 234 of file CAN_comm.h.
float PACKED::differentialAge |
Age of differential (seconds)
Definition at line 2723 of file data_sets.h.
is_can_dual_imu_px PACKED::dimupx |
Definition at line 271 of file CAN_comm.h.
is_can_dual_imu_qy PACKED::dimuqy |
Definition at line 272 of file CAN_comm.h.
is_can_dual_imu_rz PACKED::dimurz |
Definition at line 273 of file CAN_comm.h.
float PACKED::dist2base |
Definition at line 2204 of file data_sets.h.
float PACKED::distance |
Distance between the left wheel and the right wheel
Definition at line 1934 of file data_sets.h.
float PACKED::distanceToBase |
Distance to Base (m)
Definition at line 236 of file CAN_comm.h.
uint8_t PACKED::divergent_pnt_pos_iteration |
Definition at line 2192 of file data_sets.h.
uint8_t PACKED::dlc |
Definition at line 55 of file communications.h.
double PACKED::double_debug[4] |
Definition at line 2211 of file data_sets.h.
is_can_down PACKED::down |
Definition at line 263 of file CAN_comm.h.
uint16_t PACKED::dt |
Integral period in seconds for delta theta and delta velocity (scaled by 1000).
Definition at line 174 of file CAN_comm.h.
float PACKED::dt |
Integral period in seconds for delta theta and delta velocity. This is configured using DID_FLASH_CONFIG.startupNavDtMs.
Definition at line 698 of file data_sets.h.
dual_imu_t PACKED::dualImu |
Definition at line 3533 of file data_sets.h.
float PACKED::e_i2l[3] |
Euler angles describing the rotation from imu to left wheel
Definition at line 1928 of file data_sets.h.
double PACKED::ecef |
Position in ECEF (earth-centered earth-fixed) frame in meters
Position in ECEF {x,y,z} (m)
(m) Position in ECEF frame
Definition at line 420 of file data_sets.h.
double PACKED::ecef1 |
X Position in ECEF (earth-centered earth-fixed) frame in meters
Definition at line 141 of file CAN_comm.h.
double PACKED::ecef2 |
Y Position in ECEF (earth-centered earth-fixed) frame in meters
Definition at line 149 of file CAN_comm.h.
double PACKED::ecef3 |
Z Position in ECEF (earth-centered earth-fixed) frame in meters
Definition at line 157 of file CAN_comm.h.
is_can_ecef_x PACKED::ecefx |
Definition at line 264 of file CAN_comm.h.
is_can_ecef_y PACKED::ecefy |
Definition at line 265 of file CAN_comm.h.
is_can_ecef_z PACKED::ecefz |
Definition at line 266 of file CAN_comm.h.
int8_t PACKED::elev |
(deg) Elevation (range: +/-90)
Definition at line 829 of file data_sets.h.
uint8_t PACKED::end_relpos |
Definition at line 2180 of file data_sets.h.
uint8_t PACKED::endByte |
Definition at line 57 of file communications.h.
eph_t PACKED::eph |
Satellite non-GLONASS ephemeris data (GPS, Galileo, Beidou, QZSS)
Definition at line 2886 of file data_sets.h.
uint8_t PACKED::error_code |
Definition at line 2202 of file data_sets.h.
uint8_t PACKED::error_count |
Definition at line 2201 of file data_sets.h.
is_can_ins_euler PACKED::euler |
Definition at line 254 of file CAN_comm.h.
uint8_t PACKED::extension[30] |
Extension
Definition at line 885 of file data_sets.h.
f_t PACKED::f[DEBUG_F_ARRAY_SIZE] |
Definition at line 2106 of file data_sets.h.
uint8_t PACKED::firmwareVer[4] |
Firmware (software) version
Definition at line 448 of file data_sets.h.
uint32_t PACKED::flags |
(see eSatSvFlags)
Definition at line 838 of file data_sets.h.
nvm_flash_cfg_t PACKED::flashCfg |
Definition at line 3547 of file data_sets.h.
uint32_t PACKED::freeHeapSize |
Heap high water mark bytes
Definition at line 3448 of file data_sets.h.
uint32_t PACKED::freeSize |
Total memory freed using RTOS vPortFree()
Definition at line 3454 of file data_sets.h.
union { ... } PACKED::g0 |
union { ... } PACKED::g1 |
uint32_t PACKED::gapCount |
Counter of times task took too long to run
Definition at line 3435 of file data_sets.h.
float PACKED::gDop |
Geometric dilution of precision (meters)
Definition at line 2761 of file data_sets.h.
uint8_t PACKED::gdop_error |
Definition at line 2207 of file data_sets.h.
uint32_t PACKED::genFaultCode |
General fault code descriptor (eGenFaultCodes). Set to zero to reset fault code.
Definition at line 1079 of file data_sets.h.
geph_t PACKED::gloEph |
Satellite GLONASS ephemeris data
Definition at line 2889 of file data_sets.h.
uint8_t PACKED::gnssId |
GNSS identifier: 0 GPS, 1 SBAS, 2 Galileo, 3 BeiDou, 5 QZSS, 6 GLONASS
Definition at line 820 of file data_sets.h.
uint16_t PACKED::gnssSatSigConst |
Satellite system constellation used in GNSS solution. (see eGnssSatSigConst) 0x0003=GPS, 0x000C=QZSS, 0x0030=Galileo, 0x00C0=Beidou, 0x0300=GLONASS, 0x1000=SBAS
Definition at line 1997 of file data_sets.h.
uint16_t PACKED::gpgga |
Broadcast period (ms) - ASCII NMEA GPGGA GPS 3D location, fix, and accuracy. 0 to disable.
Definition at line 1173 of file data_sets.h.
uint32_t PACKED::gpgga |
Broadcast period (ms) - ASCII NMEA GPGGA GPS 3D location, fix, and accuracy. 0 to disable.
Definition at line 1217 of file data_sets.h.
uint16_t PACKED::gpgll |
Broadcast period (ms) - ASCII NMEA GPGLL GPS 2D location and time. 0 to disable.
Definition at line 1176 of file data_sets.h.
uint32_t PACKED::gpgll |
Broadcast period (ms) - ASCII NMEA GPGLL GPS 2D location and time. 0 to disable.
Definition at line 1220 of file data_sets.h.
uint16_t PACKED::gpgsa |
Broadcast period (ms) - ASCII NMEA GSA GPS DOP and active satellites. 0 to disable.
Definition at line 1179 of file data_sets.h.
uint32_t PACKED::gpgsa |
Broadcast period (ms) - ASCII NMEA GSA GPS DOP and active satellites. 0 to disable.
Definition at line 1223 of file data_sets.h.
uint32_t PACKED::gpioStatus |
General purpose I/O status
Definition at line 1375 of file data_sets.h.
uint16_t PACKED::gprmc |
Broadcast period (ms) - ASCII NMEA recommended minimum specific GPS/Transit data. 0 to disable.
Definition at line 1182 of file data_sets.h.
uint32_t PACKED::gprmc |
Broadcast period (ms) - ASCII NMEA recommended minimum specific GPS/Transit data. 0 to disable.
Definition at line 1226 of file data_sets.h.
float PACKED::gps1AntOffset[3] |
X,Y,Z offset in meters from Sensor Frame origin to GPS 1 antenna.
Definition at line 1988 of file data_sets.h.
float PACKED::gps2AntOffset[3] |
X,Y,Z offset in meters from DOD_ Frame origin to GPS 2 antenna.
Definition at line 2024 of file data_sets.h.
float PACKED::gpsMinimumElevation |
Minimum elevation of a satellite above the horizon to be used in the solution (radians). Low elevation satellites may provide degraded accuracy, due to the long signal path through the atmosphere.
Definition at line 2054 of file data_sets.h.
is_can_gps1_pos_status PACKED::gpspos |
Definition at line 274 of file CAN_comm.h.
gps_pos_t PACKED::gpsPos |
Definition at line 3540 of file data_sets.h.
gps_raw_t PACKED::gpsRaw |
Definition at line 3552 of file data_sets.h.
gps_rtk_misc_t PACKED::gpsRtkMisc |
Definition at line 3544 of file data_sets.h.
gps_rtk_rel_t PACKED::gpsRtkRel |
Definition at line 3543 of file data_sets.h.
gps_sat_t PACKED::gpsSat |
Definition at line 3542 of file data_sets.h.
uint32_t PACKED::gpsTimeSyncPeriodMs |
Time between GPS time synchronization pulses in milliseconds. Requires reboot to take effect.
Definition at line 2039 of file data_sets.h.
gps_vel_t PACKED::gpsVel |
Definition at line 3541 of file data_sets.h.
uint16_t PACKED::gpzda |
Broadcast period (ms) - ASCII NMEA Data and Time. 0 to disable.
Definition at line 1185 of file data_sets.h.
uint32_t PACKED::gpzda |
Broadcast period (ms) - ASCII NMEA Data and Time. 0 to disable.
Definition at line 1229 of file data_sets.h.
float PACKED::hAcc |
Horizontal accuracy in meters
Definition at line 775 of file data_sets.h.
uint32_t PACKED::handle |
Handle
Definition at line 3441 of file data_sets.h.
uint8_t PACKED::hardwareVer[4] |
Hardware version
Definition at line 445 of file data_sets.h.
float PACKED::hDop |
Horizontal dilution of precision (meters)
Definition at line 2764 of file data_sets.h.
uint32_t PACKED::hdwBitStatus |
Hardware BIT status (see eHdwBitStatusFlags)
Definition at line 1488 of file data_sets.h.
uint32_t PACKED::hdwStatus |
Hardware status flags (eHdwStatusFlags). Copy of DID_SYS_PARAMS.hdwStatus
System status 2 flags (eHdwStatusFlags)
Definition at line 40 of file CAN_comm.h.
int16_t PACKED::headingToBase |
Angle from north to vectorToBase in local tangent plane. (rad)
Definition at line 238 of file CAN_comm.h.
float PACKED::hMSL |
Height above mean sea level (MSL) in meters
Definition at line 772 of file data_sets.h.
float PACKED::humidity |
Relative humidity as a percent (rH). Range is 0% - 100%
Definition at line 675 of file data_sets.h.
f_t PACKED::humidity |
Definition at line 1252 of file data_sets.h.
uint8_t PACKED::hwVersion[10] |
Hardware version
Definition at line 883 of file data_sets.h.
imus_t PACKED::I |
Inertial Measurement Unit (IMU)
Inertial Measurement Units (IMUs)
Definition at line 617 of file data_sets.h.
int32_t PACKED::i[DEBUG_I_ARRAY_SIZE] |
Definition at line 2105 of file data_sets.h.
dual_imu_t PACKED::imu |
dual imu - raw or pre-integrated depending on data id
Definition at line 638 of file data_sets.h.
imu_t PACKED::imu |
Definition at line 3532 of file data_sets.h.
uint8_t PACKED::imu1ok |
IMU is valid
Definition at line 641 of file data_sets.h.
uint8_t PACKED::imu2ok |
Definition at line 642 of file data_sets.h.
uint32_t PACKED::imuPeriodMs |
IMU sample period in milliseconds. Zero disables sampling.
Definition at line 1067 of file data_sets.h.
float PACKED::imuTemp |
IMU temperature
Definition at line 1055 of file data_sets.h.
inl2_ned_sigma_t PACKED::inl2NedSigma |
Definition at line 3546 of file data_sets.h.
inl2_states_t PACKED::inl2States |
Definition at line 3545 of file data_sets.h.
ins_1_t PACKED::ins1 |
Definition at line 3528 of file data_sets.h.
ins_2_t PACKED::ins2 |
Definition at line 3529 of file data_sets.h.
ins_3_t PACKED::ins3 |
Definition at line 3530 of file data_sets.h.
ins_4_t PACKED::ins4 |
Definition at line 3531 of file data_sets.h.
uint8_t PACKED::insDynModel |
INS dynamic platform model. Options are: 0=PORTABLE, 2=STATIONARY, 3=PEDESTRIAN, 4=AUTOMOTIVE, 5=SEA, 6=AIRBORNE_1G, 7=AIRBORNE_2G, 8=AIRBORNE_4G, 9=WRIST. Used to balance noise and performance characteristics of the system. The dynamics selected here must be at least as fast as your system or you experience accuracy error. This is tied to the GPS position estimation model and intend in the future to be incorporated into the INS position model.
Definition at line 1991 of file data_sets.h.
float PACKED::insHdg |
Definition at line 1408 of file data_sets.h.
float PACKED::insOffset[3] |
X,Y,Z offset in meters from Intermediate Output Frame to INS Output Frame.
Definition at line 1985 of file data_sets.h.
int16_t PACKED::insRoll |
Euler roll, roll rates from each IMU(DID_DUAL_IMU)
Definition at line 244 of file CAN_comm.h.
float PACKED::insRotation[3] |
Roll, pitch, yaw euler angle rotation in radians from INS Sensor Frame to Intermediate Output Frame. Order applied: heading, pitch, roll.
Definition at line 1982 of file data_sets.h.
uint32_t PACKED::insStatus |
INS status flags (eInsStatusFlags). Copy of DID_SYS_PARAMS.insStatus
System status 1 flags (eInsStatusFlags)
Definition at line 37 of file CAN_comm.h.
is_can_ins_status PACKED::insstatus |
Definition at line 253 of file CAN_comm.h.
uint8_t PACKED::invalid_base_position |
Definition at line 2166 of file data_sets.h.
uint32_t PACKED::invCommand |
Error checking field that must be set to bitwise inverse of command field for the command to take effect.
Definition at line 1125 of file data_sets.h.
uint32_t PACKED::ioConfig |
Hardware interface configuration bits (see eIoConfig).
Definition at line 2018 of file data_sets.h.
ion_model_utc_alm_t PACKED::ion |
Ionosphere model and UTC parameters
Definition at line 2898 of file data_sets.h.
uint32_t PACKED::ionUtcAlmCount |
Ionosphere model, utc and almanac count
Definition at line 2845 of file data_sets.h.
uint32_t PACKED::key |
double PACKED::L[1] |
Observation data carrier-phase (cycle). The carrier phase initial ambiguity is initialized using an approximate value to make the magnitude of the phase close to the pseudorange measurement. Clock resets are applied to both phase and code measurements in accordance with the RINEX specification.
Definition at line 2408 of file data_sets.h.
uint8_t PACKED::lack_of_valid_sats |
Definition at line 2191 of file data_sets.h.
uint8_t PACKED::large_v2b |
Definition at line 2173 of file data_sets.h.
double PACKED::lastLla[3] |
Last latitude, longitude, HAE (height above ellipsoid) used to aid GPS startup (deg, deg, m)
Definition at line 2006 of file data_sets.h.
uint32_t PACKED::lastLlaTimeOfWeekMs |
Last LLA GPS time since week start (Sunday morning) in milliseconds
Definition at line 2009 of file data_sets.h.
float PACKED::lastLlaUpdateDistance |
Distance between current and last LLA that triggers an update of lastLla
Definition at line 2015 of file data_sets.h.
uint32_t PACKED::lastLlaWeek |
Last LLA GPS number of weeks since January 6th, 1980
Definition at line 2012 of file data_sets.h.
double PACKED::lat |
WGS84 latitude (degrees)
Definition at line 97 of file CAN_comm.h.
is_can_ins_lat PACKED::lat |
Definition at line 259 of file CAN_comm.h.
uint8_t PACKED::leapS |
GPS leap second (GPS-UTC) offset. Receiver's best knowledge of the leap seconds offset from UTC to GPS time. Subtract from GPS time of week to get UTC time of week. (18 seconds as of December 31, 2016)
Definition at line 790 of file data_sets.h.
double PACKED::lf[DEBUG_LF_ARRAY_SIZE] |
Definition at line 2107 of file data_sets.h.
double PACKED::lla |
WGS84 latitude, longitude, height above ellipsoid (degrees,degrees,meters)
WGS84 latitude, longitude, height above ellipsoid in meters (not MSL)
Position - WGS84 latitude, longitude, height above ellipsoid (not MSL) (degrees, m)
Latitude, longitude and height above ellipsoid (rad, rad, m)
Definition at line 511 of file data_sets.h.
uint8_t PACKED::LLI[1] |
Loss of Lock Indicator. Set to non-zero values only when carrier-phase is valid (L > 0). bit1 = loss-of-lock, bit2 = half-cycle-invalid
Definition at line 2393 of file data_sets.h.
double PACKED::lon |
WGS84 longitude (degrees)
Definition at line 105 of file CAN_comm.h.
is_can_ins_lon PACKED::lon |
Definition at line 260 of file CAN_comm.h.
uint32_t PACKED::lotNumber |
Lot number
Definition at line 479 of file data_sets.h.
uint8_t PACKED::lsq_error |
Definition at line 2190 of file data_sets.h.
evb_flash_cfg_t PACKED::m |
float PACKED::mag |
Magnetometers in Gauss
Definition at line 655 of file data_sets.h.
f_t PACKED::mag[3] |
Definition at line 1241 of file data_sets.h.
magnetometer_t PACKED::mag |
Definition at line 3534 of file data_sets.h.
magnetometer_t PACKED::mag1 |
mag 1
Definition at line 712 of file data_sets.h.
magnetometer_t PACKED::mag2 |
Definition at line 713 of file data_sets.h.
int PACKED::mag_cal_done |
Definition at line 936 of file data_sets.h.
int PACKED::mag_cal_good |
Definition at line 935 of file data_sets.h.
mag_cal_t PACKED::magCal |
Definition at line 3535 of file data_sets.h.
float PACKED::magDec |
(rad) Magnetic declination
Definition at line 915 of file data_sets.h.
float PACKED::magDeclination |
Earth magnetic field (magnetic north) declination (heading offset from true north) in radians
Definition at line 2036 of file data_sets.h.
float PACKED::magHdg |
Definition at line 1407 of file data_sets.h.
float PACKED::magHdgOffset |
Definition at line 1414 of file data_sets.h.
float PACKED::magInc |
(rad) Magnetic inclination
Definition at line 918 of file data_sets.h.
float PACKED::magInclination |
Earth magnetic field (magnetic north) inclination (negative pitch offset) in radians
Definition at line 2033 of file data_sets.h.
float PACKED::magInsHdgDelta |
Definition at line 1409 of file data_sets.h.
uint32_t PACKED::mallocSize |
Total memory allocated using RTOS pvPortMalloc()
Definition at line 3451 of file data_sets.h.
char PACKED::manufacturer[DEVINFO_MANUFACTURER_STRLEN] |
Manufacturer name
Definition at line 460 of file data_sets.h.
uint32_t PACKED::marker |
Definition at line 63 of file communications.h.
uint32_t PACKED::maxRunTimeUs |
Max run time microseconds
Definition at line 3429 of file data_sets.h.
float PACKED::mcuTemp |
MCU temperature (not available yet)
Definition at line 1061 of file data_sets.h.
uint8_t PACKED::moveb_time_sync_error |
Definition at line 2186 of file data_sets.h.
sensors_mpu_w_temp_t PACKED::mpu[NUM_IMU_DEVICES] |
Definition at line 1249 of file data_sets.h.
float PACKED::msl |
Height above mean sea level (MSL) in meters
height above mean sea level (MSL) in meters
Definition at line 165 of file CAN_comm.h.
is_can_msl PACKED::msl |
Definition at line 267 of file CAN_comm.h.
float PACKED::mslBar |
MSL altitude from barometric pressure sensor in meters
Definition at line 669 of file data_sets.h.
char PACKED::name[MAX_TASK_NAME_LEN] |
Task name
Definition at line 3414 of file data_sets.h.
uint32_t PACKED::navPeriodMs |
Nav filter update period in milliseconds. Zero disables nav filter.
Definition at line 1070 of file data_sets.h.
uint32_t PACKED::Ncal_samples |
Definition at line 1402 of file data_sets.h.
is_can_north_east PACKED::ne |
Definition at line 262 of file CAN_comm.h.
float PACKED::ned[3] |
North, east and down offset from reference latitude, longitude, and altitude to current latitude, longitude, and altitude
Definition at line 514 of file data_sets.h.
float PACKED::ned1 |
North offset from reference latitude, longitude, and altitude to current latitude, longitude, and altitude
Definition at line 121 of file CAN_comm.h.
float PACKED::ned2 |
East offset from reference latitude, longitude, and altitude to current latitude, longitude, and altitude
Definition at line 123 of file CAN_comm.h.
float PACKED::ned3 |
Down offset from reference latitude, longitude, and altitude to current latitude, longitude, and altitude
Definition at line 131 of file CAN_comm.h.
float PACKED::nis |
Definition at line 1410 of file data_sets.h.
float PACKED::nis_threshold |
Definition at line 1411 of file data_sets.h.
uint8_t PACKED::no_base_obs_data |
Definition at line 2183 of file data_sets.h.
uint32_t PACKED::numSats |
Number of satellites in the sky
Definition at line 871 of file data_sets.h.
int32_t PACKED::nv |
Definition at line 2149 of file data_sets.h.
obsd_t PACKED::obs[MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE] |
Satellite observation data
Definition at line 2883 of file data_sets.h.
uint8_t PACKED::obs_count_bas |
Definition at line 2214 of file data_sets.h.
uint8_t PACKED::obs_count_rov |
Definition at line 2215 of file data_sets.h.
uint8_t PACKED::obs_pairs_filtered |
Definition at line 2217 of file data_sets.h.
uint8_t PACKED::obs_pairs_used |
Definition at line 2218 of file data_sets.h.
uint8_t PACKED::obsCount |
Number of observations in data (obsd_t) when dataType==1 (raw_data_type_observation).
Definition at line 2914 of file data_sets.h.
float PACKED::omega_l |
Left wheel angular rate (rad/s)
Definition at line 1901 of file data_sets.h.
float PACKED::omega_r |
Right wheel angular rate (rad/s)
Definition at line 1904 of file data_sets.h.
uint32_t PACKED::options |
Options: Port selection0x0=current, 0xFF=all, 0x1=ser0, 0x2=ser1, 0x4=USB
Options to select alternate ports to output data, etc. (see RMC_OPTIONS_...)
Definition at line 1152 of file data_sets.h.
uint8_t PACKED::outc_ovfl |
Definition at line 2170 of file data_sets.h.
uint32_t PACKED::outlier |
Definition at line 1406 of file data_sets.h.
double PACKED::P[1] |
Observation data pseudorange (m). GLONASS inter frequency channel delays are compensated with an internal calibration table
Definition at line 2411 of file data_sets.h.
float PACKED::PABias[3] |
Acceleration bias error sigma
Definition at line 2073 of file data_sets.h.
uint32_t PACKED::padding[BOOTLOADER_FLASH_BLOCK_SIZE/2/sizeof(uint32_t)] |
uint16_t PACKED::pashr |
Broadcast period (ms) - ASCII NMEA Inertial Attitude Data. 0 to disable.
Definition at line 1188 of file data_sets.h.
uint32_t PACKED::pashr |
Broadcast period (ms) - ASCII NMEA Inertial Attitude Data. 0 to disable.
Definition at line 1232 of file data_sets.h.
float PACKED::PattNED[3] |
NED attitude error sigma
Definition at line 2071 of file data_sets.h.
is_can_payload PACKED::payload |
Definition at line 56 of file communications.h.
float PACKED::PBaroBias |
Barometric altitude bias error sigma
Definition at line 2077 of file data_sets.h.
float PACKED::PDeclination |
Mag declination error sigma
Definition at line 2079 of file data_sets.h.
float PACKED::pDop |
Position dilution of precision (unitless)
Definition at line 781 of file data_sets.h.
uint32_t PACKED::periodMs |
Task period ms
Definition at line 3423 of file data_sets.h.
uint16_t PACKED::pgpsp |
Broadcast period (ms) - ASCII GPS position data. 0 to disable.
Definition at line 1167 of file data_sets.h.
uint32_t PACKED::pgpsp |
Broadcast period (ms) - ASCII GPS position data. 0 to disable.
Definition at line 1211 of file data_sets.h.
uint8_t PACKED::phase_large_residual |
Definition at line 2165 of file data_sets.h.
uint8_t PACKED::phase_outlier |
Definition at line 2162 of file data_sets.h.
preintegrated_imu_t PACKED::pimu |
dual preintegrated imu
Definition at line 721 of file data_sets.h.
uint16_t PACKED::pimu |
Broadcast period (ms) - ASCII dual IMU data. 0 to disable.
Definition at line 1155 of file data_sets.h.
uint32_t PACKED::pimu |
Broadcast period (ms) - ASCII dual IMU data. 0 to disable.
Definition at line 1199 of file data_sets.h.
preintegrated_imu_t PACKED::pImu |
Definition at line 3539 of file data_sets.h.
int16_t PACKED::pImu1 |
Definition at line 245 of file CAN_comm.h.
int16_t PACKED::pImu2 |
Definition at line 246 of file CAN_comm.h.
is_can_preint_imu_px PACKED::pimupx |
Definition at line 268 of file CAN_comm.h.
is_can_preint_imu_qy PACKED::pimuqy |
Definition at line 269 of file CAN_comm.h.
is_can_preint_imu_rz PACKED::pimurz |
Definition at line 270 of file CAN_comm.h.
uint32_t PACKED::pin |
Strobe input pin
Definition at line 2092 of file data_sets.h.
uint16_t PACKED::pins1 |
Broadcast period (ms) - ASCII INS output: euler rotation w/ respect to NED, NED position from reference LLA. 0 to disable.
Definition at line 1161 of file data_sets.h.
uint32_t PACKED::pins1 |
Broadcast period (ms) - ASCII INS output: euler rotation w/ respect to NED, NED position from reference LLA. 0 to disable.
Definition at line 1205 of file data_sets.h.
uint16_t PACKED::pins2 |
Broadcast period (ms) - ASCII INS output: quaternion rotation w/ respect to NED, ellipsoid altitude. 0 to disable.
Definition at line 1164 of file data_sets.h.
uint32_t PACKED::pins2 |
Broadcast period (ms) - ASCII INS output: quaternion rotation w/ respect to NED, ellipsoid altitude. 0 to disable.
Definition at line 1208 of file data_sets.h.
uint8_t PACKED::pnt_pos_error |
Definition at line 2182 of file data_sets.h.
pos_measurement_t PACKED::posMeasurement |
Definition at line 3538 of file data_sets.h.
uint16_t PACKED::ppimu |
Broadcast period (ms) - ASCII preintegrated dual IMU: delta theta (rad) and delta velocity (m/s). 0 to disable.
Definition at line 1158 of file data_sets.h.
uint32_t PACKED::ppimu |
Broadcast period (ms) - ASCII preintegrated dual IMU: delta theta (rad) and delta velocity (m/s). 0 to disable.
Definition at line 1202 of file data_sets.h.
float PACKED::pqr |
Gyroscope P, Q, R in radians / second
Gyros in radians / second
PQR motion (angular rate)
Definition at line 603 of file data_sets.h.
f_t PACKED::pqr[3] |
Definition at line 1239 of file data_sets.h.
float PACKED::pqrSigma |
Angular rate standard deviation
Definition at line 1512 of file data_sets.h.
uint32_t PACKED::priority |
Task priority (0 - 8)
Definition at line 3417 of file data_sets.h.
float PACKED::progress |
Mag recalibration progress indicator: 0-100 %
Definition at line 1393 of file data_sets.h.
uint8_t PACKED::protocolVer[4] |
Communications protocol version
Definition at line 454 of file data_sets.h.
int16_t PACKED::prRes |
(m) Pseudo range residual
Definition at line 835 of file data_sets.h.
float PACKED::psi |
Heading with respect to NED frame (rad)
Definition at line 423 of file data_sets.h.
protocol_type_t PACKED::ptype |
Definition at line 64 of file communications.h.
float PACKED::PvelNED[3] |
NED velocity error sigma
Definition at line 2069 of file data_sets.h.
float PACKED::PWBias[3] |
Angular rate bias error sigma
Definition at line 2075 of file data_sets.h.
float PACKED::PxyzNED[3] |
NED position error sigma
Definition at line 2067 of file data_sets.h.
double PACKED::qb[24] |
Definition at line 2142 of file data_sets.h.
float PACKED::qe2b |
Quaternion body rotation with respect to ECEF: W, X, Y, Z
Quaternion body rotation with respect to ECEF
Definition at line 589 of file data_sets.h.
int16_t PACKED::qe2b1 |
Quaternion body rotation with respect to ECEF: W, X, Y, Z (scaled by 10000)
Definition at line 68 of file CAN_comm.h.
int16_t PACKED::qe2b2 |
Definition at line 69 of file CAN_comm.h.
int16_t PACKED::qe2b3 |
Definition at line 70 of file CAN_comm.h.
int16_t PACKED::qe2b4 |
Definition at line 71 of file CAN_comm.h.
float PACKED::qn2b |
Quaternion body rotation with respect to NED: W, X, Y, Z
Definition at line 534 of file data_sets.h.
int16_t PACKED::qn2b1 |
Quaternion body rotation with respect to NED: W, X, Y, Z (scaled by 10000)
Definition at line 58 of file CAN_comm.h.
int16_t PACKED::qn2b2 |
Definition at line 59 of file CAN_comm.h.
int16_t PACKED::qn2b3 |
Definition at line 60 of file CAN_comm.h.
int16_t PACKED::qn2b4 |
Definition at line 61 of file CAN_comm.h.
double PACKED::qr[6] |
Definition at line 2140 of file data_sets.h.
uint8_t PACKED::qualL[1] |
Estimated carrier phase measurement standard deviation (0.004 cycles), zero means invalid
Definition at line 2399 of file data_sets.h.
uint8_t PACKED::qualP[1] |
Estimated pseudorange measurement standard deviation (0.01 m), zero means invalid
Definition at line 2402 of file data_sets.h.
is_can_ins_quate2b PACKED::quate2b |
Definition at line 256 of file CAN_comm.h.
is_can_ins_quatn2b PACKED::quatn2b |
Definition at line 255 of file CAN_comm.h.
double PACKED::ra_ecef[3] |
Definition at line 2137 of file data_sets.h.
uint8_t PACKED::raw_dat_queue_overrun |
Definition at line 2220 of file data_sets.h.
uint8_t PACKED::raw_ptr_queue_overrun |
Definition at line 2219 of file data_sets.h.
uint8_t PACKED::rcv |
receiver number
Definition at line 2387 of file data_sets.h.
uint32_t PACKED::ready |
Definition at line 1403 of file data_sets.h.
uint32_t PACKED::recalCmd |
Set mode and start recalibration. 1 = multi-axis, 2 = single-axis, 101 = abort.
Definition at line 1390 of file data_sets.h.
uint8_t PACKED::receiverIndex |
Receiver index (1=RECEIVER_INDEX_GPS1, 2=RECEIVER_INDEX_EXTERNAL_BASE, or 3=RECEIVER_INDEX_GPS2 )
Definition at line 2908 of file data_sets.h.
double PACKED::refLla[3] |
Reference latitude, longitude and height above ellipsoid for north east down (NED) calculations (deg, deg, m)
Definition at line 2003 of file data_sets.h.
uint8_t PACKED::rej_ovfl |
Definition at line 2160 of file data_sets.h.
uint32_t PACKED::repoRevision |
Repository revision number
Definition at line 457 of file data_sets.h.
uint8_t PACKED::rescode_err_marker |
Definition at line 2200 of file data_sets.h.
uint8_t PACKED::reserved |
Reserved bits
Broadcast period (ms) - Reserved. Leave zero.
ensure 32 bit aligned in memory
Reserved
reserved, for alignment
Definition at line 439 of file data_sets.h.
uint8_t PACKED::reserved |
Reserved for future use
ensure 32 bit aligned in memory
Reserved
reserved, for alignment
Definition at line 793 of file data_sets.h.
uint16_t PACKED::reserved |
Broadcast period (ms) - Reserved. Leave zero.
Definition at line 1170 of file data_sets.h.
uint8_t PACKED::reserved1 |
Definition at line 643 of file data_sets.h.
float PACKED::reserved1 |
Reserved
Definition at line 1064 of file data_sets.h.
uint8_t PACKED::reserved2 |
Definition at line 644 of file data_sets.h.
float PACKED::reserved2[2] |
Reserved
Definition at line 1076 of file data_sets.h.
uint8_t PACKED::reset_bias |
Definition at line 2177 of file data_sets.h.
uint8_t PACKED::reset_timer |
Definition at line 2171 of file data_sets.h.
rmc_t PACKED::rmc |
Definition at line 3554 of file data_sets.h.
is_can_roll_rollRate PACKED::rollrollrate |
Definition at line 276 of file CAN_comm.h.
int PACKED::rot_motion |
Definition at line 927 of file data_sets.h.
uint8_t PACKED::rover_position_error |
Definition at line 2176 of file data_sets.h.
uint32_t PACKED::roverBeidouEphemerisCount |
Rover beidou ephemeris element counter
Definition at line 2824 of file data_sets.h.
uint32_t PACKED::roverBeidouObservationCount |
Rover beidou observation element counter
Definition at line 2794 of file data_sets.h.
uint32_t PACKED::roverGalileoEphemerisCount |
Rover galileo ephemeris element counter
Definition at line 2818 of file data_sets.h.
uint32_t PACKED::roverGalileoObservationCount |
Rover galileo observation element counter
Definition at line 2788 of file data_sets.h.
uint32_t PACKED::roverGlonassEphemerisCount |
Rover glonass ephemeris element counter
Definition at line 2812 of file data_sets.h.
uint32_t PACKED::roverGlonassObservationCount |
Rover glonass observation element counter
Definition at line 2782 of file data_sets.h.
uint32_t PACKED::roverGpsEphemerisCount |
Rover gps ephemeris element counter
Definition at line 2806 of file data_sets.h.
uint32_t PACKED::roverGpsObservationCount |
Rover gps observation element counter
Definition at line 2776 of file data_sets.h.
uint32_t PACKED::roverQzsEphemerisCount |
Rover qzs ephemeris element counter
Definition at line 2830 of file data_sets.h.
uint32_t PACKED::roverQzsObservationCount |
Rover qzs observation element counter
Definition at line 2800 of file data_sets.h.
uint32_t PACKED::roverSbasCount |
Rover sbas element counter
Definition at line 2836 of file data_sets.h.
double PACKED::rp_ecef[3] |
Definition at line 2135 of file data_sets.h.
uint32_t PACKED::RTKCfgBits |
RTK configuration bits (see eRTKConfigBits).
Definition at line 2045 of file data_sets.h.
is_can_gps1_rtk_rel PACKED::rtkrel |
Definition at line 275 of file CAN_comm.h.
rtos_info_t PACKED::rtosInfo |
Definition at line 3551 of file data_sets.h.
uint32_t PACKED::runTimeUs |
Last run time microseconds
Definition at line 3426 of file data_sets.h.
double PACKED::rv_ecef[3] |
Definition at line 2136 of file data_sets.h.
uint8_t PACKED::s[DEBUG_STRING_SIZE] |
Definition at line 2115 of file data_sets.h.
float PACKED::sAcc |
Speed accuracy in meters / second
Definition at line 809 of file data_sets.h.
gps_sat_sv_t PACKED::sat[MAX_NUM_SAT_CHANNELS] |
Satellite information list
Definition at line 873 of file data_sets.h.
uint8_t PACKED::sat |
Satellite number in RTKlib notation. GPS: 1-32, GLONASS: 33-59, Galilleo: 60-89, SBAS: 90-95
Definition at line 2384 of file data_sets.h.
uint8_t PACKED::sat_id[24] |
Definition at line 2143 of file data_sets.h.
uint8_t PACKED::sat_id_i[24] |
Definition at line 2150 of file data_sets.h.
uint8_t PACKED::sat_id_j[24] |
Definition at line 2151 of file data_sets.h.
sbsmsg_t PACKED::sbas |
Satellite-Based Augmentation Systems (SBAS) data
Definition at line 2892 of file data_sets.h.
uint32_t PACKED::sensorConfig |
Sensor config to specify the full-scale sensing ranges and output rotation for the IMU and magnetometer (see eSensorConfig in data_sets.h)
Definition at line 2048 of file data_sets.h.
sys_sensors_adc_t PACKED::sensorsAdc |
Definition at line 3553 of file data_sets.h.
double PACKED::sensorTruePeriod |
Actual sample period relative to GPS PPS
Definition at line 1073 of file data_sets.h.
uint32_t PACKED::ser0BaudRate |
Serial port 0 baud rate in bits per second
Definition at line 1976 of file data_sets.h.
uint32_t PACKED::ser1BaudRate |
Serial port 1 baud rate in bits per second
Definition at line 1979 of file data_sets.h.
uint32_t PACKED::ser2BaudRate |
Serial port 2 baud rate in bits per second
Definition at line 2057 of file data_sets.h.
uint32_t PACKED::serialNumber |
Serial number
Definition at line 442 of file data_sets.h.
uint32_t PACKED::size |
Size of group or union, which is nvm_group_x_t + padding
Definition at line 65 of file communications.h.
uint8_t PACKED::SNR[1] |
Cno, carrier-to-noise density ratio (signal strength) (0.25 dB-Hz)
Definition at line 2390 of file data_sets.h.
uint8_t PACKED::solStatus |
Definition at line 2199 of file data_sets.h.
sta_t PACKED::sta |
Base station information (base position, antenna position, antenna height, etc.)
Definition at line 2895 of file data_sets.h.
uint32_t PACKED::stackUnused |
Stack high water mark bytes
Definition at line 3420 of file data_sets.h.
int PACKED::start_proc_done |
Definition at line 934 of file data_sets.h.
uint8_t PACKED::start_relpos |
Definition at line 2178 of file data_sets.h.
uint8_t PACKED::start_rtkpos |
Definition at line 2181 of file data_sets.h.
uint8_t PACKED::startByte |
Definition at line 53 of file communications.h.
uint32_t PACKED::startupGPSDtMs |
GPS measurement (system input data) update period in milliseconds set on startup. 200ms minimum (5Hz max).
Definition at line 2042 of file data_sets.h.
uint32_t PACKED::startupImuDtMs |
IMU sample (system input data) period in milliseconds set on startup. Cannot be larger than startupNavDtMs. Zero disables sensor/IMU sampling.
Definition at line 1970 of file data_sets.h.
uint32_t PACKED::startupNavDtMs |
Nav filter (system output data) update period in milliseconds set on startup. 1ms minimum (1KHz max). Zero disables nav filter updates.
Definition at line 1973 of file data_sets.h.
int PACKED::stat_magfield |
Definition at line 937 of file data_sets.h.
uint32_t PACKED::state |
Built-in self-test state (see eBitState)
Definition at line 1485 of file data_sets.h.
uint32_t PACKED::status |
(see eGpsStatus) GPS status: [0x000000xx] number of satellites used, [0x0000xx00] fix type, [0x00xx0000] status flags
IMU Status (eImuStatus)
(see eGpsStatus) GPS status: [0x000000xx] number of satellites used, [0x0000xx00] fix type, [0x00xx0000] status flags, NMEA input flag
NMEA input if status flag GPS_STATUS_FLAGS_GPS_NMEA_DATA
Status Word
Definition at line 114 of file CAN_comm.h.
survey_in_t PACKED::surveyIn |
Definition at line 3548 of file data_sets.h.
uint8_t PACKED::svId |
Satellite identifier
Definition at line 823 of file data_sets.h.
uint8_t PACKED::swVersion[30] |
Software version
Definition at line 881 of file data_sets.h.
uint32_t PACKED::sysCfgBits |
System configuration bits (see eSysConfigBits).
Definition at line 2000 of file data_sets.h.
sys_params_t PACKED::sysParams |
Definition at line 3549 of file data_sets.h.
sys_sensors_t PACKED::sysSensors |
Definition at line 3550 of file data_sets.h.
float PACKED::t_i2l[3] |
Translation from the imu to the left wheel, expressed in the imu frame
Definition at line 1931 of file data_sets.h.
rtos_task_t PACKED::task |
Tasks
Definition at line 3457 of file data_sets.h.
float PACKED::tcAccBias |
Definition at line 1495 of file data_sets.h.
float PACKED::tcAccLinearity |
Definition at line 1503 of file data_sets.h.
float PACKED::tcAccSlope |
Definition at line 1499 of file data_sets.h.
float PACKED::Tcal |
Definition at line 1415 of file data_sets.h.
float PACKED::tcPqrBias |
Temperature calibration bias
Definition at line 1494 of file data_sets.h.
float PACKED::tcPqrLinearity |
Temperature calibration linearity
Definition at line 1502 of file data_sets.h.
float PACKED::tcPqrSlope |
Temperature calibration slope
Definition at line 1498 of file data_sets.h.
float PACKED::temp |
Temperature in Celsius
Definition at line 990 of file data_sets.h.
f_t PACKED::temp |
Definition at line 1242 of file data_sets.h.
float PACKED::theta[3] |
Euler angles: roll, pitch, yaw in radians with respect to NED
Definition at line 505 of file data_sets.h.
int16_t PACKED::theta0 |
Definition at line 171 of file CAN_comm.h.
int16_t PACKED::theta1 |
Euler angles: roll, pitch, yaw in radians with respect to NED (scaled by 10000)
Definition at line 48 of file CAN_comm.h.
float PACKED::theta1[3] |
IMU 1 delta theta (gyroscope {p,q,r} integral) in radians in sensor frame
Definition at line 686 of file data_sets.h.
int16_t PACKED::theta2 |
Definition at line 49 of file CAN_comm.h.
float PACKED::theta2[3] |
IMU 2 delta theta (gyroscope {p,q,r} integral) in radians in sensor frame
Definition at line 689 of file data_sets.h.
int16_t PACKED::theta3 |
Definition at line 50 of file CAN_comm.h.
float PACKED::theta_l |
Left wheel angle (rad)
Definition at line 1895 of file data_sets.h.
float PACKED::theta_r |
Right wheel angle (rad)
Definition at line 1898 of file data_sets.h.
gtime_t PACKED::time |
Time since boot up in seconds. Convert to GPS time of week by adding gps.towOffset
Time in seconds
Receiver local time approximately aligned to the GPS time system (GPST)
Definition at line 252 of file CAN_comm.h.
double PACKED::time |
Time since boot up in seconds. Convert to GPS time of week by adding gps.towOffset
Time in seconds
Definition at line 614 of file data_sets.h.
gtime_t PACKED::time |
Receiver local time approximately aligned to the GPS time system (GPST)
Definition at line 2134 of file data_sets.h.
double PACKED::timeOfWeek |
GPS time of week (since Sunday morning) in seconds
Time of measurement wrt current week
Definition at line 417 of file data_sets.h.
uint32_t PACKED::timeOfWeekMs |
Time of week (since Sunday morning) in milliseconds, GMT
GPS time of week (since Sunday morning) in milliseconds
Definition at line 29 of file CAN_comm.h.
uint32_t PACKED::timeOfWeekMs |
GPS time of week (since Sunday morning) in milliseconds
Definition at line 760 of file data_sets.h.
unsigned int PACKED::timeOfWeekMs |
Timestamp in milliseconds
Definition at line 2065 of file data_sets.h.
uint32_t PACKED::timeToFirstFixMs |
Time to first RTK fix.
Definition at line 2851 of file data_sets.h.
double PACKED::towOffset |
Time sync offset between local time since boot up to GPS time of week in seconds. Add this to IMU and sensor time to get GPS time of week in seconds.
Definition at line 787 of file data_sets.h.
uint8_t PACKED::type[24] |
Definition at line 2152 of file data_sets.h.
float PACKED::ubx_error |
Definition at line 2197 of file data_sets.h.
uint8_t PACKED::use_ubx_position |
Definition at line 2172 of file data_sets.h.
float PACKED::uvw |
Velocity U, V, W in meters per second. Convert to NED velocity using "quatRot(vel_ned, qn2b, uvw)".
Velocities in body frames of X, Y and Z (m/s)
Definition at line 257 of file CAN_comm.h.
float PACKED::uvw[3] |
Velocity U, V, W in meters per second. Convert to NED velocity using "vectorBodyToReference( uvw, theta, vel_ned )".
Velocity U, V, W in meters per second. Convert to NED velocity using "quatRot(vel_ned, qn2b, uvw)".
Velocities in body frames of X, Y and Z (m/s)
Definition at line 508 of file data_sets.h.
int16_t PACKED::uvw1 |
Velocity U, V, W in meters per second (scaled by 100). Convert to NED velocity using "vectorBodyToReference( uvw, theta, vel_ned )".
Definition at line 78 of file CAN_comm.h.
int16_t PACKED::uvw2 |
Definition at line 79 of file CAN_comm.h.
int16_t PACKED::uvw3 |
Definition at line 80 of file CAN_comm.h.
double PACKED::v[24] |
Definition at line 2153 of file data_sets.h.
float PACKED::vAcc |
Vertical accuracy in meters
Definition at line 778 of file data_sets.h.
float PACKED::val |
Three axis sensor
Definition at line 947 of file data_sets.h.
double PACKED::val[3] |
Three axis sensor
Definition at line 980 of file data_sets.h.
float PACKED::val1[3] |
First three axis sensor
Definition at line 967 of file data_sets.h.
float PACKED::val2[3] |
Second three axis sensor
Definition at line 970 of file data_sets.h.
float PACKED::vDop |
Vertical dilution of precision (meters)
Definition at line 2767 of file data_sets.h.
float PACKED::ve |
(m/s) Velocity in ECEF frame
Definition at line 258 of file CAN_comm.h.
float PACKED::ve[3] |
Velocity in ECEF (earth-centered earth-fixed) frame in meters per second
(m/s) Velocity in ECEF frame
Definition at line 592 of file data_sets.h.
int16_t PACKED::ve1 |
Velocity in ECEF (earth-centered earth-fixed) (scaled by 100) frame in meters per second
Definition at line 87 of file CAN_comm.h.
int16_t PACKED::ve2 |
Definition at line 88 of file CAN_comm.h.
int16_t PACKED::ve3 |
Definition at line 89 of file CAN_comm.h.
float PACKED::vel[3] |
if status flag GPS_STATUS_FLAGS_GPS_NMEA_DATA = 0, Speed in ECEF {vx,vy,vz} (m/s) if status flag GPS_STATUS_FLAGS_GPS_NMEA_DATA = 1, Speed in NED {vN, vE, 0} (m/s)
Definition at line 806 of file data_sets.h.
int16_t PACKED::vel0 |
Definition at line 172 of file CAN_comm.h.
int16_t PACKED::vel1 |
Definition at line 181 of file CAN_comm.h.
float PACKED::vel1[3] |
IMU 1 delta velocity (accelerometer {x,y,z} integral) in m/s in sensor frame
Definition at line 692 of file data_sets.h.
int16_t PACKED::vel2 |
Definition at line 191 of file CAN_comm.h.
float PACKED::vel2[3] |
IMU 2 delta velocity (accelerometer {x,y,z} integral) in m/s in sensor frame
Definition at line 695 of file data_sets.h.
float PACKED::vin |
EVB system input voltage in volts. uINS pin 5 (G2/AN2). Use 10K/1K resistor divider between Vin and GND.
Definition at line 1014 of file data_sets.h.
uint8_t PACKED::waiting_for_base_packet |
Definition at line 2188 of file data_sets.h.
uint8_t PACKED::waiting_for_rover_packet |
Definition at line 2187 of file data_sets.h.
uint8_t PACKED::warning_code |
Definition at line 2209 of file data_sets.h.
uint8_t PACKED::warning_count |
Definition at line 2208 of file data_sets.h.
float PACKED::Wcal[9] |
Definition at line 1412 of file data_sets.h.
uint32_t PACKED::week |
Weeks since January 6th, 1980
GPS number of weeks since January 6th, 1980
Definition at line 26 of file CAN_comm.h.
wheel_config_t PACKED::wheelConfig |
Wheel encoder: euler angles describing the rotation from imu to left wheel
Definition at line 2051 of file data_sets.h.
wheel_encoder_t PACKED::wheelEncoder |
Definition at line 3537 of file data_sets.h.
uint32_t PACKED::wrap_count_l |
Left wheel revolution count
Definition at line 1907 of file data_sets.h.
uint32_t PACKED::wrap_count_r |
Right wheel revolution count
Definition at line 1910 of file data_sets.h.
int PACKED::zero_accel |
Definition at line 924 of file data_sets.h.
int PACKED::zero_angrate |
Definition at line 925 of file data_sets.h.
int PACKED::zero_vel |
Definition at line 928 of file data_sets.h.
float PACKED::zeroVelOffset[3] |
X,Y,Z offset in meters from Intermediate ZeroVelocity Frame to Zero Velocity Frame.
Definition at line 2030 of file data_sets.h.
float PACKED::zeroVelRotation[3] |
Euler (roll, pitch, yaw) rotation in radians from INS Sensor Frame to Intermediate ZeroVelocity Frame. Order applied: heading, pitch, roll.
Definition at line 2027 of file data_sets.h.