|
PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
|
Setpoint type for smooth global position and heading control. More...
#include <px4_ros2/control/setpoint_types/multicopter/goto.hpp>
Public Member Functions | |
| MulticopterGotoGlobalSetpointType (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... | |
Setpoint type for smooth global position and heading control.
| void px4_ros2::MulticopterGotoGlobalSetpointType::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
| global_position | latitude [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 |