9#include <px4_msgs/msg/trajectory_setpoint.hpp>
10#include <px4_ros2/common/setpoint_base.hpp>
17struct TrajectorySetpoint;
37 void update(
const Eigen::Vector3f& velocity_ned_m_s,
38 const std::optional<Eigen::Vector3f>& acceleration_ned_m_s2 = {},
39 std::optional<float> yaw_ned_rad = {}, std::optional<float> yaw_rate_ned_rad_s = {});
64 rclcpp::Publisher<px4_msgs::msg::TrajectorySetpoint>::SharedPtr _trajectory_setpoint_pub;
66 const bool _local_position_is_optional;
94 std::optional<float> position_ned_m_x;
95 std::optional<float> position_ned_m_y;
96 std::optional<float> position_ned_m_z;
98 std::optional<float> velocity_ned_m_s_x;
99 std::optional<float> velocity_ned_m_s_y;
100 std::optional<float> velocity_ned_m_s_z;
102 std::optional<float> acceleration_ned_m_s2_x;
103 std::optional<float> acceleration_ned_m_s2_y;
104 std::optional<float> acceleration_ned_m_s2_z;
106 std::optional<float> yaw_ned_rad;
107 std::optional<float> yaw_rate_ned_rad_s;
116 position_ned_m_x = x_ned_m;
127 position_ned_m_y = y_ned_m;
138 position_ned_m_z = z_ned_m;
149 velocity_ned_m_s_x = x_ned_m_s;
160 velocity_ned_m_s_y = y_ned_m_s;
171 velocity_ned_m_s_z = z_ned_m_s;
182 acceleration_ned_m_s2_x = x_ned_m_s2;
193 acceleration_ned_m_s2_y = y_ned_m_s2;
204 acceleration_ned_m_s2_z = z_ned_m_s2;
215 this->yaw_ned_rad = yaw_rad;
226 this->yaw_rate_ned_rad_s = rate_rad_s;
238 position_ned_m_x = position_ned_m.x();
239 position_ned_m_y = position_ned_m.y();
240 position_ned_m_z = position_ned_m.z();
251 position_ned_m_x = position_ned_m.x();
252 position_ned_m_y = position_ned_m.y();
263 velocity_ned_m_s_x = velocity_ned_m_s.x();
264 velocity_ned_m_s_y = velocity_ned_m_s.y();
265 velocity_ned_m_s_z = velocity_ned_m_s.z();
276 velocity_ned_m_s_x = velocity_ned_m_s.x();
277 velocity_ned_m_s_y = velocity_ned_m_s.y();
288 acceleration_ned_m_s2_x = acceleration_ned_m_s2.x();
289 acceleration_ned_m_s2_y = acceleration_ned_m_s2.y();
290 acceleration_ned_m_s2_z = acceleration_ned_m_s2.z();
301 acceleration_ned_m_s2_x = acceleration_ned_m_s2.x();
302 acceleration_ned_m_s2_y = acceleration_ned_m_s2.y();
Definition context.hpp:18
Definition setpoint_base.hpp:19
Setpoint type for trajectory control.
Definition trajectory.hpp:24
void updatePosition(const Eigen::Vector3f &position_ned_m)
Position setpoint update.
TrajectorySetpointType(Context &context, bool local_position_is_optional=false)
void update(const TrajectorySetpoint &setpoint)
Update the setpoint with full flexibility by passing a TrajectorySetpoint.
Definition setpoint_base.hpp:23
Setpoint structure for trajectory control with fine-grained control over individual components.
Definition trajectory.hpp:93
TrajectorySetpoint & withYaw(float yaw_rad)
Set yaw setpoint in NED frame.
Definition trajectory.hpp:213
TrajectorySetpoint & withHorizontalAcceleration(const Eigen::Vector2f &acceleration_ned_m_s2)
Set acceleration setpoint for horizontal axes (x, y) in NED frame.
Definition trajectory.hpp:299
TrajectorySetpoint & withHorizontalVelocity(const Eigen::Vector2f &velocity_ned_m_s)
Set velocity setpoint for horizontal axes (x, y) in NED frame.
Definition trajectory.hpp:274
TrajectorySetpoint & withHorizontalPosition(const Eigen::Vector2f &position_ned_m)
Set position setpoint for horizontal axes (x, y) in NED frame.
Definition trajectory.hpp:249
TrajectorySetpoint & withPositionX(float x_ned_m)
Set position setpoint for x-axis in NED frame.
Definition trajectory.hpp:114
TrajectorySetpoint & withAccelerationY(float y_ned_m_s2)
Set acceleration setpoint for y-axis in NED frame.
Definition trajectory.hpp:191
TrajectorySetpoint & withYawRate(float rate_rad_s)
Set yaw rate setpoint in NED frame.
Definition trajectory.hpp:224
TrajectorySetpoint & withAcceleration(const Eigen::Vector3f &acceleration_ned_m_s2)
Set acceleration setpoint for all axes (x, y, z) in NED frame.
Definition trajectory.hpp:286
TrajectorySetpoint & withVelocityX(float x_ned_m_s)
Set velocity setpoint for x-axis in NED frame.
Definition trajectory.hpp:147
TrajectorySetpoint & withPositionY(float y_ned_m)
Set position setpoint for y-axis in NED frame.
Definition trajectory.hpp:125
TrajectorySetpoint & withVelocityZ(float z_ned_m_s)
Set velocity setpoint for z-axis in NED frame.
Definition trajectory.hpp:169
TrajectorySetpoint & withAccelerationX(float x_ned_m_s2)
Set acceleration setpoint for x-axis in NED frame.
Definition trajectory.hpp:180
TrajectorySetpoint & withPositionZ(float z_ned_m)
Set position setpoint for z-axis in NED frame.
Definition trajectory.hpp:136
TrajectorySetpoint & withVelocity(const Eigen::Vector3f &velocity_ned_m_s)
Set velocity setpoint for all axes (x, y, z) in NED frame.
Definition trajectory.hpp:261
TrajectorySetpoint & withPosition(const Eigen::Vector3f &position_ned_m)
Set position setpoint for all axes (x, y, z) in NED frame.
Definition trajectory.hpp:236
TrajectorySetpoint & withAccelerationZ(float z_ned_m_s2)
Set acceleration setpoint for z-axis in NED frame.
Definition trajectory.hpp:202
TrajectorySetpoint & withVelocityY(float y_ned_m_s)
Set velocity setpoint for y-axis in NED frame.
Definition trajectory.hpp:158