8#include <px4_msgs/msg/vtol_vehicle_status.hpp>
9#include <px4_ros2/common/context.hpp>
10#include <px4_ros2/utils/subscription.hpp>
11#include <px4_ros2/utils/message_version.hpp>
29 "fmu/out/vtol_vehicle_status" +
30 px4_ros2::getMessageNameVersion<px4_msgs::msg::VtolVehicleStatus>()) {}
39 return last().vehicle_vtol_state ==
40 px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_UNDEFINED;
50 return last().vehicle_vtol_state ==
51 px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_TRANSITION_TO_FW;
61 return last().vehicle_vtol_state ==
62 px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_TRANSITION_TO_MC;
72 return last().vehicle_vtol_state == px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_MC;
82 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:25
bool isUndefined() const
Check if vehicle is in an undefined state. This indicates the vehicle is not a VTOL.
Definition vtol_status.hpp:37
bool isTransitioningToFw() const
Check if VTOL is transitioning to fixed-wing.
Definition vtol_status.hpp:48
bool isFwMode() const
Check if VTOL is in fixed-wing mode.
Definition vtol_status.hpp:80
bool isMcMode() const
Check if VTOL is in multicopter mode.
Definition vtol_status.hpp:70
bool isTransitioningToMc() const
Check if VTOL is transitioning to multicopter.
Definition vtol_status.hpp:59