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

Provides access to the vehicle's attitude estimate. More...

#include <px4_ros2/odometry/attitude.hpp>

Inheritance diagram for px4_ros2::OdometryAttitude:
px4_ros2::Subscription< px4_msgs::msg::VehicleAttitude >

Public Member Functions

 OdometryAttitude (Context &context)
 
Eigen::Quaternionf attitude () const
 Get the vehicle's attitude. More...
 
float roll () const
 Get the vehicle's roll in extrinsic RPY order. More...
 
float pitch () const
 Get the vehicle's pitch in extrinsic RPY order. More...
 
float yaw () const
 Get the vehicle's yaw in extrinsic RPY order. More...
 
- Public Member Functions inherited from px4_ros2::Subscription< px4_msgs::msg::VehicleAttitude >
 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::VehicleAttitude & 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 attitude estimate.

Member Function Documentation

◆ attitude()

Eigen::Quaternionf px4_ros2::OdometryAttitude::attitude ( ) const
inline

Get the vehicle's attitude.

Returns
the attitude quaternion

◆ pitch()

float px4_ros2::OdometryAttitude::pitch ( ) const
inline

Get the vehicle's pitch in extrinsic RPY order.

Returns
the attitude pitch in radians within [-pi, pi]

◆ roll()

float px4_ros2::OdometryAttitude::roll ( ) const
inline

Get the vehicle's roll in extrinsic RPY order.

Returns
the attitude roll in radians within [-pi, pi]

◆ yaw()

float px4_ros2::OdometryAttitude::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: