PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
manual_control_input.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/manual_control_setpoint.hpp>
9 #include <rclcpp/rclcpp.hpp>
10 #include <px4_ros2/common/context.hpp>
11 
12 using namespace std::chrono_literals; // NOLINT
13 
14 namespace px4_ros2
15 {
24 {
25 public:
26  explicit ManualControlInput(Context & context, bool is_optional = false);
27 
31  float roll() const {return _manual_control_setpoint.roll;}
35  float pitch() const {return _manual_control_setpoint.pitch;}
39  float yaw() const {return _manual_control_setpoint.yaw;}
43  float throttle() const {return _manual_control_setpoint.throttle;}
44 
45  float aux1() const {return _manual_control_setpoint.aux1;}
46  float aux2() const {return _manual_control_setpoint.aux2;}
47  float aux3() const {return _manual_control_setpoint.aux3;}
48  float aux4() const {return _manual_control_setpoint.aux4;}
49  float aux5() const {return _manual_control_setpoint.aux5;}
50  float aux6() const {return _manual_control_setpoint.aux6;}
51 
52  bool isValid() const
53  {
54  return _manual_control_setpoint.valid &&
55  _node.get_clock()->now() - _last_manual_control_setpoint < 500ms;
56  }
57 
58 private:
59  rclcpp::Subscription<px4_msgs::msg::ManualControlSetpoint>::SharedPtr _manual_control_setpoint_sub;
60  px4_msgs::msg::ManualControlSetpoint _manual_control_setpoint{};
61  rclcpp::Time _last_manual_control_setpoint{};
62  rclcpp::Node & _node;
63 };
64 
66 } /* namespace px4_ros2 */
Definition: context.hpp:20
Provides access to manually input control setpoints.
Definition: manual_control_input.hpp:24
float yaw() const
Definition: manual_control_input.hpp:39
float roll() const
Definition: manual_control_input.hpp:31
float pitch() const
Definition: manual_control_input.hpp:35
float throttle() const
Definition: manual_control_input.hpp:43