mirror of https://github.com/ArduPilot/ardupilot
autotest: remove un-needed calls to drain_mav_unparsed
these calls are generally bad now, given we have context_collect things going on which always want to see messages coming in
This commit is contained in:
parent
a8357531d1
commit
515b79a6ca
|
@ -4778,7 +4778,6 @@ class AutoTestCopter(AutoTest):
|
|||
raise e
|
||||
|
||||
self.progress("Testing mount ROI behaviour")
|
||||
self.drain_mav_unparsed()
|
||||
self.test_mount_pitch(0, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING)
|
||||
start = self.mav.location()
|
||||
self.progress("start=%s" % str(start))
|
||||
|
@ -6703,7 +6702,6 @@ class AutoTestCopter(AutoTest):
|
|||
self.wait_statustext("requested state is not RUN", timeout=60)
|
||||
|
||||
self.set_message_rate_hz("GENERATOR_STATUS", 10)
|
||||
self.drain_mav_unparsed()
|
||||
|
||||
self.wait_generator_speed_and_state(0, 0, mavutil.mavlink.MAV_GENERATOR_STATUS_FLAG_OFF)
|
||||
|
||||
|
|
|
@ -990,8 +990,8 @@ class AutoTestPlane(AutoTest):
|
|||
raise NotAchievedException("Did not go via circle mode")
|
||||
self.progress("Ensure we've had our throttle squashed to 950")
|
||||
self.wait_rc_channel_value(3, 950)
|
||||
self.drain_mav_unparsed()
|
||||
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
|
||||
self.do_timesync_roundtrip()
|
||||
m = self.assert_receive_message('SYS_STATUS')
|
||||
self.progress("Got (%s)" % str(m))
|
||||
self.progress("Testing receiver enabled")
|
||||
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
|
||||
|
@ -1004,10 +1004,10 @@ class AutoTestPlane(AutoTest):
|
|||
# if (m.onboard_control_sensors_health & receiver_bit):
|
||||
# raise NotAchievedException("Sensor healthy when it shouldn't be")
|
||||
self.set_parameter("SIM_RC_FAIL", 0)
|
||||
self.drain_mav_unparsed()
|
||||
# have to allow time for RC to be fetched from SITL
|
||||
self.delay_sim_time(0.5)
|
||||
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
|
||||
self.do_timesync_roundtrip()
|
||||
m = self.assert_receive_message('SYS_STATUS')
|
||||
self.progress("Testing receiver enabled")
|
||||
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
|
||||
raise NotAchievedException("Receiver not enabled")
|
||||
|
@ -1026,8 +1026,8 @@ class AutoTestPlane(AutoTest):
|
|||
if (not self.get_mode_from_mode_mapping("CIRCLE") in
|
||||
[x.custom_mode for x in self.context_stop_collecting("HEARTBEAT")]):
|
||||
raise NotAchievedException("Did not go via circle mode")
|
||||
self.drain_mav_unparsed()
|
||||
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
|
||||
self.do_timesync_roundtrip()
|
||||
m = self.assert_receive_message('SYS_STATUS')
|
||||
self.progress("Got (%s)" % str(m))
|
||||
self.progress("Testing receiver enabled")
|
||||
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
|
||||
|
@ -1043,8 +1043,8 @@ class AutoTestPlane(AutoTest):
|
|||
# have to allow time for RC to be fetched from SITL
|
||||
self.progress("Giving receiver time to recover")
|
||||
self.delay_sim_time(0.5)
|
||||
self.drain_mav_unparsed()
|
||||
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
|
||||
self.do_timesync_roundtrip()
|
||||
m = self.assert_receive_message('SYS_STATUS')
|
||||
self.progress("Testing receiver enabled")
|
||||
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
|
||||
raise NotAchievedException("Receiver not enabled")
|
||||
|
@ -1146,12 +1146,11 @@ class AutoTestPlane(AutoTest):
|
|||
self.set_parameter("SIM_RC_FAIL", 2) # throttle-to-950
|
||||
self.wait_mode("CIRCLE")
|
||||
self.delay_sim_time(1) # give
|
||||
self.drain_mav_unparsed()
|
||||
self.do_timesync_roundtrip()
|
||||
|
||||
self.progress("Checking fence is OK after receiver failure (bind-values)")
|
||||
fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
|
||||
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
|
||||
self.progress("Got (%s)" % str(m))
|
||||
m = self.assert_receive_message('SYS_STATUS')
|
||||
if (not (m.onboard_control_sensors_enabled & fence_bit)):
|
||||
raise NotAchievedException("Fence not enabled after RC fail")
|
||||
self.do_fence_disable() # Ensure the fence is disabled after test
|
||||
|
@ -1178,7 +1177,7 @@ class AutoTestPlane(AutoTest):
|
|||
|
||||
def assert_fence_sys_status(self, present, enabled, health):
|
||||
self.delay_sim_time(1)
|
||||
self.drain_mav_unparsed()
|
||||
self.do_timesync_roundtrip()
|
||||
m = self.assert_receive_message('SYS_STATUS', timeout=1)
|
||||
tests = [
|
||||
("present", present, m.onboard_control_sensors_present),
|
||||
|
@ -1246,7 +1245,6 @@ class AutoTestPlane(AutoTest):
|
|||
m = self.mav.recv_match(type='FENCE_STATUS', blocking=True, timeout=2)
|
||||
if m is not None:
|
||||
raise NotAchievedException("Got FENCE_STATUS unexpectedly")
|
||||
self.drain_mav_unparsed()
|
||||
self.set_parameter("FENCE_ACTION", 0) # report only
|
||||
self.assert_fence_sys_status(True, False, True)
|
||||
self.set_parameter("FENCE_ACTION", 1) # RTL
|
||||
|
|
|
@ -2752,6 +2752,9 @@ class AutoTest(ABC):
|
|||
self.get_sim_time()
|
||||
|
||||
def drain_mav(self, mav=None, unparsed=False, quiet=True):
|
||||
'''parse all data available on connection mav (defaulting to
|
||||
self.mav). It is assumed that mav is connected to the normal
|
||||
simulation'''
|
||||
if unparsed:
|
||||
return self.drain_mav_unparsed(quiet=quiet, mav=mav)
|
||||
if mav is None:
|
||||
|
@ -3995,7 +3998,7 @@ class AutoTest(ABC):
|
|||
# the following hack is to get around MAVProxy statustext deduping:
|
||||
while time.time() - self.last_wp_load < 3:
|
||||
self.progress("Waiting for MAVProxy de-dupe timer to expire")
|
||||
self.drain_mav_unparsed()
|
||||
self.drain_mav()
|
||||
time.sleep(0.1)
|
||||
mavproxy.send('wp load %s\n' % path)
|
||||
mavproxy.expect('Loaded ([0-9]+) waypoints from')
|
||||
|
@ -4508,7 +4511,6 @@ class AutoTest(ABC):
|
|||
def disarm_vehicle(self, timeout=60, force=False):
|
||||
"""Disarm vehicle with mavlink disarm message."""
|
||||
self.progress("Disarm motors with MAVLink cmd")
|
||||
self.drain_mav_unparsed()
|
||||
p2 = 0
|
||||
if force:
|
||||
p2 = 21196 # magic force disarm value
|
||||
|
@ -10433,7 +10435,7 @@ switch value'''
|
|||
"--uartE=tcp:6735", # GPS2 is NMEA....
|
||||
"--uartF=tcpclient:127.0.0.1:6735", # serial5 spews to localhost:6735
|
||||
])
|
||||
self.drain_mav_unparsed()
|
||||
self.do_timesync_roundtrip()
|
||||
self.wait_gps_fix_type_gte(3)
|
||||
gps1 = self.mav.recv_match(type="GPS_RAW_INT", blocking=True, timeout=10)
|
||||
self.progress("gps1=(%s)" % str(gps1))
|
||||
|
@ -11113,7 +11115,7 @@ switch value'''
|
|||
self.wait_ready_to_arm()
|
||||
|
||||
# we need to start the engine to get some RPM readings, we do it for plane only
|
||||
self.drain_mav_unparsed()
|
||||
self.drain_mav()
|
||||
# anything with a lambda in here needs a proper test written.
|
||||
# This, at least makes sure we're getting some of each
|
||||
# message. These are ordered according to the wfq scheduler
|
||||
|
@ -11547,7 +11549,7 @@ switch value'''
|
|||
|
||||
self.assert_current_onboard_log_contains_message("RPM")
|
||||
|
||||
self.drain_mav_unparsed()
|
||||
self.drain_mav()
|
||||
# anything with a lambda in here needs a proper test written.
|
||||
# This, at least makes sure we're getting some of each
|
||||
# message.
|
||||
|
@ -11607,7 +11609,6 @@ switch value'''
|
|||
])
|
||||
frsky = FRSkyD(("127.0.0.1", 6735))
|
||||
self.wait_ready_to_arm()
|
||||
self.drain_mav_unparsed()
|
||||
m = self.assert_receive_message('GLOBAL_POSITION_INT', timeout=1)
|
||||
gpi_abs_alt = int((m.alt+500) / 1000) # mm -> m
|
||||
|
||||
|
@ -11649,8 +11650,7 @@ switch value'''
|
|||
|
||||
if have_alt and have_battery:
|
||||
break
|
||||
|
||||
self.drain_mav_unparsed()
|
||||
self.drain_mav()
|
||||
|
||||
def test_ltm_g(self, ltm):
|
||||
g = ltm.g()
|
||||
|
@ -11730,7 +11730,6 @@ switch value'''
|
|||
])
|
||||
ltm = LTM(("127.0.0.1", 6735))
|
||||
self.wait_ready_to_arm()
|
||||
self.drain_mav_unparsed()
|
||||
|
||||
wants = {
|
||||
"g": self.test_ltm_g,
|
||||
|
@ -11738,7 +11737,7 @@ switch value'''
|
|||
"s": self.test_ltm_s,
|
||||
}
|
||||
|
||||
tstart = self.get_sim_time_cached()
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
self.progress("Still wanting (%s)" %
|
||||
",".join([("%s" % x) for x in wants.keys()]))
|
||||
|
@ -11772,7 +11771,6 @@ switch value'''
|
|||
])
|
||||
devo = DEVO(("127.0.0.1", 6735))
|
||||
self.wait_ready_to_arm()
|
||||
self.drain_mav_unparsed()
|
||||
m = self.assert_receive_message('GLOBAL_POSITION_INT', timeout=1)
|
||||
|
||||
tstart = self.get_sim_time_cached()
|
||||
|
@ -11844,15 +11842,13 @@ switch value'''
|
|||
])
|
||||
msp = MSP_DJI(("127.0.0.1", 6735))
|
||||
self.wait_ready_to_arm()
|
||||
self.drain_mav_unparsed()
|
||||
|
||||
tstart = self.get_sim_time_cached()
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
self.drain_mav()
|
||||
if self.get_sim_time_cached() - tstart > 10:
|
||||
raise NotAchievedException("Did not get location")
|
||||
msp.update()
|
||||
self.drain_mav_unparsed(quiet=True)
|
||||
try:
|
||||
f = msp.get_frame(msp.FRAME_GPS_RAW)
|
||||
except KeyError:
|
||||
|
|
|
@ -2391,7 +2391,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
|
||||
def click_three_in(self, mavproxy, target_system=1, target_component=1):
|
||||
mavproxy.send('rally clear\n')
|
||||
self.drain_mav_unparsed()
|
||||
self.drain_mav()
|
||||
# there are race conditions in MAVProxy. Beware.
|
||||
mavproxy.send("click 1.0 1.0\n")
|
||||
mavproxy.send("rally add\n")
|
||||
|
@ -2427,7 +2427,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
lat = float(lat_s)
|
||||
lng = float(lng_s)
|
||||
mavproxy.send('click %s %s\n' % (lat_s, lng_s))
|
||||
self.drain_mav_unparsed()
|
||||
self.drain_mav()
|
||||
mavproxy.send('rally add\n')
|
||||
self.assert_receive_mission_ack(mavutil.mavlink.MAV_MISSION_TYPE_RALLY,
|
||||
target_system=255,
|
||||
|
@ -2634,9 +2634,9 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
self.end_subsubtest("rally move")
|
||||
|
||||
self.start_subsubtest("rally movemulti")
|
||||
self.drain_mav_unparsed()
|
||||
self.drain_mav()
|
||||
mavproxy.send('rally clear\n')
|
||||
self.drain_mav_unparsed()
|
||||
self.drain_mav()
|
||||
# there are race conditions in MAVProxy. Beware.
|
||||
mavproxy.send("click 1.0 1.0\n")
|
||||
mavproxy.send("rally add\n")
|
||||
|
@ -2662,7 +2662,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
# MAVProxy currently sends three separate items up. That's
|
||||
# not great and I don't want to lock that behaviour in here.
|
||||
self.delay_sim_time(10)
|
||||
self.drain_mav_unparsed()
|
||||
expected_moved_items = copy.copy(unmoved_items)
|
||||
expected_moved_items[0].x = 1.0 * 1e7
|
||||
expected_moved_items[0].y = 2.0 * 1e7
|
||||
|
@ -2681,7 +2680,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
# MAVProxy currently sends three separate items up. That's
|
||||
# not great and I don't want to lock that behaviour in here.
|
||||
self.delay_sim_time(10)
|
||||
self.drain_mav_unparsed()
|
||||
expected_moved_items = copy.copy(unmoved_items)
|
||||
expected_moved_items[0].x = 3.0 * 1e7
|
||||
expected_moved_items[0].y = 1.0 * 1e7
|
||||
|
@ -2722,7 +2720,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
self.progress("Removing first in list")
|
||||
mavproxy.send("rally remove 1\n")
|
||||
self.delay_sim_time(5)
|
||||
self.drain_mav_unparsed()
|
||||
self.assert_mission_count_on_link(
|
||||
self.mav,
|
||||
1,
|
||||
|
@ -2739,7 +2736,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
self.progress("Removing remaining item")
|
||||
mavproxy.send("rally remove 1\n")
|
||||
self.delay_sim_time(5)
|
||||
self.drain_mav_unparsed()
|
||||
self.assert_mission_count_on_link(
|
||||
self.mav,
|
||||
0,
|
||||
|
@ -2781,7 +2777,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
self.progress("Removing first in list")
|
||||
mavproxy.send("rally remove 1\n")
|
||||
self.delay_sim_time(5)
|
||||
self.drain_mav_unparsed()
|
||||
self.assert_mission_count_on_link(
|
||||
self.mav,
|
||||
2,
|
||||
|
@ -2801,10 +2796,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
mavproxy.send("rally move 1\n")
|
||||
# move has already been tested, assume it works...
|
||||
self.delay_sim_time(5)
|
||||
self.drain_mav_unparsed()
|
||||
mavproxy.send("rally undo\n")
|
||||
self.delay_sim_time(5)
|
||||
self.drain_mav_unparsed()
|
||||
undone_items = self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_RALLY)
|
||||
self.check_rally_items_same(pure_items, undone_items)
|
||||
|
||||
|
@ -3446,7 +3439,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
self.delay_sim_time(1)
|
||||
if self.get_parameter("MIS_TOTAL") != 0:
|
||||
raise NotAchievedException("Failed to clear mission")
|
||||
self.drain_mav_unparsed()
|
||||
m = self.assert_receive_message('MISSION_CURRENT', timeout=5)
|
||||
if m.seq != 0:
|
||||
raise NotAchievedException("Bad mission current")
|
||||
|
|
Loading…
Reference in New Issue