|
|
|
@ -811,6 +811,56 @@ class AutoTestQuadPlane(AutoTest):
@@ -811,6 +811,56 @@ class AutoTestQuadPlane(AutoTest):
|
|
|
|
|
raise NotAchievedException("Changed throttle output on mode change to QHOVER") |
|
|
|
|
self.disarm_vehicle() |
|
|
|
|
|
|
|
|
|
def ICEngine(self): |
|
|
|
|
rc_engine_start_chan = 11 |
|
|
|
|
self.set_parameters({ |
|
|
|
|
'SERVO13_FUNCTION': 67, # ignition |
|
|
|
|
'SERVO14_FUNCTION': 69, # starter |
|
|
|
|
'ICE_ENABLE': 1, |
|
|
|
|
'ICE_START_CHAN': rc_engine_start_chan, |
|
|
|
|
'ICE_RPM_CHAN': 1, |
|
|
|
|
'RPM1_TYPE': 10, |
|
|
|
|
}) |
|
|
|
|
self.reboot_sitl() |
|
|
|
|
self.wait_ready_to_arm() |
|
|
|
|
self.wait_rpm(1, 0, 0, minimum_duration=1) |
|
|
|
|
self.arm_vehicle() |
|
|
|
|
self.wait_rpm(1, 0, 0, minimum_duration=1) |
|
|
|
|
self.context_collect("STATUSTEXT") |
|
|
|
|
self.progress("Setting engine-start RC switch to HIGH") |
|
|
|
|
self.set_rc(rc_engine_start_chan, 2000) |
|
|
|
|
self.wait_statustext("Starting engine", check_context=True) |
|
|
|
|
self.wait_rpm(1, 300, 400, minimum_duration=1) |
|
|
|
|
self.progress("Setting engine-start RC switch to MID") |
|
|
|
|
self.set_rc(rc_engine_start_chan, 1500) |
|
|
|
|
self.progress("Setting full throttle") |
|
|
|
|
self.set_rc(3, 2000) |
|
|
|
|
self.wait_rpm(1, 6500, 7500, minimum_duration=30, timeout=40) |
|
|
|
|
self.progress("Setting min-throttle") |
|
|
|
|
self.set_rc(3, 1000) |
|
|
|
|
self.wait_rpm(1, 300, 400, minimum_duration=1) |
|
|
|
|
self.progress("Setting engine-start RC switch to LOW") |
|
|
|
|
self.set_rc(rc_engine_start_chan, 1000) |
|
|
|
|
self.wait_rpm(1, 0, 0, minimum_duration=1) |
|
|
|
|
self.disarm_vehicle() |
|
|
|
|
|
|
|
|
|
def ICEngineMission(self): |
|
|
|
|
rc_engine_start_chan = 11 |
|
|
|
|
self.set_parameters({ |
|
|
|
|
'SERVO13_FUNCTION': 67, # ignition |
|
|
|
|
'SERVO14_FUNCTION': 69, # starter |
|
|
|
|
'ICE_ENABLE': 1, |
|
|
|
|
'ICE_START_CHAN': rc_engine_start_chan, |
|
|
|
|
'ICE_RPM_CHAN': 1, |
|
|
|
|
'RPM1_TYPE': 10, |
|
|
|
|
}) |
|
|
|
|
self.load_mission("mission.txt") |
|
|
|
|
self.wait_ready_to_arm() |
|
|
|
|
self.set_rc(rc_engine_start_chan, 2000) |
|
|
|
|
self.arm_vehicle() |
|
|
|
|
self.change_mode('AUTO') |
|
|
|
|
self.wait_disarmed(timeout=300) |
|
|
|
|
|
|
|
|
|
def tests(self): |
|
|
|
|
'''return list of all tests''' |
|
|
|
|
|
|
|
|
@ -854,6 +904,13 @@ class AutoTestQuadPlane(AutoTest):
@@ -854,6 +904,13 @@ class AutoTestQuadPlane(AutoTest):
|
|
|
|
|
"Test tailsitter support", |
|
|
|
|
self.tailsitter), |
|
|
|
|
|
|
|
|
|
("ICEngine", |
|
|
|
|
"Test ICE Engine support", |
|
|
|
|
self.ICEngine), |
|
|
|
|
|
|
|
|
|
("ICEngineMission", |
|
|
|
|
"Test ICE Engine Mission support", |
|
|
|
|
self.ICEngineMission), |
|
|
|
|
|
|
|
|
|
("LogUpload", |
|
|
|
|
"Log upload", |
|
|
|
|