8 #include <px4_msgs/msg/manual_control_setpoint.hpp>
9 #include <rclcpp/rclcpp.hpp>
10 #include <px4_ros2/common/context.hpp>
12 using namespace std::chrono_literals;
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;}
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;}
54 return _manual_control_setpoint.valid &&
55 _node.get_clock()->now() - _last_manual_control_setpoint < 500ms;
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{};
Definition: context.hpp:20