Skip to content

Commit a6769e0

Browse files
committed
autotest: increase debug when retrying parameter download
1 parent 7b64263 commit a6769e0

1 file changed

Lines changed: 4 additions & 2 deletions

File tree

Tools/autotest/vehicle_test_suite.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -12313,6 +12313,7 @@ def download_parameters(self, target_system, target_component):
1231312313
expected_count = 0
1231412314
seen_ids = {}
1231512315
self.progress("Downloading parameters")
12316+
debug = False
1231612317
while True:
1231712318
now = self.get_sim_time_cached()
1231812319
if not start_done or now - last_parameter_received > 10:
@@ -12323,6 +12324,7 @@ def download_parameters(self, target_system, target_component):
1232312324
elif attempt_count != 0:
1232412325
self.progress("Download failed; retrying")
1232512326
self.delay_sim_time(1)
12327+
debug = True
1232612328
self.drain_mav()
1232712329
self.mav.mav.param_request_list_send(target_system, target_component)
1232812330
attempt_count += 1
@@ -12337,8 +12339,8 @@ def download_parameters(self, target_system, target_component):
1233712339
if m.param_index == 65535:
1233812340
self.progress("volunteered parameter: %s" % str(m))
1233912341
continue
12340-
if False:
12341-
self.progress(" received (%4u/%4u %s=%f" %
12342+
if debug:
12343+
self.progress(" received id=%4u param_count=%4u %s=%f" %
1234212344
(m.param_index, m.param_count, m.param_id, m.param_value))
1234312345
if m.param_index >= m.param_count:
1234412346
raise ValueError("parameter index (%u) gte parameter count (%u)" %

0 commit comments

Comments
 (0)