mirror of https://github.com/ArduPilot/ardupilot
autotest: increase debug when retrying parameter download
This commit is contained in:
parent
7b64263562
commit
a6769e003a
|
@ -12313,6 +12313,7 @@ switch value'''
|
|||
expected_count = 0
|
||||
seen_ids = {}
|
||||
self.progress("Downloading parameters")
|
||||
debug = False
|
||||
while True:
|
||||
now = self.get_sim_time_cached()
|
||||
if not start_done or now - last_parameter_received > 10:
|
||||
|
@ -12323,6 +12324,7 @@ switch value'''
|
|||
elif attempt_count != 0:
|
||||
self.progress("Download failed; retrying")
|
||||
self.delay_sim_time(1)
|
||||
debug = True
|
||||
self.drain_mav()
|
||||
self.mav.mav.param_request_list_send(target_system, target_component)
|
||||
attempt_count += 1
|
||||
|
@ -12337,8 +12339,8 @@ switch value'''
|
|||
if m.param_index == 65535:
|
||||
self.progress("volunteered parameter: %s" % str(m))
|
||||
continue
|
||||
if False:
|
||||
self.progress(" received (%4u/%4u %s=%f" %
|
||||
if debug:
|
||||
self.progress(" received id=%4u param_count=%4u %s=%f" %
|
||||
(m.param_index, m.param_count, m.param_id, m.param_value))
|
||||
if m.param_index >= m.param_count:
|
||||
raise ValueError("parameter index (%u) gte parameter count (%u)" %
|
||||
|
|
Loading…
Reference in New Issue