PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
|
Setpoint type for rover throttle and attitude control. More...
#include <px4_ros2/control/setpoint_types/experimental/rover/throttle_attitude.hpp>
Public Member Functions | |
RoverThrottleAttitudeSetpointType (Context &context) | |
Configuration | getConfiguration () override |
float | desiredUpdateRateHz () override |
void | update (float throttle_body_x, float yaw_setpoint, std::optional< float > throttle_body_y={}) |
Send a rover throttle setpoint and a rover attitude 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 throttle and attitude control.
void px4_ros2::RoverThrottleAttitudeSetpointType::update | ( | float | throttle_body_x, |
float | yaw_setpoint, | ||
std::optional< float > | throttle_body_y = {} |
||
) |
Send a rover throttle setpoint and a rover attitude setpoint to the flight controller.
throttle_body_x | [-] Throttle setpoint along body X axis. Takes values in [-1 (Backwards), 1 (Forwards)]. |
yaw_setpoint | [rad] Yaw setpoint in NED frame. Takes values in [-pi, pi]. |
throttle_body_y | [-] Mecanum only: Throttle setpoint along body Y axis (Only relevant for mecanum rovers). Takes values in [-1 (Left), 1 (Right)]. |