Hello everyone, I am working on testing an EFI IC Engine (with Alternator starter) mounted as fixed-wing propulsion on a QuadPlane equipped with a CubeOrange. While reviewing the ArduPilot documentation for IC Engines, it is mentioned that the DO_ENGINE_CONTROL command should be used in AutoMission after VTOL_TAKEOFF to automatically start the engine before transitioning to fixed-wing mode, eliminating the need for RC input.
Simulation Setup:
→ ICE_ENABLE: 1
→ SERVO13_FUNCTION: Ignition
→ SERVO14_FUNCTION: Starter
→ RC5_OPTION: IC_ENGINE_START_STOP (179) In the mission setup, I have included VTOL_TAKEOFF followed by the DO_ENGINE_CONTROL command to auto-start the engine. The vehicle is armed in Auto mode, with RC5 set to mid-stick, allowing MAVLink commands to control the engine start/stop, as per the documentation.
Observations:
→ During takeoff in VTOL mode, the vehicle ascends to the desired altitude.
→ When the DO_ENGINE_CONTROL command is executed, the ignition is successfully enabled (verified through the SERVO13 output).
→ However, the starter (assigned to SERVO14) is not being triggered. Without this, the engine does not start, even though the throttle PWM is correctly output through SERVO3.
Please let me know if there are additional configurations or steps I may have missed to ensure the proper operation of the starter during the mission. Any guidance on resolving this issue or refining the setup would be highly appreciated.
Hello, I have further investigated the issue by debugging the ArduPilot code, and I have identified the root cause of the observed behavior (Ignition enabling but Starter not triggering). The problem stems from how the ICEngine state is being updated in the code. The ICEngine state transitions directly from ‘ICE_STARTING’ to ‘ICE_RUNNING’ without engaging the output channels for Ignition and Starter. This behavior is caused by a logic condition in 'AP_ICEngine.cpp ’ based on time intervals.
I have attached an image illustrating how the status transitions to ICE_RUNNING. This behavior arises due to the logic evaluating time intervals in the code.
→ starter_time: Specifies the duration the starter should run (set to 3 seconds in my case). → now: The current runtime after powering on the autopilot.
→ starter_start_time_ms: Tracks the time when the starter was engaged.
→ However, starter_start_time_ms defaults to ‘0’, causing the condition to immediately evaluate as true. This skips the output channel operations, transitioning the state prematurely to ICE_RUNNING.
Note: I am not using any RPM data to detect the ICEngine status.
I have modified the code to start the IC Engine for the first time when the flag ICE_STARTING is raised, this may tamper the ICEngine starting behavior in other cases but works for my case when running a Auto mission with DO_ENGINE_CONTROL command for the first time after a reboot.
Out of curiosity, are you sure you even want to use the ICE library? Without an RPM sensor, most of the ICE features in there are useless to you (auto restart, idle govern, redline limiting). You could set up two relays (or PWM channels depending on your setup) and have two switches (or one switch that controls two channels) for “ignition enable” and “starter”, without using the ICE library at all.
You are absolutely correct regarding the manual setup of the ignition and starter to the switch in RC when not using an RPM sensor. I have also tested this setup previously, and it works perfectly fine without any issues.
However, I would like to clarify a specific point. In the case of using the engine control command during an Auto mission, the auto-start functionality seems to only engage the ignition but does not activate the starter. Does this behavior require an RPM sensor to function correctly?
To clarify further, I am not referring to the auto-start functionality triggered during an engine cut-off in mid-air (for which I understand an RPM sensor is required). My question pertains solely to the auto-start process during an Auto mission in a quadplane after completing VTOL take-off.