mavsdk::Telemetry::Odometry Struct Reference
#include: telemetry.h
Odometry message type.
Public Types
Type | Description |
---|---|
enum MavFrame | Mavlink frame id. |
Data Fields
uint64_t time_usec {} - Timestamp (0 to use Backend timestamp).
MavFrame frame_id {} - Coordinate frame of reference for the pose data.
MavFrame child_frame_id {} - Coordinate frame of reference for the velocity in free space (twist) data.
PositionBody position_body {} - Position.
Quaternion q {} - Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation).
VelocityBody velocity_body {} - Linear velocity (m/s).
AngularVelocityBody angular_velocity_body {} - Angular velocity (rad/s).
Covariance pose_covariance {} - Pose cross-covariance matrix.
Covariance velocity_covariance {} - Velocity cross-covariance matrix.
Member Enumeration Documentation
enum MavFrame
Mavlink frame id.
Value | Description |
---|---|
Undef |
Frame is undefined.. |
BodyNed |
Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right.. |
VisionNed |
Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: north, y: east, z: down).. |
EstimNed |
Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: north, y: east, z: down).. |
Field Documentation
time_usec
uint64_t mavsdk::Telemetry::Odometry::time_usec {}
Timestamp (0 to use Backend timestamp).
frame_id
MavFrame mavsdk::Telemetry::Odometry::frame_id {}
Coordinate frame of reference for the pose data.
child_frame_id
MavFrame mavsdk::Telemetry::Odometry::child_frame_id {}
Coordinate frame of reference for the velocity in free space (twist) data.
position_body
PositionBody mavsdk::Telemetry::Odometry::position_body {}
q
Quaternion mavsdk::Telemetry::Odometry::q {}
Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation).
velocity_body
VelocityBody mavsdk::Telemetry::Odometry::velocity_body {}
Linear velocity (m/s).
angular_velocity_body
AngularVelocityBody mavsdk::Telemetry::Odometry::angular_velocity_body {}
Angular velocity (rad/s).
pose_covariance
Covariance mavsdk::Telemetry::Odometry::pose_covariance {}
Pose cross-covariance matrix.
velocity_covariance
Covariance mavsdk::Telemetry::Odometry::velocity_covariance {}
Velocity cross-covariance matrix.