mirror of https://github.com/ArduPilot/ardupilot
autotest: add test for PILOT_THR_BHV parameter
This commit is contained in:
parent
d63307f881
commit
800a834740
|
@ -25,6 +25,7 @@ import vehicle_test_suite
|
|||
from vehicle_test_suite import NotAchievedException, AutoTestTimeoutException, PreconditionFailedException
|
||||
from vehicle_test_suite import Test
|
||||
from vehicle_test_suite import MAV_POS_TARGET_TYPE_MASK
|
||||
from vehicle_test_suite import WaitAndMaintainArmed
|
||||
|
||||
from pymavlink.rotmat import Vector3
|
||||
|
||||
|
@ -10705,6 +10706,32 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
|
||||
self.do_RTL()
|
||||
|
||||
def PILOT_THR_BHV(self):
|
||||
'''test the PILOT_THR_BHV parameter'''
|
||||
self.start_subtest("Test default behaviour, no disarm on land")
|
||||
self.set_parameters({
|
||||
"DISARM_DELAY": 0,
|
||||
})
|
||||
self.takeoff(2, mode='GUIDED')
|
||||
self.set_rc(3, 1500)
|
||||
self.change_mode('LOITER')
|
||||
self.set_rc(3, 1300)
|
||||
|
||||
maintain_armed = WaitAndMaintainArmed(self, minimum_duration=20)
|
||||
maintain_armed.run()
|
||||
|
||||
self.start_subtest("Test THR_BEHAVE_DISARM_ON_LAND_DETECT")
|
||||
self.set_parameters({
|
||||
"PILOT_THR_BHV": 4, # Disarm on land detection
|
||||
})
|
||||
self.zero_throttle()
|
||||
self.takeoff(2, mode='GUIDED')
|
||||
self.set_rc(3, 1500)
|
||||
self.change_mode('LOITER')
|
||||
self.set_rc(3, 1300)
|
||||
|
||||
self.wait_disarmed()
|
||||
|
||||
def tests2b(self): # this block currently around 9.5mins here
|
||||
'''return list of all tests'''
|
||||
ret = ([
|
||||
|
@ -10779,6 +10806,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.MAV_CMD_NAV_TAKEOFF,
|
||||
self.MAV_CMD_NAV_TAKEOFF_command_int,
|
||||
self.Ch6TuningWPSpeed,
|
||||
self.PILOT_THR_BHV,
|
||||
])
|
||||
return ret
|
||||
|
||||
|
|
Loading…
Reference in New Issue