mirror of https://github.com/ArduPilot/ardupilot
autotest: correct upload/download-mission timeouts
This commit is contained in:
parent
e27b98f47e
commit
aa7987a4fb
|
@ -7328,7 +7328,7 @@ Also, ignores heartbeats not from our target system'''
|
|||
remaining_to_send = set(range(0, len(items)))
|
||||
sent = set()
|
||||
while True:
|
||||
if self.get_sim_time_cached() - tstart > (10 + len(items)/10):
|
||||
if self.get_sim_time_cached() - tstart > (10 + len(items)/10.0):
|
||||
raise NotAchievedException("timeout uploading %s" % str(mission_type))
|
||||
if len(remaining_to_send) == 0:
|
||||
self.progress("All sent")
|
||||
|
@ -7419,7 +7419,7 @@ Also, ignores heartbeats not from our target system'''
|
|||
tstart = self.get_sim_time_cached()
|
||||
remaining_to_receive = set(range(0, m.count))
|
||||
next_to_request = 0
|
||||
timeout = m.count / 10
|
||||
timeout = m.count / 10.0
|
||||
timeout *= self.speedup / 10.0
|
||||
timeout += 10
|
||||
while True:
|
||||
|
|
Loading…
Reference in New Issue