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

Provides access to the vehicle's home position. More...

#include <px4_ros2/vehicle_state/home_position.hpp>

Inheritance diagram for px4_ros2::HomePosition:
px4_ros2::Subscription< px4_msgs::msg::HomePosition >

Public Member Functions

 HomePosition (Context &context)
 
Eigen::Vector3f localPosition () const
 Get the vehicle's home position in local coordinates. More...
 
Eigen::Vector3d globalPosition () const
 Get the vehicle's home position in global coordinates. More...
 
float yaw () const
 Get the vehicle's home position yaw. More...
 
bool localPositionValid () const
 Check if vehicle's local home position is valid (xyz). More...
 
bool globaHorizontalPositionValid () const
 Check if vehicle's global horizontal home position is valid (lat, lon). More...
 
bool altitudeValid () const
 Check if vehicle's home position altitude is valid. More...
 
bool manualHome () const
 Check if home position has been set manually. More...
 
- Public Member Functions inherited from px4_ros2::Subscription< px4_msgs::msg::HomePosition >
 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::HomePosition & 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...
 

Additional Inherited Members

- Protected Attributes inherited from px4_ros2::Subscription< px4_msgs::msg::HomePosition >
rclcpp::Node & _node
 

Detailed Description

Provides access to the vehicle's home position.

Member Function Documentation

◆ altitudeValid()

bool px4_ros2::HomePosition::altitudeValid ( ) const
inline

Check if vehicle's home position altitude is valid.

Returns
true if altitude has been set, otherwise false

◆ globaHorizontalPositionValid()

bool px4_ros2::HomePosition::globaHorizontalPositionValid ( ) const
inline

Check if vehicle's global horizontal home position is valid (lat, lon).

Returns
true if latitude and longitude have been set, otherwise false

◆ globalPosition()

Eigen::Vector3d px4_ros2::HomePosition::globalPosition ( ) const
inline

Get the vehicle's home position in global coordinates.

Returns
the global coordinates of the home position (latitude [°], longitude [°], altitude [m AMSL])

◆ localPosition()

Eigen::Vector3f px4_ros2::HomePosition::localPosition ( ) const
inline

Get the vehicle's home position in local coordinates.

Returns
the local coordinates of the home position (NED) [m]

◆ localPositionValid()

bool px4_ros2::HomePosition::localPositionValid ( ) const
inline

Check if vehicle's local home position is valid (xyz).

Returns
true if the local position has been set, otherwise false

◆ manualHome()

bool px4_ros2::HomePosition::manualHome ( ) const
inline

Check if home position has been set manually.

Returns
true if set manually, otherwise false

◆ yaw()

float px4_ros2::HomePosition::yaw ( ) const
inline

Get the vehicle's home position yaw.

Returns
the yaw of the home position (NED) [rad]

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