PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
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 <px4_msgs/msg/trajectory_setpoint.hpp>
9#include <Eigen/Eigen>
10
11#include <px4_ros2/common/setpoint_base.hpp>
12
13namespace px4_ros2
14{
19struct TrajectorySetpoint;
20
27{
28public:
34 explicit TrajectorySetpointType(Context & context, bool local_position_is_optional = false);
35
36 ~TrajectorySetpointType() override = default;
37
38 Configuration getConfiguration() override;
39
40 void update(
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 = {});
45
56 void update(const TrajectorySetpoint & setpoint);
57
66 const Eigen::Vector3f & position_ned_m);
67
68private:
69 rclcpp::Node & _node;
70 rclcpp::Publisher<px4_msgs::msg::TrajectorySetpoint>::SharedPtr _trajectory_setpoint_pub;
71
72 const bool _local_position_is_optional;
73};
74
100{
101 std::optional<float> position_ned_m_x;
102 std::optional<float> position_ned_m_y;
103 std::optional<float> position_ned_m_z;
104
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;
108
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;
112
113 std::optional<float> yaw_ned_rad;
114 std::optional<float> yaw_rate_ned_rad_s;
115
116
123 {
124 position_ned_m_x = x_ned_m;
125 return *this;
126 }
127
134 {
135 position_ned_m_y = y_ned_m;
136 return *this;
137 }
138
145 {
146 position_ned_m_z = z_ned_m;
147 return *this;
148 }
149
156 {
157 velocity_ned_m_s_x = x_ned_m_s;
158 return *this;
159 }
160
167 {
168 velocity_ned_m_s_y = y_ned_m_s;
169 return *this;
170 }
171
178 {
179 velocity_ned_m_s_z = z_ned_m_s;
180 return *this;
181 }
182
189 {
190 acceleration_ned_m_s2_x = x_ned_m_s2;
191 return *this;
192 }
193
200 {
201 acceleration_ned_m_s2_y = y_ned_m_s2;
202 return *this;
203 }
204
211 {
212 acceleration_ned_m_s2_z = z_ned_m_s2;
213 return *this;
214 }
215
222 {
223 this->yaw_ned_rad = yaw_rad;
224 return *this;
225 }
226
232 TrajectorySetpoint & withYawRate(float rate_rad_s)
233 {
234 this->yaw_rate_ned_rad_s = rate_rad_s;
235 return *this;
236 }
237
238 // Helper methods for setting multiple components at once
244 TrajectorySetpoint & withPosition(const Eigen::Vector3f & position_ned_m)
245 {
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();
249 return *this;
250 }
251
257 TrajectorySetpoint & withHorizontalPosition(const Eigen::Vector2f & position_ned_m)
258 {
259 position_ned_m_x = position_ned_m.x();
260 position_ned_m_y = position_ned_m.y();
261 return *this;
262 }
263
269 TrajectorySetpoint & withVelocity(const Eigen::Vector3f & velocity_ned_m_s)
270 {
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();
274 return *this;
275 }
276
282 TrajectorySetpoint & withHorizontalVelocity(const Eigen::Vector2f & velocity_ned_m_s)
283 {
284 velocity_ned_m_s_x = velocity_ned_m_s.x();
285 velocity_ned_m_s_y = velocity_ned_m_s.y();
286 return *this;
287 }
288
294 TrajectorySetpoint & withAcceleration(const Eigen::Vector3f & acceleration_ned_m_s2)
295 {
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();
299 return *this;
300 }
301
307 TrajectorySetpoint & withHorizontalAcceleration(const Eigen::Vector2f & acceleration_ned_m_s2)
308 {
309 acceleration_ned_m_s2_x = acceleration_ned_m_s2.x();
310 acceleration_ned_m_s2_y = acceleration_ned_m_s2.y();
311 return *this;
312 }
313};
314
315
316} /* namespace px4_ros2 */
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