mirror of https://github.com/ArduPilot/ardupilot
Tools: correct prearm message
This commit is contained in:
parent
9b041be8a1
commit
9311344f4b
|
@ -1498,7 +1498,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
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 Polygon fence")
|
||||
self.assert_prearm_failure("Vehicle breaching Polygon fence")
|
||||
self.progress("Failed to arm outside fence (good!)")
|
||||
self.clear_fence()
|
||||
self.delay_sim_time(5) # let fence breach clear
|
||||
|
|
|
@ -1551,12 +1551,12 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.delay_sim_time(2) # Allow breach to propagate
|
||||
self.assert_fence_enabled()
|
||||
|
||||
self.try_arm(False, "vehicle outside Min Alt fence")
|
||||
self.try_arm(False, "Vehicle breaching Min Alt fence")
|
||||
self.do_fence_disable()
|
||||
self.set_parameter("FENCE_ALT_MIN", default_fence_alt_min)
|
||||
|
||||
# Test arming outside inclusion zone
|
||||
self.progress("Test arming while vehicle outside of inclusion zone")
|
||||
self.progress("Test arming while Vehicle breaching of inclusion zone")
|
||||
self.set_parameter("FENCE_TYPE", 4) # Enables polygon fence types
|
||||
self.upload_fences_from_locations([(
|
||||
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION, [
|
||||
|
@ -1570,7 +1570,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.do_fence_enable()
|
||||
self.assert_fence_enabled()
|
||||
self.delay_sim_time(2) # Allow breach to propagate
|
||||
self.try_arm(False, "vehicle outside Polygon fence")
|
||||
self.try_arm(False, "Vehicle breaching Polygon fence")
|
||||
self.do_fence_disable()
|
||||
self.clear_fence()
|
||||
|
||||
|
@ -1590,7 +1590,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.do_fence_enable()
|
||||
self.assert_fence_enabled()
|
||||
self.delay_sim_time(2) # Allow breach to propagate
|
||||
self.try_arm(False, "vehicle outside Polygon fence")
|
||||
self.try_arm(False, "Vehicle breaching Polygon fence")
|
||||
self.do_fence_disable()
|
||||
|
||||
def test_fence_breach_circle_at(self, loc, disable_on_breach=False):
|
||||
|
|
|
@ -6674,10 +6674,10 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
]),
|
||||
])
|
||||
|
||||
self.assert_prearm_failure('vehicle outside Polygon fence', other_prearm_failures_fatal=False)
|
||||
self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False)
|
||||
self.reboot_sitl()
|
||||
|
||||
self.assert_prearm_failure('vehicle outside Polygon fence', other_prearm_failures_fatal=False, timeout=120)
|
||||
self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120)
|
||||
|
||||
self.progress("Ensure we can arm when a polyfence fence is cleared when we've previously been in breach")
|
||||
self.clear_fence()
|
||||
|
@ -6693,7 +6693,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
]),
|
||||
])
|
||||
self.reboot_sitl()
|
||||
self.assert_prearm_failure('vehicle outside Polygon fence', other_prearm_failures_fatal=False, timeout=120)
|
||||
self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120)
|
||||
self.clear_fence()
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
|
@ -6707,11 +6707,11 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||
self.offset_location_ne(here, 50, 20), # tl,
|
||||
]),
|
||||
])
|
||||
self.assert_prearm_failure('vehicle outside Polygon fence', other_prearm_failures_fatal=False, timeout=120)
|
||||
self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120)
|
||||
self.set_parameter('FENCE_TYPE', 2)
|
||||
self.wait_ready_to_arm()
|
||||
self.set_parameter('FENCE_TYPE', 6)
|
||||
self.assert_prearm_failure('vehicle outside Polygon fence', other_prearm_failures_fatal=False, timeout=120)
|
||||
self.assert_prearm_failure('Vehicle breaching Polygon fence', other_prearm_failures_fatal=False, timeout=120)
|
||||
|
||||
def OpticalFlow(self):
|
||||
'''lightly test OpticalFlow'''
|
||||
|
|
Loading…
Reference in New Issue