PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
|
Setpoint type for rover position control. More...
#include <px4_ros2/control/setpoint_types/experimental/rover/position.hpp>
Public Member Functions | |
RoverPositionSetpointType (Context &context) | |
Configuration | getConfiguration () override |
float | desiredUpdateRateHz () override |
void | update (const Eigen::Vector2f &position_ned, const std::optional< Eigen::Vector2f > &start_ned={}, std::optional< float > cruising_speed={}, std::optional< float > arrival_speed={}, std::optional< float > yaw={}) |
Send a rover position setpoint to the flight controller. More... | |
![]() | |
SetpointBase (Context &context) | |
std::shared_ptr< SetpointBase > | getSharedPtr () |
void | setShouldActivateCallback (const ShouldActivateCB &should_activate_cb) |
void | setActive (bool active) |
Additional Inherited Members | |
![]() | |
using | ShouldActivateCB = std::function< void()> |
![]() | |
void | onUpdate () |
Setpoint type for rover position control.
void px4_ros2::RoverPositionSetpointType::update | ( | const Eigen::Vector2f & | position_ned, |
const std::optional< Eigen::Vector2f > & | start_ned = {} , |
||
std::optional< float > | cruising_speed = {} , |
||
std::optional< float > | arrival_speed = {} , |
||
std::optional< float > | yaw = {} |
||
) |
Send a rover position setpoint to the flight controller.
position_ned | [m] Target position in NED frame. Takes values in [-inf, inf]. |
start_ned | [m] Start position which specifies a line for the rover to track (Optional, defaults to vehicle position). Takes values in [-inf, inf]. |
cruising_speed | [m/s] Cruising speed (Optional, defaults to maximum speed). Takes values in [0, inf]. |
arrival_speed | [m/s] Speed the rover should arrive at the target with (Optional, defaults to zero). Takes values in [0, inf]. |
yaw | [rad] Mecanum only: Specify vehicle yaw during travel (Optional, defaults to vehicle yaw). Takes values in [-pi,pi]. |