PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
|
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 | |
TrajectorySetpoint & | withPositionX (float x_ned_m) |
Set position setpoint for x-axis in NED frame. More... | |
TrajectorySetpoint & | withPositionY (float y_ned_m) |
Set position setpoint for y-axis in NED frame. More... | |
TrajectorySetpoint & | withPositionZ (float z_ned_m) |
Set position setpoint for z-axis in NED frame. More... | |
TrajectorySetpoint & | withVelocityX (float x_ned_m_s) |
Set velocity setpoint for x-axis in NED frame. More... | |
TrajectorySetpoint & | withVelocityY (float y_ned_m_s) |
Set velocity setpoint for y-axis in NED frame. More... | |
TrajectorySetpoint & | withVelocityZ (float z_ned_m_s) |
Set velocity setpoint for z-axis in NED frame. More... | |
TrajectorySetpoint & | withAccelerationX (float x_ned_m_s2) |
Set acceleration setpoint for x-axis in NED frame. More... | |
TrajectorySetpoint & | withAccelerationY (float y_ned_m_s2) |
Set acceleration setpoint for y-axis in NED frame. More... | |
TrajectorySetpoint & | withAccelerationZ (float z_ned_m_s2) |
Set acceleration setpoint for z-axis in NED frame. More... | |
TrajectorySetpoint & | withYaw (float yaw_rad) |
Set yaw setpoint in NED frame. More... | |
TrajectorySetpoint & | withYawRate (float rate_rad_s) |
Set yaw rate setpoint in NED frame. More... | |
TrajectorySetpoint & | withPosition (const Eigen::Vector3f &position_ned_m) |
Set position setpoint for all axes (x, y, z) in NED frame. More... | |
TrajectorySetpoint & | withHorizontalPosition (const Eigen::Vector2f &position_ned_m) |
Set position setpoint for horizontal axes (x, y) in NED frame. More... | |
TrajectorySetpoint & | withVelocity (const Eigen::Vector3f &velocity_ned_m_s) |
Set velocity setpoint for all axes (x, y, z) in NED frame. More... | |
TrajectorySetpoint & | withHorizontalVelocity (const Eigen::Vector2f &velocity_ned_m_s) |
Set velocity setpoint for horizontal axes (x, y) in NED frame. More... | |
TrajectorySetpoint & | withAcceleration (const Eigen::Vector3f &acceleration_ned_m_s2) |
Set acceleration setpoint for all axes (x, y, z) in NED frame. More... | |
TrajectorySetpoint & | withHorizontalAcceleration (const Eigen::Vector2f &acceleration_ned_m_s2) |
Set acceleration setpoint for horizontal axes (x, y) in NED frame. More... | |
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).
|
inline |
Set acceleration setpoint for all axes (x, y, z) in NED frame.
acceleration_ned_m_s2 | Acceleration vector in NED frame [m/s²] |
|
inline |
Set acceleration setpoint for x-axis in NED frame.
x_ned_m_s2 | Acceleration in x-axis [m/s²] |
|
inline |
Set acceleration setpoint for y-axis in NED frame.
y_ned_m_s2 | Acceleration in y-axis [m/s²] |
|
inline |
Set acceleration setpoint for z-axis in NED frame.
z_ned_m_s2 | Acceleration in z-axis [m/s²] (negative = upward in NED frame) |
|
inline |
Set acceleration setpoint for horizontal axes (x, y) in NED frame.
acceleration_ned_m_s2 | Acceleration vector in NE plane [m/s²] |
|
inline |
Set position setpoint for horizontal axes (x, y) in NED frame.
position_ned_m | Position vector in NE plane [m] |
|
inline |
Set velocity setpoint for horizontal axes (x, y) in NED frame.
velocity_ned_m_s | Velocity vector in NE plane [m/s] |
|
inline |
Set position setpoint for all axes (x, y, z) in NED frame.
position_ned_m | Position vector in NED frame [m] |
|
inline |
Set position setpoint for x-axis in NED frame.
x_ned_m | Position in x-axis [m] |
|
inline |
Set position setpoint for y-axis in NED frame.
y_ned_m | Position in y-axis [m] |
|
inline |
Set position setpoint for z-axis in NED frame.
z_ned_m | Position in z-axis [m] (negative = above ground in NED frame) |
|
inline |
Set velocity setpoint for all axes (x, y, z) in NED frame.
velocity_ned_m_s | Velocity vector in NED frame [m/s] |
|
inline |
Set velocity setpoint for x-axis in NED frame.
x_ned_m_s | Velocity in x-axis [m/s] |
|
inline |
Set velocity setpoint for y-axis in NED frame.
y_ned_m_s | Velocity in y-axis [m/s] |
|
inline |
Set velocity setpoint for z-axis in NED frame.
z_ned_m_s | Velocity in z-axis [m/s] (negative = upward in NED frame) |
|
inline |
Set yaw setpoint in NED frame.
yaw_rad | Yaw angle rad |
|
inline |
Set yaw rate setpoint in NED frame.
rate_rad_s | Yaw angular velocity [rad/s] |