PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
px4_ros2::TrajectorySetpoint Struct Reference

Setpoint structure for trajectory control with fine-grained control over individual components. More...

#include <px4_ros2/control/setpoint_types/experimental/trajectory.hpp>

Public Member Functions

TrajectorySetpointwithPositionX (float x_ned_m)
 Set position setpoint for x-axis in NED frame.
 
TrajectorySetpointwithPositionY (float y_ned_m)
 Set position setpoint for y-axis in NED frame.
 
TrajectorySetpointwithPositionZ (float z_ned_m)
 Set position setpoint for z-axis in NED frame.
 
TrajectorySetpointwithVelocityX (float x_ned_m_s)
 Set velocity setpoint for x-axis in NED frame.
 
TrajectorySetpointwithVelocityY (float y_ned_m_s)
 Set velocity setpoint for y-axis in NED frame.
 
TrajectorySetpointwithVelocityZ (float z_ned_m_s)
 Set velocity setpoint for z-axis in NED frame.
 
TrajectorySetpointwithAccelerationX (float x_ned_m_s2)
 Set acceleration setpoint for x-axis in NED frame.
 
TrajectorySetpointwithAccelerationY (float y_ned_m_s2)
 Set acceleration setpoint for y-axis in NED frame.
 
TrajectorySetpointwithAccelerationZ (float z_ned_m_s2)
 Set acceleration setpoint for z-axis in NED frame.
 
TrajectorySetpointwithYaw (float yaw_rad)
 Set yaw setpoint in NED frame.
 
TrajectorySetpointwithYawRate (float rate_rad_s)
 Set yaw rate setpoint in NED frame.
 
TrajectorySetpointwithPosition (const Eigen::Vector3f &position_ned_m)
 Set position setpoint for all axes (x, y, z) in NED frame.
 
TrajectorySetpointwithHorizontalPosition (const Eigen::Vector2f &position_ned_m)
 Set position setpoint for horizontal axes (x, y) in NED frame.
 
TrajectorySetpointwithVelocity (const Eigen::Vector3f &velocity_ned_m_s)
 Set velocity setpoint for all axes (x, y, z) in NED frame.
 
TrajectorySetpointwithHorizontalVelocity (const Eigen::Vector2f &velocity_ned_m_s)
 Set velocity setpoint for horizontal axes (x, y) in NED frame.
 
TrajectorySetpointwithAcceleration (const Eigen::Vector3f &acceleration_ned_m_s2)
 Set acceleration setpoint for all axes (x, y, z) in NED frame.
 
TrajectorySetpointwithHorizontalAcceleration (const Eigen::Vector2f &acceleration_ned_m_s2)
 Set acceleration setpoint for horizontal axes (x, y) in NED frame.
 

Public Attributes

std::optional< float > position_ned_m_x
 
std::optional< float > position_ned_m_y
 
std::optional< float > position_ned_m_z
 
std::optional< float > velocity_ned_m_s_x
 
std::optional< float > velocity_ned_m_s_y
 
std::optional< float > velocity_ned_m_s_z
 
std::optional< float > acceleration_ned_m_s2_x
 
std::optional< float > acceleration_ned_m_s2_y
 
std::optional< float > acceleration_ned_m_s2_z
 
std::optional< float > yaw_ned_rad
 
std::optional< float > yaw_rate_ned_rad_s
 

Detailed Description

Setpoint structure for trajectory control with fine-grained control over individual components.

This structure allows setting position, velocity, acceleration, yaw, and yaw rate individually on a per-axis basis. All fields are optional which means unset fields will not be controlled (NaN values will be sent to PX4).

Warning
Combining certain types of setpoints (e.g., position and velocity on the same axis) can lead to inconsistencies and unstable behavior. Use with caution.
Note
For simple position control, use TrajectorySetpointType::updatePosition() instead, or even better, use the GotoSetpointTypeif possible.

Example: Altitude hold with horizontal velocity

setpoint.withHorizontalVelocity(Eigen::Vector2f(1.0f, 0.5f)) // Move at 1 m/s forward, 0.5 m/s right
.withPositionZ(-2.0f); // Hold altitude at 2 meters above ground
trajectory_setpoint_type->update(setpoint);
Setpoint structure for trajectory control with fine-grained control over individual components.
Definition trajectory.hpp:93
TrajectorySetpoint & withHorizontalVelocity(const Eigen::Vector2f &velocity_ned_m_s)
Set velocity setpoint for horizontal axes (x, y) in NED frame.
Definition trajectory.hpp:275
TrajectorySetpoint & withPositionZ(float z_ned_m)
Set position setpoint for z-axis in NED frame.
Definition trajectory.hpp:137

Member Function Documentation

