forked from Archive/PX4-Autopilot
Preserve gimbal control when receiving updates from an input that is not active
The update function of InputMavlinkGimbalV2 returns UpdatedNotActive when receiving control commands from a system or component that doesn't match the primary control. This can happen if a component just sends commands without being in control or when transitioning to a different primary control. If the input is marked as already_active, it will reset last_input_active which in turn resets the primary control in the next iteration. According to the MAVLink gimbal protocol v2, a component needs to send MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE to start controlling the gimbal and to remove control. However, with the current implementation there are several other commands that would reset the primary control. With this PR, the primary control remains with the component that requested it last if updates from a not active component are received.
This commit is contained in:
parent
2586900c26
commit
19bca47b9e
|
@ -250,11 +250,7 @@ static int gimbal_thread_main(int argc, char *argv[])
|
|||
break;
|
||||
|
||||
case InputBase::UpdateResult::UpdatedNotActive:
|
||||
if (already_active) {
|
||||
// No longer active
|
||||
thread_data.last_input_active = -1;
|
||||
}
|
||||
|
||||
// Ignore, input not active
|
||||
break;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue