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

Setpoint type for smooth position and heading control. More...

#include <px4_ros2/control/setpoint_types/goto.hpp>

Inheritance diagram for px4_ros2::GotoSetpointType:
px4_ros2::SetpointBase

Public Member Functions

 GotoSetpointType (Context &context)
 
Configuration getConfiguration () override
 
void update (const Eigen::Vector3f &position, const std::optional< float > &heading={}, const std::optional< float > &max_horizontal_speed={}, const std::optional< float > &max_vertical_speed={}, const std::optional< float > &max_heading_rate={})
 Go-to setpoint update. More...
 
float desiredUpdateRateHz () override
 
- Public Member Functions inherited from px4_ros2::SetpointBase
 SetpointBase (Context &context)
 
std::shared_ptr< SetpointBasegetSharedPtr ()
 
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 smooth position and heading control.

Member Function Documentation

◆ update()

void px4_ros2::GotoSetpointType::update ( const Eigen::Vector3f &  position,
const std::optional< float > &  heading = {},
const std::optional< float > &  max_horizontal_speed = {},
const std::optional< float > &  max_vertical_speed = {},
const std::optional< float > &  max_heading_rate = {} 
)

Go-to setpoint update.

Unset optional values are not controlled

Parameters
position[m] NED earth-fixed frame
heading[rad] from North
max_horizontal_speed[m/s] in NE-datum of NED earth-fixed frame
max_vertical_speed[m/s] in D-axis of NED earth-fixed frame
max_heading_rate[rad/s] about D-axis of NED earth-fixed frame

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