◆ withAcceleration()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withAcceleration ( const Eigen::Vector3f &  acceleration_ned_m_s2)
inline

Set acceleration setpoint for all axes (x, y, z) in NED frame.

Parameters
acceleration_ned_m_s2Acceleration vector in NED frame [m/s²]
Returns
Reference to self for method chaining

◆ withAccelerationX()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withAccelerationX ( float  x_ned_m_s2)
inline

Set acceleration setpoint for x-axis in NED frame.

Parameters
x_ned_m_s2Acceleration in x-axis [m/s²]
Returns
Reference to self for method chaining

◆ withAccelerationY()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withAccelerationY ( float  y_ned_m_s2)
inline

Set acceleration setpoint for y-axis in NED frame.

Parameters
y_ned_m_s2Acceleration in y-axis [m/s²]
Returns
Reference to self for method chaining

◆ withAccelerationZ()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withAccelerationZ ( float  z_ned_m_s2)
inline

Set acceleration setpoint for z-axis in NED frame.

Parameters
z_ned_m_s2Acceleration in z-axis [m/s²] (negative = upward in NED frame)
Returns
Reference to self for method chaining

◆ withHorizontalAcceleration()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withHorizontalAcceleration ( const Eigen::Vector2f &  acceleration_ned_m_s2)
inline

Set acceleration setpoint for horizontal axes (x, y) in NED frame.

Parameters
acceleration_ned_m_s2Acceleration vector in NE plane [m/s²]
Returns
Reference to self for method chaining

◆ withHorizontalPosition()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withHorizontalPosition ( const Eigen::Vector2f &  position_ned_m)
inline

Set position setpoint for horizontal axes (x, y) in NED frame.

Parameters
position_ned_mPosition vector in NE plane [m]
Returns
Reference to self for method chaining

◆ withHorizontalVelocity()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withHorizontalVelocity ( const Eigen::Vector2f &  velocity_ned_m_s)
inline

Set velocity setpoint for horizontal axes (x, y) in NED frame.

Parameters
velocity_ned_m_sVelocity vector in NE plane [m/s]
Returns
Reference to self for method chaining

◆ withPosition()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withPosition ( const Eigen::Vector3f &  position_ned_m)
inline

Set position setpoint for all axes (x, y, z) in NED frame.

Parameters
position_ned_mPosition vector in NED frame [m]
Returns
Reference to self for method chaining

◆ withPositionX()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withPositionX ( float  x_ned_m)
inline

Set position setpoint for x-axis in NED frame.

Parameters
x_ned_mPosition in x-axis [m]
Returns
Reference to self for method chaining

◆ withPositionY()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withPositionY ( float  y_ned_m)
inline

Set position setpoint for y-axis in NED frame.

Parameters
y_ned_mPosition in y-axis [m]
Returns
Reference to self for method chaining

◆ withPositionZ()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withPositionZ ( float  z_ned_m)
inline

Set position setpoint for z-axis in NED frame.

Parameters
z_ned_mPosition in z-axis [m] (negative = above ground in NED frame)
Returns
Reference to self for method chaining

◆ withVelocity()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withVelocity ( const Eigen::Vector3f &  velocity_ned_m_s)
inline

Set velocity setpoint for all axes (x, y, z) in NED frame.

Parameters
velocity_ned_m_sVelocity vector in NED frame [m/s]
Returns
Reference to self for method chaining

◆ withVelocityX()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withVelocityX ( float  x_ned_m_s)
inline

Set velocity setpoint for x-axis in NED frame.

Parameters
x_ned_m_sVelocity in x-axis [m/s]
Returns
Reference to self for method chaining

◆ withVelocityY()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withVelocityY ( float  y_ned_m_s)
inline

Set velocity setpoint for y-axis in NED frame.

Parameters
y_ned_m_sVelocity in y-axis [m/s]
Returns
Reference to self for method chaining

◆ withVelocityZ()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withVelocityZ ( float  z_ned_m_s)
inline

Set velocity setpoint for z-axis in NED frame.

Parameters
z_ned_m_sVelocity in z-axis [m/s] (negative = upward in NED frame)
Returns
Reference to self for method chaining

◆ withYaw()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withYaw ( float  yaw_rad)
inline

Set yaw setpoint in NED frame.

Parameters
yaw_radYaw angle [rad] (0 = North, PI/2 = East)
Returns
Reference to self for method chaining

◆ withYawRate()

TrajectorySetpoint & px4_ros2::TrajectorySetpoint::withYawRate ( float  rate_rad_s)
inline

Set yaw rate setpoint in NED frame.

Parameters
rate_rad_sYaw angular velocity [rad/s]
Returns
Reference to self for method chaining

The documentation for this struct was generated from the following file: