Skip to content

Conversation

@LachlanConn
Copy link
Contributor

Current behaviour has a harsh dip from start percent to minimum throttle before slewing up to defined idle governor RPM.
This change now slews smoothly from whatever the start percent is, up or down to the defined idle governor RPM.

if (!ap_rpm->get_rpm(rpm_instance-1, rpmv) || rpmv < 1) {
// Reset idle point to the default value when the engine is stopped
idle_governor_integrator = min_throttle;
idle_governor_integrator = start_percent.get();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Would it be better to set idle_point_initialized = false here? Maybe we should do the same for the return on 655?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

yeh that's probably a bit clearer

@LachlanConn LachlanConn force-pushed the idle_governor__initialise_at_start_pct branch from aad74f5 to 6d5cb7f Compare December 16, 2025 00:54
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants