mirror of https://github.com/ArduPilot/ardupilot
Tools: autotest check-avoidance-corners disables proximity before RTL
This commit is contained in:
parent
1552b72596
commit
4944eb9e7f
|
@ -7403,7 +7403,6 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.reach_heading_manual(225)
|
||||
self.wait_location(west_loc, accuracy=6, timeout=200)
|
||||
self.set_rc(2, 1500)
|
||||
self.do_RTL()
|
||||
|
||||
def OBSTACLE_DISTANCE_3D_test_angle(self, angle):
|
||||
now = self.get_sim_time_cached()
|
||||
|
@ -7493,6 +7492,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.progress("Enabling proximity")
|
||||
self.set_rc(10, 2000)
|
||||
self.check_avoidance_corners()
|
||||
self.set_rc(10, 1000)
|
||||
self.do_RTL()
|
||||
|
||||
self.assert_current_onboard_log_contains_message("PRX")
|
||||
self.assert_current_onboard_log_contains_message("PRXR")
|
||||
|
@ -7660,6 +7661,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.load_fence("copter-avoidance-fence.txt")
|
||||
self.set_parameter("FENCE_ENABLE", 1)
|
||||
self.check_avoidance_corners()
|
||||
self.do_RTL()
|
||||
|
||||
def AvoidanceAltFence(self):
|
||||
'''Test fence avoidance at minimum and maximum altitude'''
|
||||
|
|
Loading…
Reference in New Issue