Tools: autotest: break out a load_fence function

This commit is contained in:
Peter Barker 2019-08-05 14:43:27 +10:00 committed by Peter Barker
parent 6347febc9a
commit 12b9928a56
5 changed files with 31 additions and 27 deletions

View File

@ -484,10 +484,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.context_push() self.context_push()
ex = None ex = None
try: try:
avoid_filepath = os.path.join(self.mission_directory(), self.load_fence("rover-fence-ac-avoid.txt")
"rover-fence-ac-avoid.txt")
self.mavproxy.send("fence load %s\n" % avoid_filepath)
self.mavproxy.expect("Loaded 6 geo-fence")
self.set_parameter("FENCE_ENABLE", 0) self.set_parameter("FENCE_ENABLE", 0)
self.set_parameter("PRX_TYPE", 10) self.set_parameter("PRX_TYPE", 10)
self.set_parameter("RC10_OPTION", 40) # proximity-enable self.set_parameter("RC10_OPTION", 40) # proximity-enable

View File

@ -661,10 +661,7 @@ class AutoTestCopter(AutoTest):
self.progress("home: %s" % str(m)) self.progress("home: %s" % str(m))
self.start_subtest("ensure we can't arm if ouside fence") self.start_subtest("ensure we can't arm if ouside fence")
fence = os.path.join(self.mission_directory(), self.load_fence_using_mavproxy("fence-in-middle-of-nowhere.txt")
"fence-in-middle-of-nowhere.txt")
self.mavproxy.send('fence load %s\n' % fence)
self.mavproxy.expect("Loaded 6 geo-fence")
self.delay_sim_time(5) # let fence check run so it loads-from-eeprom self.delay_sim_time(5) # let fence check run so it loads-from-eeprom
seen_statustext = False seen_statustext = False
seen_command_ack = False seen_command_ack = False
@ -3299,10 +3296,7 @@ class AutoTestCopter(AutoTest):
self.context_push() self.context_push()
ex = None ex = None
try: try:
avoid_filepath = os.path.join(self.mission_directory(), self.load_fence("copter-avoidance-fence.txt")
"copter-avoidance-fence.txt")
self.mavproxy.send("fence load %s\n" % avoid_filepath)
self.mavproxy.expect("Loaded 5 geo-fence")
self.set_parameter("FENCE_ENABLE", 0) self.set_parameter("FENCE_ENABLE", 0)
self.set_parameter("PRX_TYPE", 10) self.set_parameter("PRX_TYPE", 10)
self.set_parameter("RC10_OPTION", 40) # proximity-enable self.set_parameter("RC10_OPTION", 40) # proximity-enable
@ -3324,10 +3318,7 @@ class AutoTestCopter(AutoTest):
self.context_push() self.context_push()
ex = None ex = None
try: try:
avoid_filepath = os.path.join(self.mission_directory(), self.load_fence("copter-avoidance-fence.txt")
"copter-avoidance-fence.txt")
self.mavproxy.send("fence load %s\n" % avoid_filepath)
self.mavproxy.expect("Loaded 5 geo-fence")
self.set_parameter("FENCE_ENABLE", 1) self.set_parameter("FENCE_ENABLE", 1)
self.check_avoidance_corners() self.check_avoidance_corners()
except Exception as e: except Exception as e:

View File

