autotest: drain self.mav while waiting on other link
In the short period of time it takes for us to get organised/draining mavlink connections, the ArduPilot process might block writing to the primary mavlink connection - in which case we'll never get the message we requested. Should solve 2022-08-31T23:17:43.6904119Z AT-0227.6: waiting for a message - any message.... 2022-08-31T23:17:43.6904958Z AT-0227.6: Received (ATTITUDE {time_boot_ms : 3146, roll : 0.00013471684360411018, pitch : -4.076504410477355e-05, yaw : -2.1274349689483643, rollspeed : 6.679168291157112e-05, pitchspeed : 3.297374496469274e-05, yawspeed : 9.125166684498254e-07}) 2022-08-31T23:17:43.6905505Z AT-0227.6: Waiting for mission count of (3) from (1:1) to (243:250) 2022-08-31T23:17:43.6905909Z AT-0227.6: Asserted mission count (type=2) is 3 after 0.100000s 2022-08-31T23:17:43.6906252Z AT-0227.6: Get first item on new link 2022-08-31T23:17:43.6906620Z AT-0289.2: Received exception (Did not receive MISSION_ITEM_INT 2022-08-31T23:17:43.6907047Z Traceback (most recent call last): 2022-08-31T23:17:43.6907386Z File "/__w/ardupilot/ardupilot/Tools/autotest/rover.py", line 3067, in test_rally 2022-08-31T23:17:43.6907719Z m2 = self.get_mission_item_int_on_link( 2022-08-31T23:17:43.6908080Z File "/__w/ardupilot/ardupilot/Tools/autotest/rover.py", line 2288, in get_mission_item_int_on_link 2022-08-31T23:17:43.6908469Z raise NotAchievedException("Did not receive MISSION_ITEM_INT") 2022-08-31T23:17:43.6908841Z common.NotAchievedException: Did not receive MISSION_ITEM_INT 2022-08-31T23:17:43.6909118Z ) 2022-08-31T23:17:43.6909468Z AT-0289.2: Exception caught: Did not receive MISSION_ITEM_INT
This commit is contained in:
parent
9ec13be880
commit
8777d68ac1
@ -3858,15 +3858,26 @@ class AutoTest(ABC):
|
||||
if self.get_sim_time_cached() - tstart > timeout:
|
||||
return
|
||||
|
||||
def assert_receive_message(self, type, timeout=1, verbose=False, very_verbose=False, mav=None):
|
||||
def assert_receive_message(self,
|
||||
type,
|
||||
timeout=1,
|
||||
verbose=False,
|
||||
very_verbose=False,
|
||||
mav=None,
|
||||
condition=None,
|
||||
delay_fn=None):
|
||||
if mav is None:
|
||||
mav = self.mav
|
||||
m = None
|
||||
tstart = time.time() # timeout in wallclock
|
||||
while m is None:
|
||||
m = mav.recv_match(type=type, blocking=True, timeout=0.05)
|
||||
while True:
|
||||
m = mav.recv_match(type=type, blocking=True, timeout=0.05, condition=condition)
|
||||
if m is not None:
|
||||
break
|
||||
if time.time() - tstart > timeout:
|
||||
raise NotAchievedException("Did not get %s" % type)
|
||||
if delay_fn is not None:
|
||||
delay_fn()
|
||||
if verbose:
|
||||
self.progress("Received (%s)" % str(m))
|
||||
if very_verbose:
|
||||
|
@ -2296,16 +2296,17 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
self.progress("Asserted mission count (type=%u) is %u after %fs" % (
|
||||
(mission_type, m.count, delta)))
|
||||
|
||||
def get_mission_item_int_on_link(self, item, mav, target_system, target_component, mission_type):
|
||||
def get_mission_item_int_on_link(self, item, mav, target_system, target_component, mission_type, delay_fn=None):
|
||||
self.drain_mav(mav=mav, unparsed=True)
|
||||
mav.mav.mission_request_int_send(target_system,
|
||||
target_component,
|
||||
item,
|
||||
mission_type)
|
||||
m = mav.recv_match(type='MISSION_ITEM_INT',
|
||||
blocking=True,
|
||||
timeout=60,
|
||||
condition='MISSION_ITEM_INT.mission_type==%u' % mission_type)
|
||||
m = self.assert_receive_message(
|
||||
'MISSION_ITEM_INT',
|
||||
timeout=60,
|
||||
condition='MISSION_ITEM_INT.mission_type==%u' % mission_type,
|
||||
delay_fn=delay_fn)
|
||||
if m is None:
|
||||
raise NotAchievedException("Did not receive MISSION_ITEM_INT")
|
||||
if m.mission_type != mission_type:
|
||||
@ -3086,12 +3087,16 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
target_component,
|
||||
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
|
||||
self.progress("Get first item on new link")
|
||||
|
||||
def drain_self_mav_fn():
|
||||
self.drain_mav(self.mav)
|
||||
m2 = self.get_mission_item_int_on_link(
|
||||
2,
|
||||
mav2,
|
||||
target_system,
|
||||
target_component,
|
||||
mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
|
||||
mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
|
||||
delay_fn=drain_self_mav_fn)
|
||||
self.progress("Get first item on original link")
|
||||
m = self.get_mission_item_int_on_link(
|
||||
2,
|
||||
|
Loading…
Reference in New Issue
Block a user