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 <Eigen/Core>
9 #include <px4_msgs/msg/vehicle_command.hpp>
10 #include <px4_msgs/msg/vehicle_local_position.hpp>
11 #include <px4_msgs/msg/vtol_vehicle_status.hpp>
12 #include <px4_ros2/common/context.hpp>
13 #include <px4_ros2/components/shared_subscription.hpp>
14 
15 namespace px4_ros2 {
16 struct VTOLConfig {
18  2.f};
20  0.1f};
21  float deceleration_integrator_limit{0.3f};
22 
23  VTOLConfig& withBackTransitionDeceleration(const float back_transition_deceleration)
24  {
25  this->back_transition_deceleration = back_transition_deceleration;
26  return *this;
27  }
28 
29  VTOLConfig& withDecelerationIntegratorLimit(const float deceleration_integrator_limit)
30  {
31  this->deceleration_integrator_limit = deceleration_integrator_limit;
32  return *this;
33  }
34 
35  VTOLConfig& withBackTransitionDecelerationIGain(
37  {
38  this->back_transition_deceleration_setpoint_to_pitch_i =
40  return *this;
41  }
42 };
43 
51 class VTOL {
52  public:
53  explicit VTOL(Context& context, const VTOLConfig& config = VTOLConfig{});
54 
55  enum class State {
56  Undefined = 0,
57  TransitionToFixedWing = 1,
58  TransitionToMulticopter = 2,
59  Multicopter = 3,
60  FixedWing = 4
61  };
62 
67  bool toMulticopter();
68  bool toFixedwing();
69 
70  Eigen::Vector3f computeAccelerationSetpointDuringTransition(
71  std::optional<float> back_transition_deceleration_m_s2 = std::nullopt);
72 
73  State getCurrentState() const { return _current_state; }
74 
75  private:
76  rclcpp::Node& _node;
77  rclcpp::Publisher<px4_msgs::msg::VehicleCommand>::SharedPtr _vehicle_command_pub;
78  rclcpp::Subscription<px4_msgs::msg::VtolVehicleStatus>::SharedPtr _vtol_vehicle_status_sub;
79  SharedSubscriptionCallbackInstance _vehicle_local_position_cb;
80  rclcpp::Time _last_command_sent;
81  rclcpp::Time _last_vtol_vehicle_status_received;
82  rclcpp::Time _last_pitch_integrator_update{0, 0, _node.get_clock()->get_clock_type()};
83 
84  float _vehicle_heading{NAN};
85  float _decel_error_bt_int{0.f};
86 
87  Eigen::Vector2f _vehicle_acceleration_xy{NAN, NAN};
88 
89  State _current_state{State::Undefined};
90 
91  float computePitchSetpointDuringBacktransition(
92  std::optional<float> back_transition_deceleration_m_s2 = std::nullopt);
93 
94  VTOLConfig _config;
95 };
96 
98 } /* namespace px4_ros2 */
Definition: context.hpp:18
Provides VTOL transition command.
Definition: vtol.hpp:51
bool toMulticopter()
Definition: vtol.hpp:16
float back_transition_deceleration
Definition: vtol.hpp:17
float back_transition_deceleration_setpoint_to_pitch_i
Definition: vtol.hpp:19