mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_ICEngine: Change throttle_override to pass in current throttle value
This commit is contained in:
parent
df0a75a0bb
commit
53a5043ac4
@ -357,7 +357,7 @@ 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 and maintain idle when disarmed
|
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(float &percentage)
|
||||||
{
|
{
|
||||||
if (!enable) {
|
if (!enable) {
|
||||||
return false;
|
return false;
|
||||||
@ -366,33 +366,32 @@ bool AP_ICEngine::throttle_override(uint8_t &percentage)
|
|||||||
if (state == ICE_RUNNING &&
|
if (state == ICE_RUNNING &&
|
||||||
idle_percent > 0 &&
|
idle_percent > 0 &&
|
||||||
idle_percent < 100 &&
|
idle_percent < 100 &&
|
||||||
(int16_t)idle_percent > SRV_Channels::get_output_scaled(SRV_Channel::k_throttle))
|
idle_percent > percentage)
|
||||||
{
|
{
|
||||||
percentage = (uint8_t)idle_percent;
|
percentage = idle_percent;
|
||||||
return true;
|
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 = start_percent.get();
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (redline.flag && !(options & uint16_t(Options::DISABLE_REDLINE_GOVERNOR))) {
|
if (redline.flag && !(options & uint16_t(Options::DISABLE_REDLINE_GOVERNOR))) {
|
||||||
// limit the throttle from increasing above what the current output is
|
// limit the throttle from increasing above what the current output is
|
||||||
const float incoming_throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);
|
|
||||||
if (redline.throttle_percentage < 1.0f) {
|
if (redline.throttle_percentage < 1.0f) {
|
||||||
redline.throttle_percentage = incoming_throttle;
|
redline.throttle_percentage = percentage;
|
||||||
}
|
}
|
||||||
if (incoming_throttle < redline.throttle_percentage - redline.governor_integrator) {
|
if (percentage < redline.throttle_percentage - redline.governor_integrator) {
|
||||||
// the throttle before the override is much lower than what the integrator is at
|
// the throttle before the override is much lower than what the integrator is at
|
||||||
// reset the integrator
|
// reset the integrator
|
||||||
redline.governor_integrator = 0;
|
redline.governor_integrator = 0;
|
||||||
redline.throttle_percentage = incoming_throttle;
|
redline.throttle_percentage = percentage;
|
||||||
} else if (incoming_throttle < redline.throttle_percentage) {
|
} else if (percentage < redline.throttle_percentage) {
|
||||||
// the throttle is below the integrator set point
|
// the throttle is below the integrator set point
|
||||||
// remove the difference from the integrator
|
// remove the difference from the integrator
|
||||||
redline.governor_integrator -= redline.throttle_percentage - incoming_throttle;
|
redline.governor_integrator -= redline.throttle_percentage - percentage;
|
||||||
redline.throttle_percentage = incoming_throttle;
|
redline.throttle_percentage = percentage;
|
||||||
} else if (filtered_rpm_value > redline_rpm) {
|
} else if (filtered_rpm_value > redline_rpm) {
|
||||||
// reduce the throttle if still over the redline RPM
|
// reduce the throttle if still over the redline RPM
|
||||||
const float redline_setpoint_step = idle_slew * AP::scheduler().get_loop_period_s();
|
const float redline_setpoint_step = idle_slew * AP::scheduler().get_loop_period_s();
|
||||||
|
@ -31,7 +31,7 @@ public:
|
|||||||
void update(void);
|
void update(void);
|
||||||
|
|
||||||
// check for throttle override
|
// check for throttle override
|
||||||
bool throttle_override(uint8_t &percent);
|
bool throttle_override(float &percent);
|
||||||
|
|
||||||
enum ICE_State {
|
enum ICE_State {
|
||||||
ICE_OFF=0,
|
ICE_OFF=0,
|
||||||
|
Loading…
Reference in New Issue
Block a user