autotest: tidy fence handling
This commit is contained in:
parent
03bb3237ef
commit
cc83562add
@ -1216,7 +1216,8 @@ class AutoTestCopter(AutoTest):
|
||||
self.progress("home: %s" % str(m))
|
||||
|
||||
self.start_subtest("ensure we can't arm if ouside fence")
|
||||
self.load_fence_using_mavproxy("fence-in-middle-of-nowhere.txt")
|
||||
self.load_fence("fence-in-middle-of-nowhere.txt")
|
||||
|
||||
self.delay_sim_time(5) # let fence check run so it loads-from-eeprom
|
||||
self.assert_prearm_failure("vehicle outside fence")
|
||||
self.progress("Failed to arm outside fence (good!)")
|
||||
@ -1262,7 +1263,7 @@ class AutoTestCopter(AutoTest):
|
||||
tstart = self.get_sim_time()
|
||||
while not self.mode_is("RTL"):
|
||||
if self.get_sim_time_cached() - tstart > 30:
|
||||
self.NotAchievedException("Did not breach fence")
|
||||
raise NotAchievedException("Did not breach fence")
|
||||
|
||||
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
|
||||
alt = m.relative_alt / 1000.0 # mm -> m
|
||||
@ -1312,16 +1313,16 @@ class AutoTestCopter(AutoTest):
|
||||
self.change_alt(10)
|
||||
|
||||
# first east
|
||||
self.progress("turn east")
|
||||
self.progress("turning east")
|
||||
self.set_rc(4, 1580)
|
||||
self.wait_heading(160)
|
||||
self.set_rc(4, 1500)
|
||||
|
||||
# fly forward (east) at least 20m
|
||||
self.progress("flying east 20m")
|
||||
self.set_rc(2, 1100)
|
||||
self.wait_distance(20)
|
||||
|
||||
# stop flying forward and start flying up:
|
||||
self.progress("flying up")
|
||||
self.set_rc_from_map({
|
||||
2: 1500,
|
||||
3: 1800,
|
||||
@ -5042,7 +5043,7 @@ class AutoTestCopter(AutoTest):
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
self.context_pop()
|
||||
self.mavproxy.send("fence clear\n")
|
||||
self.clear_fence()
|
||||
self.disarm_vehicle(force=True)
|
||||
self.reboot_sitl()
|
||||
if ex is not None:
|
||||
@ -5334,7 +5335,7 @@ class AutoTestCopter(AutoTest):
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
self.context_pop()
|
||||
self.mavproxy.send("fence clear\n")
|
||||
self.clear_fence()
|
||||
self.disarm_vehicle(force=True)
|
||||
self.reboot_sitl()
|
||||
if ex is not None:
|
||||
|
@ -1117,8 +1117,7 @@ class AutoTestPlane(AutoTest):
|
||||
self.assert_fence_sys_status(False, False, True)
|
||||
self.set_parameter("FENCE_ACTION", mavutil.mavlink.FENCE_ACTION_RTL) # report only
|
||||
self.assert_fence_sys_status(True, False, True)
|
||||
self.mavproxy.send('fence enable\n')
|
||||
self.mavproxy.expect("fence enabled")
|
||||
self.do_fence_enable()
|
||||
self.assert_fence_sys_status(True, True, True)
|
||||
m = self.mav.recv_match(type='FENCE_STATUS', blocking=True, timeout=2)
|
||||
if m is None:
|
||||
@ -1126,15 +1125,13 @@ class AutoTestPlane(AutoTest):
|
||||
if m.breach_status:
|
||||
raise NotAchievedException("Breached fence unexpectedly (%u)" %
|
||||
(m.breach_status))
|
||||
self.mavproxy.send('fence disable\n')
|
||||
self.mavproxy.expect("fence disabled")
|
||||
self.do_fence_disable()
|
||||
self.assert_fence_sys_status(True, False, True)
|
||||
self.set_parameter("FENCE_ACTION", mavutil.mavlink.FENCE_ACTION_NONE)
|
||||
self.assert_fence_sys_status(False, False, True)
|
||||
self.set_parameter("FENCE_ACTION", mavutil.mavlink.FENCE_ACTION_RTL)
|
||||
self.assert_fence_sys_status(True, False, True)
|
||||
self.mavproxy.send("fence clear\n")
|
||||
self.mavproxy.expect("fence removed")
|
||||
self.clear_fence()
|
||||
if self.get_parameter("FENCE_TOTAL") != 0:
|
||||
raise NotAchievedException("Expected zero points remaining")
|
||||
self.assert_fence_sys_status(False, False, True)
|
||||
@ -1147,8 +1144,7 @@ class AutoTestPlane(AutoTest):
|
||||
self.set_parameter("FENCE_ACTION", mavutil.mavlink.FENCE_ACTION_RTL)
|
||||
self.do_fence_enable()
|
||||
self.assert_fence_sys_status(True, True, True)
|
||||
self.mavproxy.send("fence clear\n")
|
||||
self.mavproxy.expect("fence removed")
|
||||
self.clear_fence()
|
||||
self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE, False, False, True)
|
||||
if self.get_parameter("FENCE_TOTAL") != 0:
|
||||
raise NotAchievedException("Expected zero points remaining")
|
||||
@ -1156,7 +1152,7 @@ class AutoTestPlane(AutoTest):
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
self.mavproxy.send('fence clear\n')
|
||||
self.clear_fence()
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
@ -1208,7 +1204,7 @@ class AutoTestPlane(AutoTest):
|
||||
except Exception as e:
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
self.mavproxy.send('fence clear\n')
|
||||
self.clear_fence()
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
||||
@ -1292,6 +1288,11 @@ class AutoTestPlane(AutoTest):
|
||||
self.start_subtest(desc)
|
||||
func()
|
||||
|
||||
def clear_fence(self):
|
||||
'''Plane doesn't use MissionItemProtocol - yet - so clear it using
|
||||
mavproxy:'''
|
||||
self.clear_fence_using_mavproxy()
|
||||
|
||||
def test_main_flight(self):
|
||||
|
||||
self.change_mode('MANUAL')
|
||||
|
@ -7440,7 +7440,7 @@ Also, ignores heartbeats not from our target system'''
|
||||
break
|
||||
|
||||
def clear_fence(self):
|
||||
self.clear_fence_using_mavproxy()
|
||||
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
|
||||
|
||||
def clear_mission_using_mavproxy(self):
|
||||
self.mavproxy.send("wp clear\n")
|
||||
@ -8626,11 +8626,11 @@ switch value'''
|
||||
# plane requires a polygon fence...
|
||||
self.start_subtest("Altitude Limit breach")
|
||||
self.set_parameter("AFS_AMSL_LIMIT", 100)
|
||||
self.mavproxy.send("fence enable\n")
|
||||
self.do_fence_enable()
|
||||
self.wait_statustext("Terminating due to fence breach", check_context=True)
|
||||
self.set_parameter("AFS_AMSL_LIMIT", 0)
|
||||
self.set_parameter("AFS_TERMINATE", 0)
|
||||
self.mavproxy.send("fence disable\n")
|
||||
self.do_fence_disable()
|
||||
|
||||
self.start_subtest("GPS Failure")
|
||||
self.set_parameter("AFS_MAX_GPS_LOSS", 1)
|
||||
@ -8654,7 +8654,11 @@ switch value'''
|
||||
|
||||
except Exception as e:
|
||||
ex = e
|
||||
self.mavproxy.send("fence disable\n")
|
||||
try:
|
||||
self.do_fence_disable()
|
||||
except ValueError:
|
||||
# may not actually be enabled....
|
||||
pass
|
||||
self.context_pop()
|
||||
if ex is not None:
|
||||
raise ex
|
||||
|
@ -596,7 +596,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
self.print_exception_caught(e)
|
||||
ex = e
|
||||
self.context_pop()
|
||||
self.mavproxy.send("fence clear\n")
|
||||
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
|
||||
self.disarm_vehicle(force=True)
|
||||
self.reboot_sitl()
|
||||
if ex:
|
||||
|
Loading…
Reference in New Issue
Block a user