9 #include <px4_msgs/msg/vehicle_attitude_setpoint.hpp>
10 #include <px4_ros2/common/setpoint_base.hpp>
27 float desiredUpdateRateHz()
override {
return 100.f; }
29 void update(
const Eigen::Quaternionf& attitude_setpoint,
30 const Eigen::Vector3f& thrust_setpoint_frd,
float yaw_sp_move_rate_rad_s = 0.f);
42 void update(
float roll,
float pitch,
float yaw,
const Eigen::Vector3f& thrust_setpoint_body,
43 float yaw_sp_move_rate_rad_s = 0.f);
47 rclcpp::Publisher<px4_msgs::msg::VehicleAttitudeSetpoint>::SharedPtr
48 _vehicle_attitude_setpoint_pub;
Setpoint type for direct attitude control.
Definition: attitude.hpp:20
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 ...
Definition: context.hpp:18
Definition: setpoint_base.hpp:19
Definition: setpoint_base.hpp:23