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; }
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; }
53 return _manual_control_setpoint.valid &&
54 _node.get_clock()->now() - _last_manual_control_setpoint < 500ms;
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{};
Definition context.hpp:18