Go to the documentation of this file.
   11 namespace fusion_engine {
 
  262   uint8_t reserved[2] = {0};
 
  343       return "IMU Mounting Angles";
 
  347       return "Unrecognized";
 
  355   stream << 
to_string(val) << 
" (" << (int)val << 
")";
 
  380   uint8_t reserved1[3] = {0};
 
  394   uint8_t reserved2[24] = {0};
 
  409   uint8_t reserved3[3] = {0};
 
  429   uint8_t reserved4[5] = {0};
 
  480   uint8_t reserved[3] = {0};
 
  
static constexpr MessageType MESSAGE_TYPE
 
float velocity_std_body_mps[3]
The velocity standard deviation (in meters/second), resolved in the body frame.
 
uint32_t reference_station_id
The ID of the differential base station.
 
static constexpr MessageType MESSAGE_TYPE
 
uint8_t mounting_angle_percent_complete
The completion percentage for IMU mounting angle estimation, stored with a scale factor of 0....
 
float vdop
The vertical dilution of precision (VDOP).
 
MessageType
Identifiers for the defined output message types.
 
double lla_deg[3]
The geodetic latitude, longitude, and altitude (in degrees/meters), expressed using the WGS-84 refere...
 
float position_std_enu_m[3]
The position standard deviation (in meters), resolved with respect to the local ENU tangent plane: ea...
 
float position_std_enu_m[3]
The position standard deviation (in meters), resolved with respect to the local ENU tangent plane: ea...
 
SolutionType
Navigation solution type definitions.
 
static constexpr uint32_t INVALID_REFERENCE_STATION
 
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
 
static constexpr uint8_t SATELLITE_USED
 
@ MOUNTING_ANGLE
Estimating IMU mounting angles.
 
Device calibration status update.
 
@ DONE
Calibration complete.
 
@ GNSS_INFO
GNSSInfoMessage
 
static constexpr uint8_t MESSAGE_VERSION
 
uint8_t accel_bias_percent_complete
The completion percentage for accelerometer bias estimation, stored with a scale factor of 0....
 
static constexpr MessageType MESSAGE_TYPE
 
float gdop
The geometric dilution of precision (GDOP).
 
uint8_t usage
A bitmask specifying how this satellite was used in the position solution.
 
static constexpr uint8_t MESSAGE_VERSION
 
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
 
float travel_distance_m
The accumulated calibration travel distance (in meters).
 
@ CALIBRATION_STATUS
CalibrationStatusMessage
 
@ GNSS_SATELLITE
GNSSSatelliteMessage
 
SatelliteType system
The GNSS system to which this satellite belongs.
 
static constexpr MessageType MESSAGE_TYPE
 
SatelliteType
System/constellation type definitions.
 
double attitude_quaternion[4]
The platform body orientation with respect to the local ENU frame, represented as a quaternion with t...
 
float min_travel_distance_m
The minimum accumulated calibration travel distance needed to complete mounting angle calibration.
 
The base class for all message payloads.
 
uint8_t cn0
The carrier-to-noise density ratio (C/N0) for the L1 signal on the satellite.
 
SolutionType solution_type
The type of this position solution.
 
Information about an individual satellite (see GNSSSatelliteMessage).
 
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
 
float ypr_std_dev_deg[3]
The IMU yaw, pitch, and roll mounting angle standard deviations (in degrees).
 
@ Invalid
Invalid, no position available.
 
float ypr_deg[3]
The IMU yaw, pitch, and roll mounting angle offsets (in degrees).
 
static constexpr int16_t INVALID_UNDULATION
 
Auxiliary platform pose information (MessageType::POSE_AUX, version 1.0).
 
float gps_time_std_sec
GPS time alignment standard deviation (in seconds).
 
float hdop
The horizontal dilution of precision (HDOP).
 
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
 
uint16_t num_satellites
The number of known satellites.
 
static constexpr uint8_t MESSAGE_VERSION
 
float position_std_body_m[3]
The position standard deviation (in meters), resolved in the body frame.
 
float pdop
The position dilution of precision (PDOP).
 
Timestamp gps_time
The GPS time of the message, if available, referenced to 1980/1/6.
 
double velocity_enu_mps[3]
The platform velocity (in meters/second), resolved in the local ENU frame.
 
static constexpr int16_t INVALID_CN0
 
double ypr_deg[3]
The platform attitude (in degrees), if known, described as intrinsic Euler-321 angles (yaw,...
 
Timestamp last_differential_time
The P1 time of the last differential GNSS update.
 
uint8_t prn
The satellite's PRN (or slot number for GLONASS).
 
Timestamp gps_time
The GPS time of the message, if available, referenced to 1980/1/6.
 
CalibrationStage
The stages of the device calibration process.
 
float ypr_std_deg[3]
The attitude standard deviation (in degrees): yaw, pitch, roll.
 
float mounting_angle_max_std_dev_deg[3]
The max threshold for each of the YPR mounting angle states (in degrees), above which calibration is ...
 
float elevation_deg
The elevation of the satellite (in degrees).
 
float aggregate_protection_level_m
The estimated aggregate 3D protection level (in meters).
 
float azimuth_deg
The azimuth of the satellite (in degrees).
 
Platform pose solution: position, velocity, attitude (MessageType::POSE, version 1....
 
static constexpr uint8_t MESSAGE_VERSION
 
CalibrationStage calibration_stage
The current calibration stage.
 
Timestamp gps_time
The GPS time of the message, if available, referenced to 1980/1/6.
 
static constexpr MessageType MESSAGE_TYPE
 
float vertical_protection_level_m
The estimated vertical protection level (in meters).
 
Timestamp p1_time
The most recent P1 time, if available.
 
@ RELATIVE_ENU_POSITION
RelativeENUPositionMessage
 
double position_cov_enu_m2[9]
The 3x3 position covariance matrix (in m^2), resolved in the local ENU frame.
 
Information about the GNSS data used in the PoseMessage with the corresponding timestamp (MessageType...
 
uint8_t state_verified
Set to 1 once the navigation engine state is validated after initialization.
 
static constexpr uint8_t MESSAGE_VERSION
 
int16_t undulation_cm
The geoid undulation at at the current location (i.e., the difference between the WGS-84 ellipsoid an...
 
std::ostream & operator<<(std::ostream &stream, ConfigType type)
ConfigType stream operator.
 
@ UNKNOWN
Calibration stage not known.
 
Relative ENU position to base station (MessageType::RELATIVE_ENU_POSITION, version 1).
 
Point One FusionEngine output message common definitions.
 
float velocity_std_enu_mps[3]
The velocity standard deviation (in meters/second), resolved in the local ENU frame.
 
uint8_t gyro_bias_percent_complete
The completion percentage for gyro bias estimation, stored with a scale factor of 0....
 
Information about the individual satellites used in the PoseMessage and GNSSInfoMessage with the corr...
 
Generic timestamp representation.
 
double velocity_body_mps[3]
The platform velocity (in meters/second), resolved in the body frame.
 
float horizontal_protection_level_m
The estimated 2D horizontal protection level (in meters).
 
SolutionType solution_type
The type of this position solution.
 
const char * to_string(ConfigType type)
Get a human-friendly string name for the specified ConfigType.
 
uint32_t reference_station_id
The ID of the differential base station, if used.
 
Timestamp gps_time
The GPS time of the message, if available, referenced to 1980/1/6.
 
static constexpr uint8_t MESSAGE_VERSION
 
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
 
double relative_position_enu_m[3]
The relative position (in meters), resolved in the local ENU frame.
 
static constexpr MessageType MESSAGE_TYPE
 
static constexpr uint32_t INVALID_REFERENCE_STATION