8 #include <px4_msgs/msg/vehicle_attitude_setpoint.hpp>
11 #include <px4_ros2/common/setpoint_base.hpp>
30 float desiredUpdateRateHz()
override {
return 100.f;}
33 const Eigen::Quaternionf & attitude_setpoint,
34 const Eigen::Vector3f & thrust_setpoint_frd,
float yaw_sp_move_rate_rad_s = 0.f);
47 float roll,
float pitch,
float yaw,
48 const Eigen::Vector3f & thrust_setpoint_body,
float yaw_sp_move_rate_rad_s = 0.f);
52 rclcpp::Publisher<px4_msgs::msg::VehicleAttitudeSetpoint>::SharedPtr
53 _vehicle_attitude_setpoint_pub;
Setpoint type for direct attitude control.
Definition: attitude.hpp:23
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:20
Definition: setpoint_base.hpp:20
Definition: setpoint_base.hpp:25