Skip to content

Commit

Permalink
Tools: autotest for Tradheli turbine start feature
Browse files Browse the repository at this point in the history
  • Loading branch information
bnsgeyer committed Feb 19, 2023
1 parent 697b239 commit f731796
Showing 1 changed file with 68 additions and 0 deletions.
68 changes: 68 additions & 0 deletions Tools/autotest/helicopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -487,6 +487,73 @@ def check_airspeeds(mav, m):

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)
Expand All @@ -500,6 +567,7 @@ def tests(self):
self.ManAutoRotation,
self.FlyEachFrame,
self.AirspeedDrivers,
self.TurbineStart,
])
return ret

Expand Down

0 comments on commit f731796

Please sign in to comment.