8 #include <px4_msgs/msg/vtol_vehicle_status.hpp>
9 #include <px4_ros2/common/context.hpp>
10 #include <px4_ros2/utils/subscription.hpp>
36 return last().vehicle_vtol_state ==
37 px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_UNDEFINED;
47 return last().vehicle_vtol_state ==
48 px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_TRANSITION_TO_FW;
58 return last().vehicle_vtol_state ==
59 px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_TRANSITION_TO_MC;
69 return last().vehicle_vtol_state == px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_MC;
79 return last().vehicle_vtol_state == px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_FW;
Definition: context.hpp:20
Provides a subscription to arbitrary ROS topics.
Definition: subscription.hpp:23
const px4_msgs::msg::VtolVehicleStatus & last() const
Get the last-received message.
Definition: subscription.hpp:58
Provides access to the vtol vehicle's status.
Definition: vtol_status.hpp:24
bool isUndefined() const
Check if vehicle is in an undefined state. This indicates the vehicle is not a VTOL.
Definition: vtol_status.hpp:34
bool isTransitioningToFw() const
Check if VTOL is transitioning to fixed-wing.
Definition: vtol_status.hpp:45
bool isFwMode() const
Check if VTOL is in fixed-wing mode.
Definition: vtol_status.hpp:77
bool isMcMode() const
Check if VTOL is in multicopter mode.
Definition: vtol_status.hpp:67
bool isTransitioningToMc() const
Check if VTOL is transitioning to multicopter.
Definition: vtol_status.hpp:56