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 <px4_msgs/msg/vehicle_attitude_setpoint.hpp>
9 #include <Eigen/Eigen>
10 
11 #include <px4_ros2/common/setpoint_base.hpp>
12 
13 namespace px4_ros2
14 {
23 {
24 public:
25  explicit AttitudeSetpointType(Context & context);
26 
27  ~AttitudeSetpointType() override = default;
28 
29  Configuration getConfiguration() override;
30  float desiredUpdateRateHz() override {return 100.f;}
31 
32  void update(
33  const Eigen::Quaternionf & attitude_setpoint,
34  const Eigen::Vector3f & thrust_setpoint_frd, float yaw_sp_move_rate_rad_s = 0.f);
35 
46  void update(
47  float roll, float pitch, float yaw,
48  const Eigen::Vector3f & thrust_setpoint_body, float yaw_sp_move_rate_rad_s = 0.f);
49 
50 private:
51  rclcpp::Node & _node;
52  rclcpp::Publisher<px4_msgs::msg::VehicleAttitudeSetpoint>::SharedPtr
53  _vehicle_attitude_setpoint_pub;
54 };
55 
57 } /* namespace px4_ros2 */
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