PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
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
17namespace px4_ros2 {
22struct FwLateralLongitudinalSetpoint;
23struct FwControlConfiguration;
24
29 public:
36 explicit FwLateralLongitudinalSetpointType(Context& context, bool is_position_optional = false);
37
38 ~FwLateralLongitudinalSetpointType() override = default;
39
40 Configuration getConfiguration() override;
41
61 void update(const FwLateralLongitudinalSetpoint& setpoint, const FwControlConfiguration& config);
62
78
87 void updateWithAltitude(float altitude_amsl_sp, float course_sp,
88 std::optional<float> equivalent_airspeed_sp = {},
89 std::optional<float> lateral_acceleration_sp = {});
90
99 void updateWithHeightRate(float height_rate_sp, float course_sp,
100 std::optional<float> equivalent_airspeed_sp = {},
101 std::optional<float> lateral_acceleration_sp = {});
102
103 float desiredUpdateRateHz() override { return 30.f; }
104
105 private:
106 rclcpp::Node& _node;
107 bool _local_position_is_optional;
108 rclcpp::Publisher<px4_msgs::msg::FixedWingLateralSetpoint>::SharedPtr _fw_lateral_sp_pub;
109 rclcpp::Publisher<px4_msgs::msg::FixedWingLongitudinalSetpoint>::SharedPtr
110 _fw_longitudinal_sp_pub;
111
112 rclcpp::Publisher<px4_msgs::msg::LateralControlConfiguration>::SharedPtr
113 _lateral_control_configuration_pub;
114 rclcpp::Publisher<px4_msgs::msg::LongitudinalControlConfiguration>::SharedPtr
115 _longitudinal_control_configuration_pub;
116};
117
119 std::optional<float> course;
120 std::optional<float> airspeed_direction;
121 std::optional<float> lateral_acceleration;
122 std::optional<float> altitude_msl;
123 std::optional<float> height_rate;
124 std::optional<float> equivalent_airspeed;
125 std::optional<float> throttle_direct;
126
127 FwLateralLongitudinalSetpoint& withCourse(float course_sp)
128 {
129 course = course_sp;
130 return *this;
131 }
132
133 FwLateralLongitudinalSetpoint& withAirspeedDirection(float airspeed_direction_sp)
134 {
135 airspeed_direction = airspeed_direction_sp;
136 return *this;
137 }
138
139 FwLateralLongitudinalSetpoint& withLateralAcceleration(float lateral_acceleration_sp)
140 {
141 lateral_acceleration = lateral_acceleration_sp;
142 return *this;
143 }
144
145 FwLateralLongitudinalSetpoint& withAltitude(float altitude_sp)
146 {
147 altitude_msl = altitude_sp;
148 return *this;
149 }
150
151 FwLateralLongitudinalSetpoint& withHeightRate(float height_rate_sp)
152 {
153 height_rate = height_rate_sp;
154 return *this;
155 }
156
157 FwLateralLongitudinalSetpoint& withEquivalentAirspeed(float equivalent_airspeed_sp)
158 {
159 equivalent_airspeed = equivalent_airspeed_sp;
160 return *this;
161 }
162
163 FwLateralLongitudinalSetpoint& withThrottleDirect(float throttle_direct_sp)
164 {
165 throttle_direct = throttle_direct_sp;
166 return *this;
167 }
168};
169
171 std::optional<float> min_pitch;
172 std::optional<float> max_pitch;
173 std::optional<float> min_throttle;
174 std::optional<float> max_throttle;
175 std::optional<float> max_lateral_acceleration;
176 std::optional<float> target_climb_rate;
177 std::optional<float> target_sink_rate;
178 std::optional<float> speed_weight;
179
180 FwControlConfiguration& withPitchLimits(float min_pitch_sp, float max_pitch_sp)
181 {
182 min_pitch = min_pitch_sp;
183 max_pitch = max_pitch_sp;
184
185 return *this;
186 }
187
188 FwControlConfiguration& withThrottleLimits(float min_throttle_sp, float max_throttle_sp)
189 {
190 min_throttle = min_throttle_sp;
191 max_throttle = max_throttle_sp;
192
193 return *this;
194 }
195
196 FwControlConfiguration& withMaxAcceleration(float max_lateral_acceleration_sp)
197 {
198 max_lateral_acceleration = max_lateral_acceleration_sp;
199 return *this;
200 }
201
202 FwControlConfiguration& withTargetSinkRate(float target_sink_rate_sp)
203 {
204 target_sink_rate = target_sink_rate_sp;
205 return *this;
206 }
207
208 FwControlConfiguration& withTargetClimbRate(float target_climb_rate_sp)
209 {
210 target_climb_rate = target_climb_rate_sp;
211 return *this;
212 }
213
223 {
224 if (speed_weight_sp < 0.0 || speed_weight_sp > 2.0) {
225 throw Exception("Speed weight must be between 0 and 2.");
226 }
227 speed_weight = speed_weight_sp;
228 return *this;
229 }
230};
231
233} /* namespace px4_ros2 */
Definition context.hpp:18
Definition exception.hpp:14
Setpoint type for fixedwing control.
Definition lateral_longitudinal.hpp:28
FwLateralLongitudinalSetpointType(Context &context, bool is_position_optional=false)
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:170
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:222
Definition lateral_longitudinal.hpp:118
Definition setpoint_base.hpp:23