mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 22:18:28 -04:00
Autotest: Helicopter: Add turbine cooldown test
This commit is contained in:
parent
14447c6e2d
commit
4ce1c5db90
@ -15,6 +15,7 @@ from pymavlink import mavutil
|
||||
from pysim import vehicleinfo
|
||||
|
||||
import copy
|
||||
import operator
|
||||
|
||||
|
||||
class AutoTestHelicopter(AutoTestCopter):
|
||||
@ -697,6 +698,52 @@ class AutoTestHelicopter(AutoTestCopter):
|
||||
self.disarm_vehicle()
|
||||
self.context_pop()
|
||||
|
||||
def TurbineCoolDown(self, timeout=200):
|
||||
"""Check Turbine Cool Down Feature"""
|
||||
# set option for Turbine
|
||||
RAMP_TIME = 4
|
||||
SETPOINT = 66
|
||||
IDLE = 15
|
||||
COOLDOWN_TIME = 5
|
||||
self.set_parameter("RC6_OPTION", 161)
|
||||
self.set_parameter("H_RSC_RAMP_TIME", RAMP_TIME)
|
||||
self.set_parameter("H_RSC_SETPOINT", SETPOINT)
|
||||
self.set_parameter("H_RSC_IDLE", IDLE)
|
||||
self.set_parameter("H_RSC_CLDWN_TIME", COOLDOWN_TIME)
|
||||
self.set_rc(3, 1000)
|
||||
self.set_rc(8, 1000)
|
||||
|
||||
self.progress("Starting turbine")
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
|
||||
self.set_rc(6, 2000)
|
||||
self.wait_statustext('Turbine startup')
|
||||
|
||||
# Engage interlock to run up to head speed
|
||||
self.set_rc(8, 2000)
|
||||
|
||||
# Check throttle gets to setpoint
|
||||
expected_thr = SETPOINT * 0.01 * 1000 + 1000 - 1 # servo end points are 1000 to 2000
|
||||
self.wait_servo_channel_value(8, expected_thr, timeout=RAMP_TIME+1, comparator=operator.ge)
|
||||
|
||||
self.progress("Checking cool down behaviour, idle x 1.5")
|
||||
self.set_rc(8, 1000)
|
||||
tstart = self.get_sim_time()
|
||||
expected_thr = IDLE * 1.5 * 0.01 * 1000 + 1000 + 1
|
||||
self.wait_servo_channel_value(8, expected_thr, timeout=2, comparator=operator.le)
|
||||
|
||||
# Check that the throttle drops to idle after cool down time
|
||||
expected_thr = IDLE * 0.01 * 1000 + 1000 + 1
|
||||
self.wait_servo_channel_value(8, expected_thr, timeout=COOLDOWN_TIME+1, comparator=operator.le)
|
||||
|
||||
measured_time = self.get_sim_time() - tstart
|
||||
if (abs(measured_time - COOLDOWN_TIME) > 1.0):
|
||||
raise NotAchievedException('Throttle did not reduce to idle within H_RSC_CLDWN_TIME')
|
||||
|
||||
self.set_rc(6, 1000)
|
||||
self.wait_disarmed(timeout=20)
|
||||
|
||||
def TurbineStart(self, timeout=200):
|
||||
"""Check Turbine Start Feature"""
|
||||
RAMP_TIME = 4
|
||||
@ -980,6 +1027,7 @@ class AutoTestHelicopter(AutoTestCopter):
|
||||
self.FlyEachFrame,
|
||||
self.AirspeedDrivers,
|
||||
self.TurbineStart,
|
||||
self.TurbineCoolDown,
|
||||
self.NastyMission,
|
||||
self.PIDNotches,
|
||||
self.AutoTune,
|
||||
|
Loading…
Reference in New Issue
Block a user