PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
px4_ros2::OdometryLocalPosition Class Reference

Provides access to the vehicle's local position estimate. More...

#include <px4_ros2/odometry/local_position.hpp>

Inheritance diagram for px4_ros2::OdometryLocalPosition:
px4_ros2::Subscription< px4_msgs::msg::VehicleLocalPosition >

Public Member Functions

 OdometryLocalPosition (Context &context)
 
bool positionXYValid () const
 
bool positionZValid () const
 
Eigen::Vector3f positionNed () const
 
bool velocityXYValid () const
 
bool velocityZValid () const
 
Eigen::Vector3f velocityNed () const
 
Eigen::Vector3f accelerationNed () const
 
float heading () const
 Get the vehicle's heading relative to NED earth-fixed frame. More...
 
- Public Member Functions inherited from px4_ros2::Subscription< px4_msgs::msg::VehicleLocalPosition >
 Subscription (Context &context, const std::string &topic)
 
void onUpdate (const UpdateCallback &callback)
 Add a callback to execute when receiving a new message. More...
 
const px4_msgs::msg::VehicleLocalPosition & last () const
 Get the last-received message. More...
 
const rclcpp::Time & lastTime () const
 Get the receive-time of the last message. More...
 
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. More...
 

Detailed Description

Provides access to the vehicle's local position estimate.

Member Function Documentation

◆ heading()

float px4_ros2::OdometryLocalPosition::heading ( ) const
inline

Get the vehicle's heading relative to NED earth-fixed frame.

Returns
The vehicle's yaw in radians within [-pi, pi] using extrinsic RPY order

The documentation for this class was generated from the following file: