PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
trajectory.hpp
1 /****************************************************************************
2  * Copyright (c) 2023 PX4 Development Team.
3  * SPDX-License-Identifier: BSD-3-Clause
4  ****************************************************************************/
5 
6 #pragma once
7 
8 #include <Eigen/Eigen>
9 #include <px4_msgs/msg/trajectory_setpoint.hpp>
10 #include <px4_ros2/common/setpoint_base.hpp>
11 
12 namespace px4_ros2 {
17 struct TrajectorySetpoint;
18 
25  public:
31  explicit TrajectorySetpointType(Context& context, bool local_position_is_optional = false);
32 
33  ~TrajectorySetpointType() override = default;
34 
35  Configuration getConfiguration() override;
36 
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 = {});
40 
51  void update(const TrajectorySetpoint& setpoint);
52 
60  void updatePosition(const Eigen::Vector3f& position_ned_m);
61 
62  private:
63  rclcpp::Node& _node;
64  rclcpp::Publisher<px4_msgs::msg::TrajectorySetpoint>::SharedPtr _trajectory_setpoint_pub;
65 
66  const bool _local_position_is_optional;
67 };
68 
94  std::optional<float> position_ned_m_x;
95  std::optional<float> position_ned_m_y;
96  std::optional<float> position_ned_m_z;
97 
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;
101 
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;
105 
106  std::optional<float> yaw_ned_rad;
107  std::optional<float> yaw_rate_ned_rad_s;
108 
115  {
116  position_ned_m_x = x_ned_m;
117  return *this;
118  }
119 
126  {
127  position_ned_m_y = y_ned_m;
128  return *this;
129  }
130 
137  {
138  position_ned_m_z = z_ned_m;
139  return *this;
140  }
141 
148  {
149  velocity_ned_m_s_x = x_ned_m_s;
150  return *this;
151  }
152 
159  {
160  velocity_ned_m_s_y = y_ned_m_s;
161  return *this;
162  }
163 
170  {
171  velocity_ned_m_s_z = z_ned_m_s;
172  return *this;
173  }
174 
181  {
182  acceleration_ned_m_s2_x = x_ned_m_s2;
183  return *this;
184  }
185 
192  {
193  acceleration_ned_m_s2_y = y_ned_m_s2;
194  return *this;
195  }
196 
203  {
204  acceleration_ned_m_s2_z = z_ned_m_s2;
205  return *this;
206  }
207 
213  TrajectorySetpoint& withYaw(float yaw_rad)
214  {
215  this->yaw_ned_rad = yaw_rad;
216  return *this;
217  }
218 
224  TrajectorySetpoint& withYawRate(float rate_rad_s)
225  {
226  this->yaw_rate_ned_rad_s = rate_rad_s;
227  return *this;
228  }
229 
230  // Helper methods for setting multiple components at once
236  TrajectorySetpoint& withPosition(const Eigen::Vector3f& position_ned_m)
237  {
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();
241  return *this;
242  }
243 
249  TrajectorySetpoint& withHorizontalPosition(const Eigen::Vector2f& position_ned_m)
250  {
251  position_ned_m_x = position_ned_m.x();
252  position_ned_m_y = position_ned_m.y();
253  return *this;
254  }
255 
261  TrajectorySetpoint& withVelocity(const Eigen::Vector3f& velocity_ned_m_s)
262  {
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();
266  return *this;
267  }
268 
274  TrajectorySetpoint& withHorizontalVelocity(const Eigen::Vector2f& velocity_ned_m_s)
275  {
276  velocity_ned_m_s_x = velocity_ned_m_s.x();
277  velocity_ned_m_s_y = velocity_ned_m_s.y();
278  return *this;
279  }
280 
286  TrajectorySetpoint& withAcceleration(const Eigen::Vector3f& acceleration_ned_m_s2)
287  {
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();
291  return *this;
292  }
293 
299  TrajectorySetpoint& withHorizontalAcceleration(const Eigen::Vector2f& acceleration_ned_m_s2)
300  {
301  acceleration_ned_m_s2_x = acceleration_ned_m_s2.x();
302  acceleration_ned_m_s2_y = acceleration_ned_m_s2.y();
303  return *this;
304  }
305 };
306 
307 } /* namespace px4_ros2 */
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 & 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 & withHorizontalVelocity(const Eigen::Vector2f &velocity_ned_m_s)
Set velocity setpoint for horizontal axes (x, y) in NED frame.
Definition: trajectory.hpp:274
TrajectorySetpoint & withPositionZ(float z_ned_m)
Set position setpoint for z-axis in NED frame.
Definition: trajectory.hpp:136
TrajectorySetpoint & withHorizontalPosition(const Eigen::Vector2f &position_ned_m)
Set position setpoint for horizontal axes (x, y) in NED frame.
Definition: trajectory.hpp:249
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 & 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 & withVelocityY(float y_ned_m_s)
Set velocity setpoint for y-axis in NED frame.
Definition: trajectory.hpp:158
TrajectorySetpoint & withPositionX(float x_ned_m)
Set position setpoint for x-axis in NED frame.
Definition: trajectory.hpp:114
TrajectorySetpoint & withAccelerationX(float x_ned_m_s2)
Set acceleration setpoint for x-axis in NED frame.
Definition: trajectory.hpp:180
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 & 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 & withVelocityX(float x_ned_m_s)
Set velocity setpoint for x-axis in NED frame.
Definition: trajectory.hpp:147
TrajectorySetpoint & withYaw(float yaw_rad)
Set yaw setpoint in NED frame.
Definition: trajectory.hpp:213
TrajectorySetpoint & withAccelerationZ(float z_ned_m_s2)
Set acceleration setpoint for z-axis in NED frame.
Definition: trajectory.hpp:202
TrajectorySetpoint & withPosition(const Eigen::Vector3f &position_ned_m)
Set position setpoint for all axes (x, y, z) in NED frame.
Definition: trajectory.hpp:236