Setpoint structure for trajectory control with fine-grained control over individual components.
More...
#include <px4_ros2/control/setpoint_types/experimental/trajectory.hpp>
|
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 |
|
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
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
◆ 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_s2 | Acceleration vector in NED frame [m/s²] |
- Returns
- Reference to self for method chaining
◆ withAccelerationX()
Set acceleration setpoint for x-axis in NED frame.
- Parameters
-
x_ned_m_s2 | Acceleration in x-axis [m/s²] |
- Returns
- Reference to self for method chaining
◆ withAccelerationY()
Set acceleration setpoint for y-axis in NED frame.
- Parameters
-
y_ned_m_s2 | Acceleration in y-axis [m/s²] |
- Returns
- Reference to self for method chaining
◆ withAccelerationZ()
Set acceleration setpoint for z-axis in NED frame.
- Parameters
-
z_ned_m_s2 | Acceleration 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_s2 | Acceleration 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_m | Position 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_s | Velocity 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_m | Position vector in NED frame [m] |
- Returns
- Reference to self for method chaining
◆ withPositionX()
Set position setpoint for x-axis in NED frame.
- Parameters
-
x_ned_m | Position in x-axis [m] |
- Returns
- Reference to self for method chaining
◆ withPositionY()
Set position setpoint for y-axis in NED frame.
- Parameters
-
y_ned_m | Position in y-axis [m] |
- Returns
- Reference to self for method chaining
◆ withPositionZ()
Set position setpoint for z-axis in NED frame.
- Parameters
-
z_ned_m | Position 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_s | Velocity vector in NED frame [m/s] |
- Returns
- Reference to self for method chaining
◆ withVelocityX()
Set velocity setpoint for x-axis in NED frame.
- Parameters
-
x_ned_m_s | Velocity in x-axis [m/s] |
- Returns
- Reference to self for method chaining
◆ withVelocityY()
Set velocity setpoint for y-axis in NED frame.
- Parameters
-
y_ned_m_s | Velocity in y-axis [m/s] |
- Returns
- Reference to self for method chaining
◆ withVelocityZ()
Set velocity setpoint for z-axis in NED frame.
- Parameters
-
z_ned_m_s | Velocity in z-axis [m/s] (negative = upward in NED frame) |
- Returns
- Reference to self for method chaining
◆ withYaw()
Set yaw setpoint in NED frame.
- Parameters
-
yaw_rad | Yaw angle [rad] (0 = North, PI/2 = East) |
- Returns
- Reference to self for method chaining
◆ withYawRate()
Set yaw rate setpoint in NED frame.
- Parameters
-
rate_rad_s | Yaw angular velocity [rad/s] |
- Returns
- Reference to self for method chaining
The documentation for this struct was generated from the following file:
- px4_ros2_cpp/include/px4_ros2/control/setpoint_types/experimental/trajectory.hpp