@ -959,10 +959,7 @@ class AutoTestPlane(AutoTest):
try: try:
self.progress("Checking for bizarre healthy-when-not-present-or-enabled") self.progress("Checking for bizarre healthy-when-not-present-or-enabled")
self.assert_fence_sys_status(False, False, True) self.assert_fence_sys_status(False, False, True)
fence_filepath = os.path.join(self.mission_directory(), self.load_fence("CMAC-fence.txt")
"CMAC-fence.txt")
self.mavproxy.send("fence load %s\n" % fence_filepath)
self.mavproxy.expect("Loaded 6 geo-fence")
m = self.mav.recv_match(type='FENCE_STATUS', blocking=True, timeout=2) m = self.mav.recv_match(type='FENCE_STATUS', blocking=True, timeout=2)
if m is not None: if m is not None:
raise NotAchievedException("Got FENCE_STATUS unexpectedly"); raise NotAchievedException("Got FENCE_STATUS unexpectedly");
@ -997,8 +994,7 @@ class AutoTestPlane(AutoTest):
# test a rather unfortunate behaviour: # test a rather unfortunate behaviour:
self.progress("Killing a live fence with fence-clear") self.progress("Killing a live fence with fence-clear")
self.mavproxy.send("fence load %s\n" % fence_filepath) self.load_fence("CMAC-fence.txt")
self.mavproxy.expect("Loaded 6 geo-fence")
self.set_parameter("FENCE_ACTION", mavutil.mavlink.FENCE_ACTION_RTL) self.set_parameter("FENCE_ACTION", mavutil.mavlink.FENCE_ACTION_RTL)
self.do_fence_enable() self.do_fence_enable()
self.assert_fence_sys_status(True, True, True) self.assert_fence_sys_status(True, True, True)
@ -1019,10 +1015,7 @@ class AutoTestPlane(AutoTest):
def test_fence_breach_circle_at(self, loc, disable_on_breach=False): def test_fence_breach_circle_at(self, loc, disable_on_breach=False):
ex = None ex = None
try: try:
fence_filepath = os.path.join(self.mission_directory(), self.load_fence("CMAC-fence.txt")
"CMAC-fence.txt")
self.mavproxy.send("fence load %s\n" % fence_filepath)
self.mavproxy.expect("Loaded 6 geo-fence")
want_radius = 100 want_radius = 100
# when ArduPlane is fixed, remove this fudge factor # when ArduPlane is fixed, remove this fudge factor
REALLY_BAD_FUDGE_FACTOR = 1.16 REALLY_BAD_FUDGE_FACTOR = 1.16

View File

@ -292,6 +292,29 @@ class AutoTest(ABC):
self.reboot_sitl() self.reboot_sitl()
self.fetch_parameters() self.fetch_parameters()
def count_lines_in_filepath(self, filepath):
return len([i for i in open(filepath)])
def load_fence_using_mavproxy(self, filename):
self.set_parameter("FENCE_TOTAL", 0)
filepath = os.path.join(self.mission_directory(), filename)
count = self.count_lines_in_filepath(filepath)
self.mavproxy.send('fence load %s\n' % filepath)
self.mavproxy.expect("Loaded %u geo-fence" % count)
tstart = self.get_sim_time_cached()
while True:
t2 = self.get_sim_time_cached()
if t2 - tstart > 10:
raise AutoTestTimeoutException("Failed to do load")
newcount = self.get_parameter("FENCE_TOTAL")
self.progress("fence total: %u want=%u" % (newcount, count))
if count == newcount:
break
self.delay_sim_time(1)
def load_fence(self, filename):
self.load_fence_using_mavproxy(filename)
def fetch_parameters(self): def fetch_parameters(self):
self.mavproxy.send("param fetch\n") self.mavproxy.send("param fetch\n")
self.mavproxy.expect("Received [0-9]+ parameters") self.mavproxy.expect("Received [0-9]+ parameters")

View File

@ -113,7 +113,7 @@ class AutoTestQuadPlane(AutoTest):
"""Fly a mission from a file.""" """Fly a mission from a file."""
self.progress("Flying mission %s" % filename) self.progress("Flying mission %s" % filename)
self.load_mission(filename) self.load_mission(filename)
self.mavproxy.send('fence load %s\n' % fence) self.load_fence(fence)
self.mavproxy.send('wp list\n') self.mavproxy.send('wp list\n')
self.mavproxy.expect('Requesting [0-9]+ waypoints') self.mavproxy.expect('Requesting [0-9]+ waypoints')
self.wait_ready_to_arm() self.wait_ready_to_arm()