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>
22struct FwLateralLongitudinalSetpoint;
23struct FwControlConfiguration;
82 std::optional<float> equivalent_airspeed_sp = {},
83 std::optional<float> lateral_acceleration_sp = {});
94 std::optional<float> equivalent_airspeed_sp = {},
95 std::optional<float> lateral_acceleration_sp = {});
97 float desiredUpdateRateHz()
override {
return 30.f; }
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;
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;
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;
128 airspeed_direction = airspeed_direction_sp;
134 lateral_acceleration = lateral_acceleration_sp;
140 altitude_msl = altitude_sp;
146 height_rate = height_rate_sp;
152 equivalent_airspeed = equivalent_airspeed_sp;
158 throttle_direct = throttle_direct_sp;
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;
175 min_pitch = min_pitch_sp;
176 max_pitch = max_pitch_sp;
183 min_throttle = min_throttle_sp;
184 max_throttle = max_throttle_sp;
191 max_lateral_acceleration = max_lateral_acceleration_sp;
197 target_sink_rate = target_sink_rate_sp;
203 target_climb_rate = target_climb_rate_sp;
217 if (speed_weight_sp < 0.0 || speed_weight_sp > 2.0) {
218 throw Exception(
"Speed weight must be between 0 and 2.");
220 speed_weight = speed_weight_sp;
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