|
PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
|
Setpoint type for direct attitude control. More...
#include <px4_ros2/control/setpoint_types/experimental/attitude.hpp>
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< SetpointBase > | getSharedPtr () |
| 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 () |
Setpoint type for direct attitude control.
| 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)
| roll | Attitude setpoint roll angle [rad] |
| pitch | Attitude setpoint pitch angle [rad] |
| yaw | Attitude setpoint yaw angle [rad] |
| thrust_setpoint_body | Throttle demand [-1, 1]^3 |
| yaw_sp_move_rate_rad_s | Yaw setpoint move rate [rad/s] |