PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
attitude.hpp
1 /****************************************************************************
2  * Copyright (c) 2023 PX4 Development Team.
3  * SPDX-License-Identifier: BSD-3-Clause
4  ****************************************************************************/
5 
6 #pragma once
7 
8 #include <Eigen/Eigen>
9 #include <px4_msgs/msg/vehicle_attitude_setpoint.hpp>
10 #include <px4_ros2/common/setpoint_base.hpp>
11 
12 namespace px4_ros2 {
21  public:
22  explicit AttitudeSetpointType(Context& context);
23 
24  ~AttitudeSetpointType() override = default;
25 
26  Configuration getConfiguration() override;
27  float desiredUpdateRateHz() override { return 100.f; }
28 
29  void update(const Eigen::Quaternionf& attitude_setpoint,
30  const Eigen::Vector3f& thrust_setpoint_frd, float yaw_sp_move_rate_rad_s = 0.f);
31 
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);
44 
45  private:
46  rclcpp::Node& _node;
47  rclcpp::Publisher<px4_msgs::msg::VehicleAttitudeSetpoint>::SharedPtr
48  _vehicle_attitude_setpoint_pub;
49 };
50 
52 } /* namespace px4_ros2 */
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