Go to the documentation of this file.
11 namespace fusion_engine {
39 uint8_t reserved[3] = {0};
187 uint8_t reserved[2] = {0};
219 uint8_t reserved = 0;
float velocity_std_body_mps[3]
The velocity standard deviation (in meters/second), resolved in the body frame.
float vdop
The vertical dilution of precision (VDOP).
double lla_deg[3]
The WGS-84 geodetic latitude, longitude, and altitude (in degrees/meters).
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
float gdop
The geometric dilution of precision (GDOP).
uint8_t usage
A bitmask specifying how this satellite was used in the position solution.
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
SatelliteType system
The GNSS system to which this satellite belongs.
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...
Information about an individual satellite (see GNSSSatelliteMessage).
Auxiliary platform pose information (MessageType::POSE_AUX).
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.
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.
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.
float ypr_std_deg[3]
The attitude standard deviation (in degrees): yaw, pitch, roll.
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).
Timestamp gps_time
The GPS time of the message, if available, referenced to 1980/1/6.
float vertical_protection_level_m
The estimated vertical protection level (in meters).
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...
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.
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.
uint32_t reference_station_id
The ID of the differential base station, if used.
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).