mirror of https://github.com/ArduPilot/ardupilot
Tools: autotest for Tradheli turbine start feature
This commit is contained in:
parent
697b23910c
commit
f7317966dc
|
@ -487,6 +487,73 @@ class AutoTestHelicopter(AutoTestCopter):
|
|||
|
||||
self.reboot_sitl()
|
||||
|
||||
def TurbineStart(self, timeout=200):
|
||||
"""Check Turbine Start Feature"""
|
||||
RAMP_TIME = 4
|
||||
# set option for Turbine Start
|
||||
self.set_parameter("RC6_OPTION", 161)
|
||||
self.set_parameter("H_RSC_RAMP_TIME", RAMP_TIME)
|
||||
self.set_parameter("H_RSC_SETPOINT", 66)
|
||||
self.set_parameter("DISARM_DELAY", 0)
|
||||
self.set_rc(3, 1000)
|
||||
self.set_rc(8, 1000)
|
||||
|
||||
# check that turbine start doesn't activate while disarmed
|
||||
self.progress("Checking Turbine Start doesn't activate while disarmed")
|
||||
self.set_rc(6, 2000)
|
||||
tstart = self.get_sim_time()
|
||||
while self.get_sim_time() - tstart < 2:
|
||||
servo = self.mav.recv_match(type='SERVO_OUTPUT_RAW', blocking=True)
|
||||
if servo.servo8_raw > 1050:
|
||||
raise NotAchievedException("Turbine Start activated while disarmed")
|
||||
self.set_rc(6, 1000)
|
||||
|
||||
# check that turbine start doesn't activate armed with interlock enabled
|
||||
self.progress("Checking Turbine Start doesn't activate while armed with interlock enabled")
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
self.set_rc(8, 2000)
|
||||
self.set_rc(6, 2000)
|
||||
tstart = self.get_sim_time()
|
||||
while self.get_sim_time() - tstart < 5:
|
||||
servo = self.mav.recv_match(type='SERVO_OUTPUT_RAW', blocking=True)
|
||||
if servo.servo8_raw > 1660:
|
||||
raise NotAchievedException("Turbine Start activated with interlock enabled")
|
||||
|
||||
self.set_rc(8, 1000)
|
||||
self.set_rc(6, 1000)
|
||||
self.disarm_vehicle()
|
||||
|
||||
# check that turbine start activates as designed (armed with interlock disabled)
|
||||
self.progress("Checking Turbine Start activates as designed (armed with interlock disabled)")
|
||||
self.delay_sim_time(2)
|
||||
self.arm_vehicle()
|
||||
|
||||
self.set_rc(6, 2000)
|
||||
tstart = self.get_sim_time()
|
||||
while True:
|
||||
if self.get_sim_time() - tstart > 5:
|
||||
raise AutoTestTimeoutException("Turbine Start did not activate")
|
||||
servo = self.mav.recv_match(type='SERVO_OUTPUT_RAW', blocking=True)
|
||||
if servo.servo8_raw > 1800:
|
||||
break
|
||||
|
||||
self.wait_servo_channel_value(8, 1000, timeout=3)
|
||||
self.set_rc(6, 1000)
|
||||
|
||||
# check that turbine start will not reactivate after interlock enabled
|
||||
self.progress("Checking Turbine Start doesn't activate once interlock is enabled after start)")
|
||||
self.set_rc(8, 2000)
|
||||
self.set_rc(6, 2000)
|
||||
tstart = self.get_sim_time()
|
||||
while self.get_sim_time() - tstart < 5:
|
||||
servo = self.mav.recv_match(type='SERVO_OUTPUT_RAW', blocking=True)
|
||||
if servo.servo8_raw > 1660:
|
||||
raise NotAchievedException("Turbine Start activated with interlock enabled")
|
||||
self.set_rc(6, 1000)
|
||||
self.set_rc(8, 1000)
|
||||
self.disarm_vehicle()
|
||||
|
||||
def tests(self):
|
||||
'''return list of all tests'''
|
||||
ret = AutoTest.tests(self)
|
||||
|
@ -500,6 +567,7 @@ class AutoTestHelicopter(AutoTestCopter):
|
|||
self.ManAutoRotation,
|
||||
self.FlyEachFrame,
|
||||
self.AirspeedDrivers,
|
||||
self.TurbineStart,
|
||||
])
|
||||
return ret
|
||||
|
||||
|
|
Loading…
Reference in New Issue