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

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

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

Public Member Functions

 GotoGlobalSetpointType (Context &context)
 
void update (const Eigen::Vector3d &global_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 global setpoint update. More...
 

Detailed Description

Setpoint type for smooth global position and heading control.

Member Function Documentation

◆ update()

void px4_ros2::GotoGlobalSetpointType::update ( const Eigen::Vector3d &  global_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 global setpoint update.

Unset optional values are not controlled

Parameters
global_positionlatitude [deg], longitude [deg], altitude AMSL [m]
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: