mirror of https://github.com/ArduPilot/ardupilot
AP_ICEngine: report when engine goes into run state
This commit is contained in:
parent
d6e7d568a0
commit
ceb53ffa92
|
@ -271,6 +271,7 @@ void AP_ICEngine::update(void)
|
|||
if (!should_run) {
|
||||
state = ICE_OFF;
|
||||
} else if (now - starter_start_time_ms >= starter_time*1000) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Engine running");
|
||||
state = ICE_RUNNING;
|
||||
}
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue