8#include <px4_msgs/msg/trajectory_setpoint.hpp>
11#include <px4_ros2/common/setpoint_base.hpp>
19struct TrajectorySetpoint;
41 const Eigen::Vector3f & velocity_ned_m_s,
42 const std::optional<Eigen::Vector3f> & acceleration_ned_m_s2 = {},
43 std::optional<float> yaw_ned_rad = {},
44 std::optional<float> yaw_rate_ned_rad_s = {});
66 const Eigen::Vector3f & position_ned_m);
70 rclcpp::Publisher<px4_msgs::msg::TrajectorySetpoint>::SharedPtr _trajectory_setpoint_pub;
72 const bool _local_position_is_optional;
101 std::optional<float> position_ned_m_x;
102 std::optional<float> position_ned_m_y;
103 std::optional<float> position_ned_m_z;
105 std::optional<float> velocity_ned_m_s_x;
106 std::optional<float> velocity_ned_m_s_y;
107 std::optional<float> velocity_ned_m_s_z;
109 std::optional<float> acceleration_ned_m_s2_x;
110 std::optional<float> acceleration_ned_m_s2_y;
111 std::optional<float> acceleration_ned_m_s2_z;
113 std::optional<float> yaw_ned_rad;
114 std::optional<float> yaw_rate_ned_rad_s;
124 position_ned_m_x = x_ned_m;
135 position_ned_m_y = y_ned_m;
146 position_ned_m_z = z_ned_m;
157 velocity_ned_m_s_x = x_ned_m_s;
168 velocity_ned_m_s_y = y_ned_m_s;
179 velocity_ned_m_s_z = z_ned_m_s;
190 acceleration_ned_m_s2_x = x_ned_m_s2;
201 acceleration_ned_m_s2_y = y_ned_m_s2;
212 acceleration_ned_m_s2_z = z_ned_m_s2;
223 this->yaw_ned_rad = yaw_rad;
234 this->yaw_rate_ned_rad_s = rate_rad_s;
246 position_ned_m_x = position_ned_m.x();
247 position_ned_m_y = position_ned_m.y();
248 position_ned_m_z = position_ned_m.z();
259 position_ned_m_x = position_ned_m.x();
260 position_ned_m_y = position_ned_m.y();
271 velocity_ned_m_s_x = velocity_ned_m_s.x();
272 velocity_ned_m_s_y = velocity_ned_m_s.y();
273 velocity_ned_m_s_z = velocity_ned_m_s.z();
284 velocity_ned_m_s_x = velocity_ned_m_s.x();
285 velocity_ned_m_s_y = velocity_ned_m_s.y();
296 acceleration_ned_m_s2_x = acceleration_ned_m_s2.x();
297 acceleration_ned_m_s2_y = acceleration_ned_m_s2.y();
298 acceleration_ned_m_s2_z = acceleration_ned_m_s2.z();
309 acceleration_ned_m_s2_x = acceleration_ned_m_s2.x();
310 acceleration_ned_m_s2_y = acceleration_ned_m_s2.y();
Definition context.hpp:20
Definition setpoint_base.hpp:20
Setpoint type for trajectory control.
Definition trajectory.hpp:27
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:25
Setpoint structure for trajectory control with fine-grained control over individual components.
Definition trajectory.hpp:100
TrajectorySetpoint & withYaw(float yaw_rad)
Set yaw setpoint in NED frame.
Definition trajectory.hpp:221
TrajectorySetpoint & withHorizontalAcceleration(const Eigen::Vector2f &acceleration_ned_m_s2)
Set acceleration setpoint for horizontal axes (x, y) in NED frame.
Definition trajectory.hpp:307
TrajectorySetpoint & withHorizontalVelocity(const Eigen::Vector2f &velocity_ned_m_s)
Set velocity setpoint for horizontal axes (x, y) in NED frame.
Definition trajectory.hpp:282
TrajectorySetpoint & withHorizontalPosition(const Eigen::Vector2f &position_ned_m)
Set position setpoint for horizontal axes (x, y) in NED frame.
Definition trajectory.hpp:257
TrajectorySetpoint & withPositionX(float x_ned_m)
Set position setpoint for x-axis in NED frame.
Definition trajectory.hpp:122
TrajectorySetpoint & withAccelerationY(float y_ned_m_s2)
Set acceleration setpoint for y-axis in NED frame.
Definition trajectory.hpp:199
TrajectorySetpoint & withYawRate(float rate_rad_s)
Set yaw rate setpoint in NED frame.
Definition trajectory.hpp:232
TrajectorySetpoint & withAcceleration(const Eigen::Vector3f &acceleration_ned_m_s2)
Set acceleration setpoint for all axes (x, y, z) in NED frame.
Definition trajectory.hpp:294
TrajectorySetpoint & withVelocityX(float x_ned_m_s)
Set velocity setpoint for x-axis in NED frame.
Definition trajectory.hpp:155
TrajectorySetpoint & withPositionY(float y_ned_m)
Set position setpoint for y-axis in NED frame.
Definition trajectory.hpp:133
TrajectorySetpoint & withVelocityZ(float z_ned_m_s)
Set velocity setpoint for z-axis in NED frame.
Definition trajectory.hpp:177
TrajectorySetpoint & withAccelerationX(float x_ned_m_s2)
Set acceleration setpoint for x-axis in NED frame.
Definition trajectory.hpp:188
TrajectorySetpoint & withPositionZ(float z_ned_m)
Set position setpoint for z-axis in NED frame.
Definition trajectory.hpp:144
TrajectorySetpoint & withVelocity(const Eigen::Vector3f &velocity_ned_m_s)
Set velocity setpoint for all axes (x, y, z) in NED frame.
Definition trajectory.hpp:269
TrajectorySetpoint & withPosition(const Eigen::Vector3f &position_ned_m)
Set position setpoint for all axes (x, y, z) in NED frame.
Definition trajectory.hpp:244
TrajectorySetpoint & withAccelerationZ(float z_ned_m_s2)
Set acceleration setpoint for z-axis in NED frame.
Definition trajectory.hpp:210
TrajectorySetpoint & withVelocityY(float y_ned_m_s)
Set velocity setpoint for y-axis in NED frame.
Definition trajectory.hpp:166