mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-12 11:26:31 +08:00
Reset _transfer_in_progress if mavlink transfer times out. (#5077)
This commit is contained in:
committed by
Lorenz Meier
parent
87e964ec10
commit
b48c081e5c
@@ -346,6 +346,9 @@ MavlinkMissionManager::send(const hrt_abstime now)
|
||||
|
||||
_state = MAVLINK_WPM_STATE_IDLE;
|
||||
|
||||
// since we are giving up, reset this state also, so another request can be started.
|
||||
_transfer_in_progress = false;
|
||||
|
||||
} else if (_state == MAVLINK_WPM_STATE_GETLIST && hrt_elapsed_time(&_time_last_sent) > _retry_timeout) {
|
||||
/* try to request item again after timeout */
|
||||
send_mission_request(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq);
|
||||
|
||||
Reference in New Issue
Block a user