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_attitude_setpoint.hpp>
9 #include <px4_msgs/msg/rover_throttle_setpoint.hpp>
10 #include <px4_ros2/common/setpoint_base.hpp>
11 
12 namespace px4_ros2 {
21  public:
22  explicit RoverThrottleAttitudeSetpointType(Context& context);
23 
24  ~RoverThrottleAttitudeSetpointType() override = default;
25 
26  Configuration getConfiguration() override;
27  float desiredUpdateRateHz() override { return 30.f; }
28 
38  void update(float throttle_body_x, float yaw_setpoint, std::optional<float> throttle_body_y = {});
39 
40  private:
41  rclcpp::Node& _node;
42  rclcpp::Publisher<px4_msgs::msg::RoverThrottleSetpoint>::SharedPtr _rover_throttle_setpoint_pub;
43  rclcpp::Publisher<px4_msgs::msg::RoverAttitudeSetpoint>::SharedPtr _rover_attitude_setpoint_pub;
44 };
45 
47 } /* namespace px4_ros2 */
Definition: context.hpp:18
Setpoint type for rover throttle and attitude control.
Definition: throttle_attitude.hpp:20
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:19
Definition: setpoint_base.hpp:23