PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
vtol.hpp
1 /****************************************************************************
2  * Copyright (c) 2025 PX4 Development Team.
3  * SPDX-License-Identifier: BSD-3-Clause
4  ****************************************************************************/
5 
6  #pragma once
7 
8  #include <px4_msgs/msg/vehicle_command.hpp>
9  #include <px4_msgs/msg/vtol_vehicle_status.hpp>
10  #include <px4_msgs/msg/vehicle_local_position.hpp>
11 #include <px4_ros2/components/shared_subscription.hpp>
12  #include <Eigen/Core>
13 
14  #include <px4_ros2/common/context.hpp>
15 
16 namespace px4_ros2
17 {
18 struct VTOLConfig
19 {
22  float deceleration_integrator_limit{0.3f};
23 
24  VTOLConfig & withBackTransitionDeceleration(
25  const float back_transition_deceleration)
26  {
27  this->back_transition_deceleration = back_transition_deceleration;
28  return *this;
29  }
30 
31  VTOLConfig & withDecelerationIntegratorLimit(
32  const float deceleration_integrator_limit)
33  {
34  this->deceleration_integrator_limit = deceleration_integrator_limit;
35  return *this;
36  }
37 
38  VTOLConfig & withBackTransitionDecelerationIGain(
40  {
41  this->back_transition_deceleration_setpoint_to_pitch_i =
43  return *this;
44  }
45 
46 
47 };
48 
56 class VTOL
57 {
58 public:
59  explicit VTOL(Context & context, const VTOLConfig & config = VTOLConfig{});
60 
61  enum class State
62  {
63  Undefined = 0,
64  TransitionToFixedWing = 1,
65  TransitionToMulticopter = 2,
66  Multicopter = 3,
67  FixedWing = 4
68  };
69 
74  bool toMulticopter();
75  bool toFixedwing();
76 
77  Eigen::Vector3f computeAccelerationSetpointDuringTransition(
78  std::optional<float> back_transition_deceleration_m_s2 = std::nullopt);
79 
80  State getCurrentState() const {return _current_state;}
81 
82 private:
83  rclcpp::Node & _node;
84  rclcpp::Publisher<px4_msgs::msg::VehicleCommand>::SharedPtr _vehicle_command_pub;
85  rclcpp::Subscription<px4_msgs::msg::VtolVehicleStatus>::SharedPtr _vtol_vehicle_status_sub;
86  SharedSubscriptionCallbackInstance _vehicle_local_position_cb;
87  rclcpp::Time _last_command_sent;
88  rclcpp::Time _last_vtol_vehicle_status_received;
89  rclcpp::Time _last_pitch_integrator_update{0, 0, _node.get_clock()->get_clock_type()};
90 
91  float _vehicle_heading{NAN};
92  float _decel_error_bt_int{0.f};
93 
94  Eigen::Vector2f _vehicle_acceleration_xy{NAN, NAN};
95 
96  State _current_state{State::Undefined};
97 
98  float computePitchSetpointDuringBacktransition(
99  std::optional<float> back_transition_deceleration_m_s2 = std::nullopt);
100 
101  VTOLConfig _config;
102 };
103 
105 } /* namespace px4_ros2 */
Definition: context.hpp:20
Provides VTOL transition command.
Definition: vtol.hpp:57
bool toMulticopter()
Definition: vtol.hpp:19
float back_transition_deceleration
Definition: vtol.hpp:20
float back_transition_deceleration_setpoint_to_pitch_i
Definition: vtol.hpp:21