PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
px4_ros2::TrajectorySetpointType Class Reference

Setpoint type for trajectory control. More...

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

Inheritance diagram for px4_ros2::TrajectorySetpointType:
px4_ros2::SetpointBase

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< SetpointBasegetSharedPtr ()
 
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 ()
 

Detailed Description

Setpoint type for trajectory control.

Control entries must not be contradicting.

Member Function Documentation

◆ updatePosition()

void px4_ros2::TrajectorySetpointType::updatePosition ( const Eigen::Vector3f &  position_ned_m)

Position setpoint update.

The GotoSetpointType should be preferred.

Parameters
position_ned_m[m] NED earth-fixed frame

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