mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-21 21:06:16 +08:00
Send mavlink manual control buttons field in manual control input topic (#22988)
Pass along button states from manual control mavlink message in new buttons field in manual control input topic
This commit is contained in:
@@ -125,7 +125,7 @@ void elrs_led_task()
|
||||
|
||||
orb_copy(ORB_ID(manual_control_input), manual_control_input_fd, &setpoint_req);
|
||||
|
||||
_cmd = (ControllerInput)setpoint_req.aux1;
|
||||
_cmd = (ControllerInput)setpoint_req.buttons;
|
||||
|
||||
// skip duplicate cmds
|
||||
if (_cmd == _prev_cmd) {
|
||||
|
||||
@@ -37,6 +37,8 @@ float32 aux6
|
||||
|
||||
bool sticks_moving
|
||||
|
||||
uint16 buttons # From uint16 buttons field of Mavlink manual_control message
|
||||
|
||||
# TOPICS manual_control_setpoint manual_control_input
|
||||
# DEPRECATED: float32 x
|
||||
# DEPRECATED: float32 y
|
||||
|
||||
@@ -2089,6 +2089,8 @@ 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;
|
||||
// Pass along the button states
|
||||
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;
|
||||
|
||||
Reference in New Issue
Block a user