mavsdk::Mocap::Odometry Struct Reference ​
#include: mocap.h
Odometry message to communicate odometry information with an external interface.
Public Types ​
| Type | Description |
|---|---|
| enum MavFrame | Mavlink frame id. |
| enum MavEstimatorType | Estimator type, matching MAVLink MAV_ESTIMATOR_TYPE. |
Data Fields ​
uint64_t time_usec {} - Timestamp (0 to use Backend timestamp).
MavFrame frame_id {} - Coordinate frame of reference for the pose data.
PositionBody position_body {} - Body Position.
Quaternion q {} - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation).
SpeedBody speed_body {} - Linear speed (m/s).
AngularVelocityBody angular_velocity_body {} - Angular speed (rad/s).
Covariance pose_covariance {} - Pose cross-covariance matrix.
Covariance velocity_covariance {} - Velocity cross-covariance matrix.
uint32_t reset_counter {} - Estimate reset counter. Increment when the estimate resets or jumps.
MavEstimatorType estimator_type {} - Type of estimator that is providing the odometry.
int32_t quality_percent {} - Optional odometry quality in percent. -1 = failed, 0 = unknown/unset, 1 = worst, 100 = best.
Member Enumeration Documentation ​
enum MavFrame ​
Mavlink frame id.
| Value | Description |
|---|---|
MocapNed | Legacy mocap NED frame. Deprecated in MAVLink and replaced by MAV_FRAME_LOCAL_FRD.. |
LocalFrd | Local FRD frame (x: forward, y: right, z: down).. |
enum MavEstimatorType ​
Estimator type, matching MAVLink MAV_ESTIMATOR_TYPE.
| Value | Description |
|---|---|
Unknown | Unknown estimator type.. |
Naive | Naive estimator.. |
Vision | Computer vision-based estimate.. |
Vio | Visual-inertial estimate.. |
Gps | Plain GPS estimate.. |
GpsIns | GPS and inertial navigation estimate.. |
Mocap | Motion capture estimate.. |
Lidar | Lidar estimate.. |
Autopilot | Autopilot estimate.. |
Field Documentation ​
time_usec ​
uint64_t mavsdk::Mocap::Odometry::time_usec {}Timestamp (0 to use Backend timestamp).
frame_id ​
MavFrame mavsdk::Mocap::Odometry::frame_id {}Coordinate frame of reference for the pose data.
position_body ​
PositionBody mavsdk::Mocap::Odometry::position_body {}Body Position.
q ​
Quaternion mavsdk::Mocap::Odometry::q {}Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation).
speed_body ​
SpeedBody mavsdk::Mocap::Odometry::speed_body {}Linear speed (m/s).
angular_velocity_body ​
AngularVelocityBody mavsdk::Mocap::Odometry::angular_velocity_body {}Angular speed (rad/s).
pose_covariance ​
Covariance mavsdk::Mocap::Odometry::pose_covariance {}Pose cross-covariance matrix.
velocity_covariance ​
Covariance mavsdk::Mocap::Odometry::velocity_covariance {}Velocity cross-covariance matrix.
reset_counter ​
uint32_t mavsdk::Mocap::Odometry::reset_counter {}Estimate reset counter. Increment when the estimate resets or jumps.
estimator_type ​
MavEstimatorType mavsdk::Mocap::Odometry::estimator_type {}Type of estimator that is providing the odometry.
quality_percent ​
int32_t mavsdk::Mocap::Odometry::quality_percent {}Optional odometry quality in percent. -1 = failed, 0 = unknown/unset, 1 = worst, 100 = best.

