mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Tools: fixed bootloader hang on GPS data
don't kill the timeout till we get valid sync and get_device calls. This makes accidental bootloader triggers very unlikely
This commit is contained in:
parent
372d9483aa
commit
5c9b3842e6
@ -942,9 +942,11 @@ bootloader(unsigned timeout)
|
||||
// we got a good command on this port, lock to the port
|
||||
lock_bl_port();
|
||||
|
||||
// we got a command worth syncing, so kill the timeout because
|
||||
// we are probably talking to the uploader
|
||||
// once we get both a valid sync and valid get_device then kill
|
||||
// the timeout
|
||||
if (done_sync && done_get_device) {
|
||||
timeout = 0;
|
||||
}
|
||||
|
||||
// send the sync response for this command
|
||||
sync_response();
|
||||
|
Loading…
Reference in New Issue
Block a user