AP_ICEngine: add idle throttle percentage

This commit is contained in:
IamPete1 2019-04-13 11:13:51 +01:00 committed by Tom Pittenger
parent 69882d9898
commit 3b9125956e
2 changed files with 20 additions and 3 deletions

View File

@ -102,7 +102,14 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
// @Range: 0 100 // @Range: 0 100
AP_GROUPINFO("START_PCT", 10, AP_ICEngine, start_percent, 5), AP_GROUPINFO("START_PCT", 10, AP_ICEngine, start_percent, 5),
AP_GROUPEND // @Param: IDLE_PCT
// @DisplayName: Throttle percentage for engine idle
// @Description: This is the minimum percentage throttle output while running, this includes being disarmed, but not safe
// @User: Standard
// @Range: 0 100
AP_GROUPINFO("IDLE_PCT", 11, AP_ICEngine, idle_percent, 0),
AP_GROUPEND
}; };
@ -210,7 +217,7 @@ void AP_ICEngine::update(void)
// reset initial height while disarmed // reset initial height while disarmed
initial_height = -pos.z; initial_height = -pos.z;
} }
} else { } else if (idle_percent == 0) { // check if we should idle
// force ignition off when disarmed // force ignition off when disarmed
state = ICE_OFF; state = ICE_OFF;
} }
@ -250,13 +257,20 @@ void AP_ICEngine::update(void)
/* /*
check for throttle override. This allows the ICE controller to force check for throttle override. This allows the ICE controller to force
the correct starting throttle when starting the engine the correct starting throttle when starting the engine and maintain idle when disarmed
*/ */
bool AP_ICEngine::throttle_override(uint8_t &percentage) bool AP_ICEngine::throttle_override(uint8_t &percentage)
{ {
if (!enable) { if (!enable) {
return false; return false;
} }
uint8_t current_throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);
if (idle_percent > current_throttle && state == ICE_RUNNING) {
percentage = (uint8_t)idle_percent;
return true;
}
if (state == ICE_STARTING || state == ICE_START_DELAY) { if (state == ICE_STARTING || state == ICE_START_DELAY) {
percentage = (uint8_t)start_percent.get(); percentage = (uint8_t)start_percent.get();
return true; return true;

View File

@ -89,6 +89,9 @@ private:
// throttle percentage for engine start // throttle percentage for engine start
AP_Int8 start_percent; AP_Int8 start_percent;
// throttle percentage for engine idle
AP_Int8 idle_percent;
// height when we enter ICE_START_HEIGHT_DELAY // height when we enter ICE_START_HEIGHT_DELAY
float initial_height; float initial_height;