diff --git a/msg/ManualControlSetpoint.msg b/msg/ManualControlSetpoint.msg index 4e4e305fd0..056a4c1b32 100644 --- a/msg/ManualControlSetpoint.msg +++ b/msg/ManualControlSetpoint.msg @@ -35,6 +35,8 @@ float32 aux4 float32 aux5 float32 aux6 +uint16 buttons # A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to button 1 of 16. + bool sticks_moving # TOPICS manual_control_setpoint manual_control_input diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 6030d9b651..dfedefa09a 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -2089,6 +2089,7 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg) // For backwards compatibility at the moment interpret throttle in range [0,1000] manual_control_setpoint.throttle = ((mavlink_manual_control.z / 1000.f) * 2.f) - 1.f; manual_control_setpoint.yaw = mavlink_manual_control.r / 1000.f; + manual_control_setpoint.buttons = mavlink_manual_control.buttons; manual_control_setpoint.data_source = manual_control_setpoint_s::SOURCE_MAVLINK_0 + _mavlink->get_instance_id(); manual_control_setpoint.timestamp = manual_control_setpoint.timestamp_sample = hrt_absolute_time(); manual_control_setpoint.valid = true;