autotest: slow down simulation to avoid receiving re-request of item

# avoid a timeout race condition where ArduPilot re-requests a
        # fence point before we receive and respond to the first one.
        # Since ArduPilot has a 1s timeout on re-requesting, This only
        # requires a round-trip delay of 1/speedup seconds to trigger
        # - and that has been seen in practise on Travis

AT-0417.0: Sending item with seq=0
AT-0417.2: Got (MISSION_REQUEST {target_system : 243, target_component : 250, seq : 0, mission_type : 1})
AT-0417.2: Got (MISSION_REQUEST {target_system : 243, target_component : 250, seq : 0, mission_type : 1})
AT-0417.2: Exception caught: Traceback (most recent call last):
  File "/home/travis/build/ArduPilot/ardupilot/Tools/autotest/common.py", line 3950, in run_one_test
    test_function()
  File "/home/travis/build/ArduPilot/ardupilot/Tools/autotest/rover.py", line 4216, in test_poly_fence
    self.test_fence_upload_timeouts()
  File "/home/travis/build/ArduPilot/ardupilot/Tools/autotest/rover.py", line 4057, in test_fence_upload_timeouts
    target_component=target_component)
  File "/home/travis/build/ArduPilot/ardupilot/Tools/autotest/rover.py", line 4010, in test_fence_upload_timeouts_2
    self.expect_request_for_item(item)
  File "/home/travis/build/ArduPilot/ardupilot/Tools/autotest/rover.py", line 3958, in expect_request_for_item
    raise NotAchievedException("Expected request for seq=%u" % item.seq)
NotAchievedException: Expected request for seq=1

The "AT" timestamps there are wallclock time.  Since speedup for Rover
is 8 by default, that could be as much as 1.6 seconds meaning a
re-request from ArduPilot would be legitimate.

I've added some debug, too - we now emit "Sending item with seq=1"
between those two "Got" lines.  That should make the problem clearer -
we've received a re-request rather than a request for the item after the
one we've already sent.
This commit is contained in:
Peter Barker 2020-08-09 09:49:47 +10:00 committed by Peter Barker
parent 7baafcd63d
commit f0482935cc

View File

@ -3881,6 +3881,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.wait_fence_not_breached()
def test_fence_upload_timeouts_1(self, target_system=1, target_component=1):
self.start_subtest("fence_upload timeouts 1")
self.progress("Telling victim there will be one item coming")
self.mav.mav.mission_count_send(target_system,
target_component,
@ -3942,6 +3943,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
continue
if rerequest_count < 3:
raise NotAchievedException("Expected several re-requests of mission item")
self.end_subtest("fence upload timeouts 1")
def expect_request_for_item(self, item):
m = self.mav.recv_match(type=['MISSION_REQUEST', 'MISSION_ACK'],
@ -3964,7 +3966,15 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
def test_fence_upload_timeouts_2(self, target_system=1, target_component=1):
self.progress("Telling victim there will be one item coming")
self.start_subtest("fence upload timeouts 2")
self.progress("Telling victim there will be two items coming")
# avoid a timeout race condition where ArduPilot re-requests a
# fence point before we receive and respond to the first one.
# Since ArduPilot has a 1s timeout on re-requesting, This only
# requires a round-trip delay of 1/speedup seconds to trigger
# - and that has been seen in practise on Travis
old_speedup = self.get_parameter("SIM_SPEEDUP")
self.set_parameter("SIM_SPEEDUP", 1)
self.mav.mav.mission_count_send(target_system,
target_component,
2,
@ -3990,6 +4000,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
item.pack(self.mav.mav)
self.mav.mav.send(item)
self.progress("Sending item with seq=1")
item = self.mav.mav.mission_item_int_encode(
target_system,
target_component,
@ -4009,6 +4020,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.expect_request_for_item(item)
self.set_parameter("SIM_SPEEDUP", old_speedup)
self.progress("Now waiting for a timeout")
tstart = self.get_sim_time()
rerequest_count = 0
@ -4049,6 +4062,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
continue
if rerequest_count < 3:
raise NotAchievedException("Expected several re-requests of mission item")
self.end_subtest("fence upload timeouts 2")
def test_fence_upload_timeouts(self, target_system=1, target_component=1):
self.test_fence_upload_timeouts_1(target_system=target_system,