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

Provides access to the vtol vehicle's status. More...

#include <px4_ros2/vehicle_state/vtol_status.hpp>

Inheritance diagram for px4_ros2::VtolStatus:
px4_ros2::Subscription< px4_msgs::msg::VtolVehicleStatus >

Public Member Functions

 VtolStatus (Context &context)
 
bool isUndefined () const
 Check if vehicle is in an undefined state. This indicates the vehicle is not a VTOL. More...
 
bool isTransitioningToFw () const
 Check if VTOL is transitioning to fixed-wing. More...
 
bool isTransitioningToMc () const
 Check if VTOL is transitioning to multicopter. More...
 
bool isMcMode () const
 Check if VTOL is in multicopter mode. More...
 
bool isFwMode () const
 Check if VTOL is in fixed-wing mode. More...
 
- Public Member Functions inherited from px4_ros2::Subscription< px4_msgs::msg::VtolVehicleStatus >
 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::VtolVehicleStatus & 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::VtolVehicleStatus >
rclcpp::Node & _node
 

Detailed Description

Provides access to the vtol vehicle's status.

Member Function Documentation

◆ isFwMode()

bool px4_ros2::VtolStatus::isFwMode ( ) const
inline

Check if VTOL is in fixed-wing mode.

Returns
true if in FW mode, false otherwise.

◆ isMcMode()

bool px4_ros2::VtolStatus::isMcMode ( ) const
inline

Check if VTOL is in multicopter mode.

Returns
true if in MC mode, false otherwise.

◆ isTransitioningToFw()

bool px4_ros2::VtolStatus::isTransitioningToFw ( ) const
inline

Check if VTOL is transitioning to fixed-wing.

Returns
true if transitioning to FW, false otherwise.

◆ isTransitioningToMc()

bool px4_ros2::VtolStatus::isTransitioningToMc ( ) const
inline

Check if VTOL is transitioning to multicopter.

Returns
true if transitioning to MC, false otherwise.

◆ isUndefined()

bool px4_ros2::VtolStatus::isUndefined ( ) const
inline

Check if vehicle is in an undefined state. This indicates the vehicle is not a VTOL.

Returns
true if undefined state, false otherwise.

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