PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
throttle_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/rover_throttle_setpoint.hpp>
9 #include <px4_msgs/msg/rover_attitude_setpoint.hpp>
10 
11 #include <px4_ros2/common/setpoint_base.hpp>
12 
13 namespace px4_ros2
14 {
23 {
24 public:
25  explicit RoverThrottleAttitudeSetpointType(Context & context);
26 
27  ~RoverThrottleAttitudeSetpointType() override = default;
28 
29  Configuration getConfiguration() override;
30  float desiredUpdateRateHz() override {return 30.f;}
31 
39  void update(float throttle_body_x, float yaw_setpoint, std::optional<float> throttle_body_y = {});
40 
41 private:
42  rclcpp::Node & _node;
43  rclcpp::Publisher<px4_msgs::msg::RoverThrottleSetpoint>::SharedPtr
44  _rover_throttle_setpoint_pub;
45  rclcpp::Publisher<px4_msgs::msg::RoverAttitudeSetpoint>::SharedPtr
46  _rover_attitude_setpoint_pub;
47 };
48 
50 } /* namespace px4_ros2 */
Definition: context.hpp:20
Setpoint type for rover throttle and attitude control.
Definition: throttle_attitude.hpp:23
void update(float throttle_body_x, float yaw_setpoint, std::optional< float > throttle_body_y={})
Send a rover throttle setpoint and a rover attitude setpoint to the flight controller.
Definition: setpoint_base.hpp:20
Definition: setpoint_base.hpp:25