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:
- ICE_RPM_CHAN set to 0 (since we are not using RPM sensor)
- ICE_START_CHAN set to 0 (hence no control from RC)
- 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?