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 #include <px4_ros2/utils/message_version.hpp>
12 
13 namespace px4_ros2
14 {
24 class VtolStatus : public Subscription<px4_msgs::msg::VtolVehicleStatus>
25 {
26 public:
27  explicit VtolStatus(Context & context)
29  "fmu/out/vtol_vehicle_status" +
30  px4_ros2::getMessageNameVersion<px4_msgs::msg::VtolVehicleStatus>()) {}
31 
37  bool isUndefined() const
38  {
39  return last().vehicle_vtol_state ==
40  px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_UNDEFINED;
41  }
42 
48  bool isTransitioningToFw() const
49  {
50  return last().vehicle_vtol_state ==
51  px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_TRANSITION_TO_FW;
52  }
53 
59  bool isTransitioningToMc() const
60  {
61  return last().vehicle_vtol_state ==
62  px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_TRANSITION_TO_MC;
63  }
64 
70  bool isMcMode() const
71  {
72  return last().vehicle_vtol_state == px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_MC;
73  }
74 
80  bool isFwMode() const
81  {
82  return last().vehicle_vtol_state == px4_msgs::msg::VtolVehicleStatus::VEHICLE_VTOL_STATE_FW;
83  }
84 
85 };
86 
88 } /* 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: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