mirror of https://github.com/ArduPilot/ardupilot
autotest: fixed race in MinAltFenceAvoid copter test
This commit is contained in:
parent
9dc6e1cbea
commit
c9e9b13404
|
@ -1719,8 +1719,6 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
# Also check that the vehicle will not try and ascend too fast when trying to backup from a min alt fence due to avoidance
|
||||
def MinAltFenceAvoid(self):
|
||||
'''Test Min Alt Fence Avoidance'''
|
||||
self.takeoff(30, mode="LOITER")
|
||||
"""Hold loiter position."""
|
||||
|
||||
# enable fence, only min altitude
|
||||
# No action, rely on avoidance to prevent the breach
|
||||
|
@ -1731,6 +1729,9 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
"FENCE_ACTION": 0,
|
||||
})
|
||||
|
||||
self.takeoff(30, mode="LOITER")
|
||||
"""Hold loiter position."""
|
||||
|
||||
# Try and fly past the fence
|
||||
self.set_rc(3, 1120)
|
||||
|
||||
|
|
Loading…
Reference in New Issue