Provides access to the vehicle's odometry estimate.
More...
#include <px4_ros2/odometry/odometry.hpp>
|
|
| Odometry (Context &context) |
| |
| Eigen::Vector3f | positionNed () const |
| | Get the vehicle's position in the North-East-Down (NED) local frame.
|
| |
| Eigen::Vector3f | velocityNed () const |
| | Get the vehicle's linear velocity in the North-East-Down (NED) frame.
|
| |
| Eigen::Vector3f | angularVelocityFrd () const |
| | Get the vehicle's angular velocity in FRD frame.
|
| |
| Eigen::Quaternionf | attitude () const |
| | Get the vehicle's attitude.
|
| |
| float | roll () const |
| | Get the vehicle's roll in extrinsic RPY order.
|
| |
| float | pitch () const |
| | Get the vehicle's pitch in extrinsic RPY order.
|
| |
| float | yaw () const |
| | Get the vehicle's yaw in extrinsic RPY order.
|
| |
|
| Subscription (Context &context, const std::string &topic) |
| |
| void | onUpdate (const UpdateCallback &callback) |
| | Add a callback to execute when receiving a new message.
|
| |
| const px4_msgs::msg::VehicleOdometry & | last () const |
| | Get the last-received message.
|
| |
| const rclcpp::Time & | lastTime () const |
| | Get the receive-time of the last message.
|
| |
| bool | lastValid (const std::chrono::duration< int64_t, DurationT > max_delay=500ms) const |
| | Check whether the last message is still valid. To be valid, the message must have been received within a given time of the current time.
|
| |
Provides access to the vehicle's odometry estimate.
Use this wrapper when you need position, velocity, attitude, and angular rates to be strictly time-aligned from the same odometry message. This class consolidates the odometry snapshot so advanced control (e.g. MPC) or end-to-end reinforcement learning pipelines can consume a consistent state vector at a single timestamp.
◆ angularVelocityFrd()
| Eigen::Vector3f px4_ros2::Odometry::angularVelocityFrd |
( |
| ) |
const |
|
inline |
Get the vehicle's angular velocity in FRD frame.
- Returns
- the angular velocity
◆ attitude()
| Eigen::Quaternionf px4_ros2::Odometry::attitude |
( |
| ) |
const |
|
inline |
Get the vehicle's attitude.
- Returns
- the attitude quaternion
◆ pitch()
| float px4_ros2::Odometry::pitch |
( |
| ) |
const |
|
inline |
Get the vehicle's pitch in extrinsic RPY order.
- Returns
- the attitude pitch in radians within [-pi, pi]
◆ positionNed()
| Eigen::Vector3f px4_ros2::Odometry::positionNed |
( |
| ) |
const |
|
inline |
Get the vehicle's position in the North-East-Down (NED) local frame.
- Returns
- The [North, East, Down] position in meters.
◆ roll()
| float px4_ros2::Odometry::roll |
( |
| ) |
const |
|
inline |
Get the vehicle's roll in extrinsic RPY order.
- Returns
- the attitude roll in radians within [-pi, pi]
◆ velocityNed()
| Eigen::Vector3f px4_ros2::Odometry::velocityNed |
( |
| ) |
const |
|
inline |
Get the vehicle's linear velocity in the North-East-Down (NED) frame.
- Note
- By default, PX4 uses VELOCITY_FRAME_NED for odometry updates.
- Returns
- the velocity.
◆ yaw()
| float px4_ros2::Odometry::yaw |
( |
| ) |
const |
|
inline |
Get the vehicle's yaw in extrinsic RPY order.
- Returns
- the attitude yaw in radians within [-pi, pi]
The documentation for this class was generated from the following file: