PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
|
Setpoint type for trajectory control. More...
#include <px4_ros2/control/setpoint_types/experimental/trajectory.hpp>
Public Member Functions | |
TrajectorySetpointType (Context &context) | |
Configuration | getConfiguration () override |
void | update (const Eigen::Vector3f &velocity_ned_m_s, const std::optional< Eigen::Vector3f > &acceleration_ned_m_s2={}, std::optional< float > yaw_ned_rad={}, std::optional< float > yaw_rate_ned_rad_s={}) |
void | updatePosition (const Eigen::Vector3f &position_ned_m) |
Position setpoint update. More... | |
Public Member Functions inherited from px4_ros2::SetpointBase | |
SetpointBase (Context &context) | |
std::shared_ptr< SetpointBase > | getSharedPtr () |
virtual float | desiredUpdateRateHz () |
void | setShouldActivateCallback (const ShouldActivateCB &should_activate_cb) |
void | setActive (bool active) |
Additional Inherited Members | |
Public Types inherited from px4_ros2::SetpointBase | |
using | ShouldActivateCB = std::function< void()> |
Protected Member Functions inherited from px4_ros2::SetpointBase | |
void | onUpdate () |
Setpoint type for trajectory control.
Control entries must not be contradicting.
void px4_ros2::TrajectorySetpointType::updatePosition | ( | const Eigen::Vector3f & | position_ned_m | ) |
Position setpoint update.
The GotoSetpointType should be preferred.
position_ned_m | [m] NED earth-fixed frame |