PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
vtol_status.hpp
1 /****************************************************************************
2  * Copyright (c) 2023-2024 PX4 Development Team.
3  * SPDX-License-Identifier: BSD-3-Clause
4  ****************************************************************************/
5 
6 #pragma once
7 
8 #include <px4_msgs/msg/vtol_vehicle_status.hpp>
9 #include <px4_ros2/common/context.hpp>
10 #include <px4_ros2/utils/subscription.hpp>
11 
12 namespace px4_ros2
13 {
23 class VtolStatus : public Subscription<px4_msgs::msg::VtolVehicleStatus>
24 {
25 public:
26  explicit VtolStatus(Context & context)
27  : Subscription<px4_msgs::msg::VtolVehicleStatus>(context, "fmu/out/vtol_vehicle_status") {}
28 
34  bool isUndefined() const
35  {
36  return last().vehicle_vtol_state ==
37  px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_UNDEFINED;
38  }
39 
45  bool isTransitioningToFw() const
46  {
47  return last().vehicle_vtol_state ==
48  px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_TRANSITION_TO_FW;
49  }
50 
56  bool isTransitioningToMc() const
57  {
58  return last().vehicle_vtol_state ==
59  px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_TRANSITION_TO_MC;
60  }
61 
67  bool isMcMode() const
68  {
69  return last().vehicle_vtol_state == px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_MC;
70  }
71 
77  bool isFwMode() const
78  {
79  return last().vehicle_vtol_state == px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_FW;
80  }
81 
82 };
83 
85 } /* namespace px4_ros2 */
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