Potential edge case in AP_ICEngine where starter will never be engaged

I am trying to perform a quadplane mission (AP 3.9.8, ChiBiOS) with DO_ENGINE_CONTROL as one of our commands. Due to hardware issues, we opted to operate without an RPM sensor and disable RC control over the engine starter.

I noticed from the AP_ICEngine library that if we send a DO_ENGINE_CONTROL command, the code appears to hit an edge case where starter is never activated. The conditions to fulfil this edge case is:

  1. ICE_RPM_CHAN set to 0 (since we are not using RPM sensor)
  2. ICE_START_CHAN set to 0 (hence no control from RC)
  3. Height delay option in DO_ENGINE_CONTROL set to 0 (our quadplane landing gear has sufficient clearance to prevent a forward engine prop strike when on the ground)

With these conditions, the state of the ICE enters ICE_STARTING (line 287) immediately after receiving the DO_ENGINE_CONTROL command (since height delay = 0):

state = ICE_STARTING;
return true;

However, starter_start_time_ms is still 0 (previously set in ICE_OFF, line 219):

case ICE_OFF:
    SRV_Channels::set_output_pwm(SRV_Channel::k_ignition, pwm_ignition_off);
    SRV_Channels::set_output_pwm(SRV_Channel::k_starter,  pwm_starter_off);
    starter_start_time_ms = 0;
    break;

In the next loop of AP_ICEngine::update, the state enters ICE_STARTING. Upon reaching line 180, the else-if statement executes since starter_start_time_ms is still 0:

case ICE_STARTING:
    if (!should_run) {
        state = ICE_OFF;
    } else if (now - starter_start_time_ms >= starter_time*1000) {
        state = ICE_RUNNING;
    }

The state then goes straight into ICE_RUNNING without ever reaching line 230, which turns on the starter:

case ICE_STARTING:
    SRV_Channels::set_output_pwm(SRV_Channel::k_ignition, pwm_ignition_on);
    SRV_Channels::set_output_pwm(SRV_Channel::k_starter,  pwm_starter_on);
    if (starter_start_time_ms == 0) {
        starter_start_time_ms = now;
    }
    starter_last_run_ms = now;
    break;

Hence, the starter will never be engaged, and the engine will not start.

We have tried testing this on our quadplane and it shows the same behaviour: The starter is never activated.

If my deduction is correct, then the solution to this edge case is update starter_start_time_ms to the current time at the end of AP_ICEngine::engine_control, so that the update() function has a chance to start the engine.

Developers, what’s your take on this issue?

looks like your right, i think i would add
if (starter_start_time_ms != 0) {

here https://github.com/ArduPilot/ardupilot/blob/d515b40966e1a7613a4767dd0b99dc6831fa25d6/libraries/AP_ICEngine/AP_ICEngine.cpp#L178

then you will hit the bottom switch case and set the start time

are you able to compile and test? if not I can build to a test firmware

I think the correct fix is to actually change line 287 (https://github.com/ArduPilot/ardupilot/blob/plane3.9/libraries/AP_ICEngine/AP_ICEngine.cpp#L287) to be:

state = ICE_START_DELAY;

That’s not only the exactly the same as when using the RC to start it, but I also think we still want to comply with the start delay.

Thanks to both for the input.

I have edited and compiled a fix (on Github: https://github.com/yonahbox/ardupilot/commit/341b42f2909ce3a89410388bcaf71d382daa9654), test firmware is below:

arduplane.apj (834.8 KB)

However, I’m not sure whether we’ll be able to test this new firmware soon as we will be flight testing other components. For now, we will bypass this problem by setting a nonzero height delay for DO_ENGINE_CONTROL

As we are unable to test on an actual aircraft yet, I ran a couple of tests on SITL by inserting a DO_ENGINE_CONTROL command into a simple VTOL takeoff and landing mission. The tests are:

  1. Plane 3.9.8 with a DO_ENGINE_CONTROL height delay of 5
  2. Plane 3.9.8 with a DO_ENGINE_CONTROL height delay of 0
  3. Modified Plane 3.9.8 (based on Francisco’s recommendation) with a DO_ENGINE_CONTROL height delay of 0

The starter is mapped to SERVO12, and the ignition mapped to SERVO13. All conditions specified in the edge case were set accordingly.

In (1), SITL behaves as expected: Starting the engine at height 5m, and running the starter for the specified start time (RCOU.C12). The ignition was also turned on (RCOU.C13):

In (2), SITL behaves as what was described in the edge case: The starter is never engaged.

In (3), SITL is able to start the engine at height 0, using the test firmware.

All SITL test products (logs, param files, waypoint files) are here: https://drive.google.com/open?id=1M85BexqvSxj1MIiTiWcXK0mykCl1bMeT

Looks like the fix is working, at least in SITL. Hopefully, me or someone else will be able to test it on a real aircraft soon :slight_smile: