Setpoint type for direct attitude control.
More...
#include <px4_ros2/control/setpoint_types/experimental/attitude.hpp>
|
| 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)
|
|
| SetpointBase (Context &context) |
|
std::shared_ptr< SetpointBase > | getSharedPtr () |
|
void | setShouldActivateCallback (const ShouldActivateCB &should_activate_cb) |
|
void | setActive (bool active) |
|
|
using | ShouldActivateCB = std::function< void()> |
|
void | onUpdate () |
|
Setpoint type for direct attitude control.
◆ desiredUpdateRateHz()
float px4_ros2::AttitudeSetpointType::desiredUpdateRateHz |
( |
| ) |
|
|
inlineoverridevirtual |
◆ getConfiguration()
Configuration px4_ros2::AttitudeSetpointType::getConfiguration |
( |
| ) |
|
|
overridevirtual |
◆ 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
-
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] |
The documentation for this class was generated from the following file:
- px4_ros2_cpp/include/px4_ros2/control/setpoint_types/experimental/attitude.hpp