mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_ICEngine: add idle throttle percentage
This commit is contained in:
parent
69882d9898
commit
3b9125956e
@ -102,6 +102,13 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = {
|
||||
// @Range: 0 100
|
||||
AP_GROUPINFO("START_PCT", 10, AP_ICEngine, start_percent, 5),
|
||||
|
||||
// @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
|
||||
initial_height = -pos.z;
|
||||
}
|
||||
} else {
|
||||
} else if (idle_percent == 0) { // check if we should idle
|
||||
// force ignition off when disarmed
|
||||
state = ICE_OFF;
|
||||
}
|
||||
@ -250,13 +257,20 @@ void AP_ICEngine::update(void)
|
||||
|
||||
/*
|
||||
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)
|
||||
{
|
||||
if (!enable) {
|
||||
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) {
|
||||
percentage = (uint8_t)start_percent.get();
|
||||
return true;
|
||||
|
@ -89,6 +89,9 @@ private:
|
||||
// throttle percentage for engine start
|
||||
AP_Int8 start_percent;
|
||||
|
||||
// throttle percentage for engine idle
|
||||
AP_Int8 idle_percent;
|
||||
|
||||
// height when we enter ICE_START_HEIGHT_DELAY
|
||||
float initial_height;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user