Go to the documentation of this file.
11 namespace fusion_engine {
243 uint8_t reserved[3] = {0};
double dip_deg
The platform dip angle (in degrees).
static const uint8_t COVARIANCE_TYPE_KNOWN
double track_deg
The vehicle direction from north (in degrees).
double position_rel_m[3]
The relative change in ENU position since the time of the first PoseMessage, resolved in the local EN...
double acceleration_mps2[3]
Vehicle x/y/z linear acceleration (in meters/second^2), resolved in the body frame.
static const uint8_t COVARIANCE_TYPE_APPROXIMATED
MessageType
Identifiers for the defined output message types.
double latitude_deg
The WGS-84 geodetic latitude (in degrees).
double err_horiz_m
Horizontal position uncertainty (in meters) [eph].
double err_roll_deg
Roll uncertainty (in degrees)
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
double angular_velocity_covariance[9]
Vehicle rate of rotation covariance matrix.
double err_time_sec
Time uncertainty (in seconds) [ept].
@ ROS_GPS_FIX
ros::GPSFixMessage
@ ROS_POSE
ros::PoseMessage
double acceleration_covariance[9]
Vehicle x/y/z acceleration covariance matrix.
static constexpr MessageType MESSAGE_TYPE
ROS Imu message (MessageType::ROS_IMU, version 1.0).
double err_track_deg
Track uncertainty (in degrees) [epd].
double hdop
Horizontal DOP.
static const uint8_t COVARIANCE_TYPE_UNKNOWN
The base class for all message payloads.
double orientation_covariance[9]
Orientation covariance matrix.
double pdop
Positional (3D) DOP.
double longitude_deg
The WGS-84 geodetic longitude (in degrees).
double speed_mps
The vehicle ground speed (in meters/second).
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
static constexpr uint8_t MESSAGE_VERSION
ROS GPSFix message (MessageType::ROS_GPS_FIX, version 1.0).
static constexpr uint8_t MESSAGE_VERSION
double gps_time
The GPS time of the message (in seconds), referenced to 1980/1/6.
double orientation[4]
The platform body orientation with respect to the local ENU frame, represented as a quaternion with t...
double err_climb_mps
Vertical speed uncertainty (in meters/second) [epc].
double err_pitch_deg
Pitch uncertainty (in degrees)
double pitch_deg
The platform pitch angle (in degrees).
Timestamp p1_time
The time of the message, in P1 time (beginning at power-on).
ROS Pose message (MessageType::ROS_POSE, version 1.0).
static constexpr uint8_t MESSAGE_VERSION
static constexpr MessageType MESSAGE_TYPE
uint8_t position_covariance_type
The method in which position_covariance_m2 was populated.
double gdop
Geometric (position + time) DOP.
double err_vert_m
Vertical position uncertainty (in meters) [epv].
static constexpr MessageType MESSAGE_TYPE
double err_speed_mps
Ground speed uncertainty (in meters/second) [eps].
double err_dip_deg
Dip uncertainty (in degrees)
double orientation[4]
The platform body orientation with respect to the local ENU frame, represented as a quaternion with t...
double altitude_m
The WGS-84 altitude above the ellipsoid (in meters).
Point One FusionEngine output message common definitions.
Generic timestamp representation.
double climb_mps
The vehicle vertical speed (in meters/second).
static const uint8_t COVARIANCE_TYPE_DIAGONAL_KNOWN
double roll_deg
The platform roll angle (in degrees).
double err_3d_m
Spherical position uncertainty (in meters) [epe].
double position_covariance_m2[9]
The 3x3 position covariance matrix (in m^2), resolved in the local ENU frame.
double angular_velocity_rps[3]
Vehicle x/y/z rate of rotation (in radians/second), resolved in the body frame.