PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
lateral_longitudinal.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/Eigen>
9 #include <optional>
10 #include <px4_msgs/msg/fixed_wing_lateral_setpoint.hpp>
11 #include <px4_msgs/msg/fixed_wing_longitudinal_setpoint.hpp>
12 #include <px4_msgs/msg/lateral_control_configuration.hpp>
13 #include <px4_msgs/msg/longitudinal_control_configuration.hpp>
14 #include <px4_ros2/common/exception.hpp>
15 #include <px4_ros2/common/setpoint_base.hpp>
16 
17 namespace px4_ros2 {
22 struct FwLateralLongitudinalSetpoint;
23 struct FwControlConfiguration;
24 
29  public:
30  explicit FwLateralLongitudinalSetpointType(Context& context);
31 
32  ~FwLateralLongitudinalSetpointType() override = default;
33 
34  Configuration getConfiguration() override;
35 
55  void update(const FwLateralLongitudinalSetpoint& setpoint, const FwControlConfiguration& config);
56 
71  void update(const FwLateralLongitudinalSetpoint& setpoint);
72 
81  void updateWithAltitude(float altitude_amsl_sp, float course_sp,
82  std::optional<float> equivalent_airspeed_sp = {},
83  std::optional<float> lateral_acceleration_sp = {});
84 
93  void updateWithHeightRate(float height_rate_sp, float course_sp,
94  std::optional<float> equivalent_airspeed_sp = {},
95  std::optional<float> lateral_acceleration_sp = {});
96 
97  float desiredUpdateRateHz() override { return 30.f; }
98 
99  private:
100  rclcpp::Node& _node;
101  rclcpp::Publisher<px4_msgs::msg::FixedWingLateralSetpoint>::SharedPtr _fw_lateral_sp_pub;
102  rclcpp::Publisher<px4_msgs::msg::FixedWingLongitudinalSetpoint>::SharedPtr
103  _fw_longitudinal_sp_pub;
104 
105  rclcpp::Publisher<px4_msgs::msg::LateralControlConfiguration>::SharedPtr
106  _lateral_control_configuration_pub;
107  rclcpp::Publisher<px4_msgs::msg::LongitudinalControlConfiguration>::SharedPtr
108  _longitudinal_control_configuration_pub;
109 };
110 
112  std::optional<float> course;
113  std::optional<float> airspeed_direction;
114  std::optional<float> lateral_acceleration;
115  std::optional<float> altitude_msl;
116  std::optional<float> height_rate;
117  std::optional<float> equivalent_airspeed;
118  std::optional<float> throttle_direct;
119 
120  FwLateralLongitudinalSetpoint& withCourse(float course_sp)
121  {
122  course = course_sp;
123  return *this;
124  }
125 
126  FwLateralLongitudinalSetpoint& withAirspeedDirection(float airspeed_direction_sp)
127  {
128  airspeed_direction = airspeed_direction_sp;
129  return *this;
130  }
131 
132  FwLateralLongitudinalSetpoint& withLateralAcceleration(float lateral_acceleration_sp)
133  {
134  lateral_acceleration = lateral_acceleration_sp;
135  return *this;
136  }
137 
138  FwLateralLongitudinalSetpoint& withAltitude(float altitude_sp)
139  {
140  altitude_msl = altitude_sp;
141  return *this;
142  }
143 
144  FwLateralLongitudinalSetpoint& withHeightRate(float height_rate_sp)
145  {
146  height_rate = height_rate_sp;
147  return *this;
148  }
149 
150  FwLateralLongitudinalSetpoint& withEquivalentAirspeed(float equivalent_airspeed_sp)
151  {
152  equivalent_airspeed = equivalent_airspeed_sp;
153  return *this;
154  }
155 
156  FwLateralLongitudinalSetpoint& withThrottleDirect(float throttle_direct_sp)
157  {
158  throttle_direct = throttle_direct_sp;
159  return *this;
160  }
161 };
162 
164  std::optional<float> min_pitch;
165  std::optional<float> max_pitch;
166  std::optional<float> min_throttle;
167  std::optional<float> max_throttle;
168  std::optional<float> max_lateral_acceleration;
169  std::optional<float> target_climb_rate;
170  std::optional<float> target_sink_rate;
171  std::optional<float> speed_weight;
172 
173  FwControlConfiguration& withPitchLimits(float min_pitch_sp, float max_pitch_sp)
174  {
175  min_pitch = min_pitch_sp;
176  max_pitch = max_pitch_sp;
177 
178  return *this;
179  }
180 
181  FwControlConfiguration& withThrottleLimits(float min_throttle_sp, float max_throttle_sp)
182  {
183  min_throttle = min_throttle_sp;
184  max_throttle = max_throttle_sp;
185 
186  return *this;
187  }
188 
189  FwControlConfiguration& withMaxAcceleration(float max_lateral_acceleration_sp)
190  {
191  max_lateral_acceleration = max_lateral_acceleration_sp;
192  return *this;
193  }
194 
195  FwControlConfiguration& withTargetSinkRate(float target_sink_rate_sp)
196  {
197  target_sink_rate = target_sink_rate_sp;
198  return *this;
199  }
200 
201  FwControlConfiguration& withTargetClimbRate(float target_climb_rate_sp)
202  {
203  target_climb_rate = target_climb_rate_sp;
204  return *this;
205  }
206 
215  FwControlConfiguration& withSpeedWeight(float speed_weight_sp)
216  {
217  if (speed_weight_sp < 0.0 || speed_weight_sp > 2.0) {
218  throw Exception("Speed weight must be between 0 and 2.");
219  }
220  speed_weight = speed_weight_sp;
221  return *this;
222  }
223 };
224 
226 } /* namespace px4_ros2 */
Definition: context.hpp:18
Definition: exception.hpp:14
Setpoint type for fixedwing control.
Definition: lateral_longitudinal.hpp:28
void updateWithAltitude(float altitude_amsl_sp, float course_sp, std::optional< float > equivalent_airspeed_sp={}, std::optional< float > lateral_acceleration_sp={})
Update the setpoint with simplest set of inputs: Altitude and Course. Lateral acceleration setpoints ...
void update(const FwLateralLongitudinalSetpoint &setpoint)
Update the setpoint with full flexibility by passing a FwLateralLongitudinalSetpoint.
void update(const FwLateralLongitudinalSetpoint &setpoint, const FwControlConfiguration &config)
Update the setpoint with full flexibility by passing a FwLateralLongitudinalSetpoint and FwControlCon...
void updateWithHeightRate(float height_rate_sp, float course_sp, std::optional< float > equivalent_airspeed_sp={}, std::optional< float > lateral_acceleration_sp={})
Update the setpoint with simplest set of inputs: Height rate and Course. Lateral acceleration setpoin...
Definition: setpoint_base.hpp:19
Definition: lateral_longitudinal.hpp:163
FwControlConfiguration & withSpeedWeight(float speed_weight_sp)
Configure the speed weight for TECS (Total Energy Control System). For more information on TECS,...
Definition: lateral_longitudinal.hpp:215
Definition: lateral_longitudinal.hpp:111
Definition: setpoint_base.hpp:23