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 <Eigen/Core>
9 #include <px4_msgs/msg/vehicle_rates_setpoint.hpp>
10 #include <px4_ros2/common/setpoint_base.hpp>
11 
12 namespace px4_ros2 {
21  public:
22  explicit RatesSetpointType(Context& context);
23 
24  ~RatesSetpointType() override = default;
25 
26  Configuration getConfiguration() override;
27  float desiredUpdateRateHz() override { return 200.f; }
28 
29  void update(const Eigen::Vector3f& rate_setpoints_frd_rad,
30  const Eigen::Vector3f& thrust_setpoint_frd);
31 
32  private:
33  rclcpp::Node& _node;
34  rclcpp::Publisher<px4_msgs::msg::VehicleRatesSetpoint>::SharedPtr _vehicle_rates_setpoint_pub;
35 };
36 
38 } /* namespace px4_ros2 */
Definition: context.hpp:18
Setpoint type for direct rate control.
Definition: rates.hpp:20
Definition: setpoint_base.hpp:19
Definition: setpoint_base.hpp:23