mirror of https://github.com/ArduPilot/ardupilot
AP_ICEngine: fixed a bug engine control when running
if you have a mission item for engine control with delayed start at height and the engine is already running them it would put the ICE subsystem into a state where it would no longer start the engine It was actually 2 bugs: - an engine control to do a height delayed start should be ignored if the engine is already running. This prevents an engine control to start the engine from stopping the engine - a start_chan high should always try to start the engine immediately, even if in the wait state
This commit is contained in:
parent
d7cf6528ac
commit
ab43186189
|
@ -217,6 +217,12 @@ void AP_ICEngine::update(void)
|
|||
start_chan_last_value = cvalue;
|
||||
}
|
||||
|
||||
if (state == ICE_START_HEIGHT_DELAY && start_chan_last_value >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
|
||||
// user is overriding the height start delay and asking for
|
||||
// immediate start. Put into ICE_OFF so that the logic below
|
||||
// can start the engine now
|
||||
state = ICE_OFF;
|
||||
}
|
||||
|
||||
if (state == ICE_OFF && start_chan_last_value >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
|
||||
should_run = true;
|
||||
|
@ -434,6 +440,10 @@ bool AP_ICEngine::engine_control(float start_control, float cold_start, float he
|
|||
state = ICE_OFF;
|
||||
return true;
|
||||
}
|
||||
if (state == ICE_RUNNING || state == ICE_START_DELAY || state == ICE_STARTING) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Engine: already running");
|
||||
return false;
|
||||
}
|
||||
RC_Channel *c = rc().channel(start_chan-1);
|
||||
if (c != nullptr && rc().has_valid_input()) {
|
||||
// get starter control channel
|
||||
|
|
Loading…
Reference in New Issue