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

Setpoint type for direct attitude control. More...

#include <px4_ros2/control/setpoint_types/experimental/attitude.hpp>

Inheritance diagram for px4_ros2::AttitudeSetpointType:
px4_ros2::SetpointBase

Public Member Functions

 AttitudeSetpointType (Context &context)
 
Configuration getConfiguration () override
 
float desiredUpdateRateHz () override
 
void update (const Eigen::Quaternionf &attitude_setpoint, const Eigen::Vector3f &thrust_setpoint_frd, float yaw_sp_move_rate_rad_s=0.f)
 
void update (float roll, float pitch, float yaw, const Eigen::Vector3f &thrust_setpoint_body, float yaw_sp_move_rate_rad_s=0.f)
 Send an attitude setpoint to the flight controller. Euler angles follow the RPY extrinsic Tait-Bryan convention (equiv. YPR intrinsic) More...
 
- 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 direct attitude control.

Member Function Documentation

◆ update()

void px4_ros2::AttitudeSetpointType::update ( float  roll,
float  pitch,
float  yaw,
const Eigen::Vector3f &  thrust_setpoint_body,
float  yaw_sp_move_rate_rad_s = 0.f 
)

Send an attitude setpoint to the flight controller. Euler angles follow the RPY extrinsic Tait-Bryan convention (equiv. YPR intrinsic)

Parameters
rollAttitude setpoint roll angle [rad]
pitchAttitude setpoint pitch angle [rad]
yawAttitude setpoint yaw angle [rad]
thrust_setpoint_bodyThrottle demand [-1, 1]^3
yaw_sp_move_rate_rad_sYaw setpoint move rate [rad/s]

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