PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
Loading...
Searching...
No Matches
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 <px4_ros2/common/context.hpp>
10#include <rclcpp/rclcpp.hpp>
11
12using namespace std::chrono_literals; // NOLINT
13
14namespace px4_ros2 {
23 public:
24 explicit ManualControlInput(Context& context, bool is_optional = false);
25
29 float roll() const { return _manual_control_setpoint.roll; }
33 float pitch() const { return _manual_control_setpoint.pitch; }
37 float yaw() const { return _manual_control_setpoint.yaw; }
42 float throttle() const { return _manual_control_setpoint.throttle; }
43
44 float aux1() const { return _manual_control_setpoint.aux1; }
45 float aux2() const { return _manual_control_setpoint.aux2; }
46 float aux3() const { return _manual_control_setpoint.aux3; }
47 float aux4() const { return _manual_control_setpoint.aux4; }
48 float aux5() const { return _manual_control_setpoint.aux5; }
49 float aux6() const { return _manual_control_setpoint.aux6; }
50
51 bool isValid() const
52 {
53 return _manual_control_setpoint.valid &&
54 _node.get_clock()->now() - _last_manual_control_setpoint < 500ms;
55 }
56
57 private:
58 rclcpp::Subscription<px4_msgs::msg::ManualControlSetpoint>::SharedPtr
59 _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:18
Provides access to manually input control setpoints.
Definition manual_control_input.hpp:22
float yaw() const
Definition manual_control_input.hpp:37
float roll() const
Definition manual_control_input.hpp:29
float pitch() const
Definition manual_control_input.hpp:33
float throttle() const
Definition manual_control_input.hpp:42