PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
rates.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_rates_setpoint.hpp>
9 #include <Eigen/Core>
10 
11 #include <px4_ros2/common/setpoint_base.hpp>
12 
13 namespace px4_ros2
14 {
23 {
24 public:
25  explicit RatesSetpointType(Context & context);
26 
27  ~RatesSetpointType() override = default;
28 
29  Configuration getConfiguration() override;
30  float desiredUpdateRateHz() override {return 200.f;}
31 
32  void update(
33  const Eigen::Vector3f & rate_setpoints_ned_rad,
34  const Eigen::Vector3f & thrust_setpoint_frd);
35 
36 private:
37  rclcpp::Node & _node;
38  rclcpp::Publisher<px4_msgs::msg::VehicleRatesSetpoint>::SharedPtr _vehicle_rates_setpoint_pub;
39 };
40 
42 } /* namespace px4_ros2 */
Definition: context.hpp:20
Setpoint type for direct rate control.
Definition: rates.hpp:23
Definition: setpoint_base.hpp:20
Definition: setpoint_base.hpp:25