Skip to content

Commit

Permalink
Tools: autotest: quadplane: ICE Don't setup ICE start channel its alr…
Browse files Browse the repository at this point in the history
…eady in model defaults
  • Loading branch information
IamPete1 authored and tridge committed Aug 26, 2024
1 parent 98d9890 commit a75a97e
Showing 1 changed file with 4 additions and 8 deletions.
12 changes: 4 additions & 8 deletions Tools/autotest/quadplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -1049,12 +1049,8 @@ def Tailsitter(self):
raise NotAchievedException("Changed throttle output on mode change to QHOVER")
self.disarm_vehicle()

def setup_ICEngine_vehicle(self, start_chan):
def setup_ICEngine_vehicle(self):
'''restarts SITL with an IC Engine setup'''
self.set_parameters({
'ICE_START_CHAN': start_chan,
})

model = "quadplane-ice"
self.customise_SITL_commandline(
[],
Expand All @@ -1066,7 +1062,7 @@ def setup_ICEngine_vehicle(self, start_chan):
def ICEngine(self):
'''Test ICE Engine support'''
rc_engine_start_chan = 11
self.setup_ICEngine_vehicle(start_chan=rc_engine_start_chan)
self.setup_ICEngine_vehicle()

self.wait_ready_to_arm()
self.wait_rpm(1, 0, 0, minimum_duration=1)
Expand Down Expand Up @@ -1105,7 +1101,7 @@ def ICEngine(self):
def ICEngineMission(self):
'''Test ICE Engine Mission support'''
rc_engine_start_chan = 11
self.setup_ICEngine_vehicle(start_chan=rc_engine_start_chan)
self.setup_ICEngine_vehicle()

self.load_mission("mission.txt")
self.wait_ready_to_arm()
Expand All @@ -1123,7 +1119,7 @@ def MAV_CMD_DO_ENGINE_CONTROL(self):
expected_starter_rpm_max = 355

rc_engine_start_chan = 11
self.setup_ICEngine_vehicle(start_chan=rc_engine_start_chan)
self.setup_ICEngine_vehicle()

self.wait_ready_to_arm()

Expand Down

0 comments on commit a75a97e

Please sign in to comment.