Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_ICEngine: Add redline RPM warning message and governor #18273

Merged
merged 3 commits into from
May 26, 2022

Conversation

TunaLobster
Copy link
Contributor

Adds warning when the RPM of the engine is above the redline RPM. Also notifies the when the RPM returns below the redline.

Tested on CubeBlack with an arduino making pulses for the RPM interrupts.

image

libraries/AP_ICEngine/AP_ICEngine.h Outdated Show resolved Hide resolved
libraries/AP_ICEngine/AP_ICEngine.cpp Outdated Show resolved Hide resolved
libraries/AP_ICEngine/AP_ICEngine.h Outdated Show resolved Hide resolved
libraries/AP_ICEngine/AP_ICEngine.h Outdated Show resolved Hide resolved
@rmackay9
Copy link
Contributor

Wouldn't it be better to have an RPM meter on the GCS with a red line? This could also be done quite easily with a script so I'm not sure adding this is worth the extra parameter and code. This is just one opinion of course.

@TunaLobster
Copy link
Contributor Author

I completely understand that. The next step to this would be adding an optional limiter to the RPM so that TECS doesn't run an engine above the redline. I backed off from that right now because the throttle_override was throwing me for a loop how how to do it correctly. It would probably end up being similar to the idle governor feature. The simple way is to limit TECS throttle percentage. Right now, this would add on having a GCS TTS the warning when it happens in non-TECS modes.

@magicrub
Copy link
Contributor

The simple way is to limit TECS throttle percentage.

Come to think of it, the ICE lib already does throttle overriding for idle. Perhaps this should morph into not just a non-zero minimum but also an rpm max too with an optional alarm.

ICE throttle override:
https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_ICEngine/AP_ICEngine.cpp#L384-L450

ICE overring throttle in Plane:
https://github.com/ArduPilot/ardupilot/blob/master/ArduPlane/servos.cpp#L482

@TunaLobster
Copy link
Contributor Author

TunaLobster commented Aug 12, 2021

Had another think at adding a governor on the high side. I haven't had a chance to test this on a bench. Need to be at a different desk to do that. Also need to make a better fake RPM pulse signal on my arduino. I made a few assumptions with the high side integrator only calculating when over the redline RPM and limiting the throttle from increasing did not put the RPM more than 10% below the redline RPM. I think that is correctly done? I guessed at using a lowpass filter from the Filter library. An averaging filter might have issues with the varying noise in the RPM signal. Also just guessed at a 5Hz cutoff to prevent attenuating the pilot commands.

And I misspelled the commit message. When do we get spellcheck on a command line?

@TunaLobster TunaLobster force-pushed the pr-ICE-redline branch 3 times, most recently from 4ea46c2 to 8d050bc Compare August 17, 2021 17:36
@TunaLobster
Copy link
Contributor Author

TunaLobster commented Aug 17, 2021

Working on a CubeBlack. Log and graph included. Removed the state == ICE_RUNNING. Open to discussion on the ICE state works. Since we used external starters, changing how the state works might be useful.

In this test I have the throttle input constant and I raise the RPM until it is over the ICE_REDLINE_RPM value of 5000. You can see that the RCOU.3 value starts dropping at a constant rate until the RPM is below the redline value. When the RPM is more than 10% below the parameter value, the throttle override is released and the output returns the same value as before.

image

https://drive.google.com/drive/folders/1tgMPDCtFYH-bZ9HhoB_c_I55gX3csFOd?usp=sharing

@TunaLobster TunaLobster changed the title AP_ICEngine: Add redline RPM warning message AP_ICEngine: Add redline RPM warning message and governor Aug 19, 2021
@TunaLobster
Copy link
Contributor Author

Added the ability for the throttle to decrease more rapidly than the integrator if commanded and the RPM is still high. Adjusts the throttle set point and the integrator to match how rapidly it is being commanded to decrease. That also removes a case of sharp throttle change.

There is another case that I'm not sure I can solve with code. If the RPM goes above redline and the prop becomes more loaded causing the RPM to drop, now there's a sharp change to increase throttle.

libraries/AP_ICEngine/AP_ICEngine.cpp Outdated Show resolved Hide resolved
libraries/AP_ICEngine/AP_ICEngine.cpp Outdated Show resolved Hide resolved
libraries/AP_ICEngine/AP_ICEngine.h Outdated Show resolved Hide resolved
@TunaLobster TunaLobster force-pushed the pr-ICE-redline branch 3 times, most recently from 05922cd to fcdfd52 Compare April 11, 2022 23:51
@tridge
Copy link
Contributor

tridge commented May 2, 2022

@magicrub can you check the requested changes?

libraries/AP_ICEngine/AP_ICEngine.cpp Outdated Show resolved Hide resolved
libraries/AP_ICEngine/AP_ICEngine.cpp Outdated Show resolved Hide resolved
libraries/AP_ICEngine/AP_ICEngine.cpp Outdated Show resolved Hide resolved

if (redline.flag && !(options & uint16_t(Options::DISABLE_REDLINE_GOVERNOR))) {
// limit the throttle from increasing above what the current output is
const float incoming_throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);
Copy link
Contributor

Choose a reason for hiding this comment

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

I'm not a fan of this method. I'd rather see throttle_override() pass in the current throttle and let it override it. Even this bool result doesn't rub me right, just have it return the same value instead of. I think I've already done this on a branch for AION somewhere but not sure how much we ended up using and/or getting merged. (I feel like I've re-written this library like 5 times, I have so many variants of it in my head)

Copy link
Contributor Author

Choose a reason for hiding this comment

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

The bool for servos.cpp? throttle_override() does get the current throttle input. update_idle_governor() changes the min_throttle value. Are you thinking this should be written to change the aparm.throttle_max value?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Changed the throttle override to pass in current throttle value rather than zero. Costs a little more in time for all loops now.

libraries/AP_ICEngine/AP_ICEngine.h Outdated Show resolved Hide resolved
Copy link
Contributor

@magicrub magicrub left a comment

Choose a reason for hiding this comment

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

Ok.. I'm a approving it because it's a feature we need and it works OK as-is but what I'd like to see if a follow-up PR that moves rpm_filter stuff up into AP_RPM and maybe even some of the GCS/flag things. Not sure about the param.. but maybe that too. Needs discussion.

@magicrub magicrub merged commit 53a5043 into ArduPilot:master May 26, 2022
@Hwurzburg Hwurzburg removed the WikiNeeded needs wiki update label Jun 26, 2022
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

7 participants