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

Copter: Throttle Pid Attenuation (TPA) #1261

Closed
sevet opened this issue Jul 27, 2014 · 26 comments
Closed

Copter: Throttle Pid Attenuation (TPA) #1261

sevet opened this issue Jul 27, 2014 · 26 comments

Comments

@sevet
Copy link

sevet commented Jul 27, 2014

Will it be possible to add TPA like feature to Arcucopter?

This feature exist on Multiwii and Baseflight,
Basically It's a dynamic PID dampener active between half and full throttle.

This eliminates oscillations when giving too much throttle, on some frames (Mini 250 frames for example) this is really necessary, as the alternative is to lower the PIDs in advance and have a less accurate/wobbly vehicle so that when you throttle it won't oscillate

@rmackay9 rmackay9 changed the title Throttle Pid Attenuation (TPA) Copter: Throttle Pid Attenuation (TPA) Jul 29, 2014
@Ju1ien
Copy link
Contributor

Ju1ien commented Aug 13, 2014

I had this somewhere in mind, nice to see ideas crossing here!
I would rather suggest TPA (Throttle PID adaptation) as you need as well to compensate low throttle during descents to try and eliminate oscillations.
Basically, auto PID adjustment would be the right solution, no need to run special autotune, the copter would autolearn during flights... but it's MUCH easier to say than to do.

@teslahed
Copy link

teslahed commented Nov 8, 2014

Just a quick note to say; Throttle PID Attenuation is vital for smaller frames and the (currently fashionable) mini quads that lots of people are now flying. With the new mini APM boards available it should be possible to get these aircraft flying with an APM but it's not worth doing until TPA is available. It makes such a big positive difference to the way some of these smaller quads fly. It would be a great feature to add.
On the Naze32 you can set the 'breakpoint' at which TPA kicks in so on more powerful aircraft you can have it kick in below 50% or on less above. If you had a sequence of breakpoints with different TPA values (including negative) then you could have your adaptable TPA feature and beat the Naze32 at it's own game :-)

@JSGordon
Copy link

A vote for this feature. As noted before smaller muliticopters and those flown more aggressively definitely benefit from variable PID's. Openpilot, Taus Labs and Naze32 variants have implemented this. Higher throttle rate effectively increases the mechanical gain of the system potentially resulting in instability during higher throttle flight and un-optimized PIDs at descent throttle rates.

@rotcehdnih
Copy link

Its a major issue for smaller frames with lots of power
some thing like

#define Usr_Tpa_Val 0.85f // TPA 85% gains or backed off 25%
orig_roll_rp = g.pid_rate_roll.kP();
pilot_throttle_scaled = get_pilot_desired_throttle(g.rc_3.control_in);
if (pilot_throttle_scaled > 500 ) {
TPA_roll_rp = orig_roll_rp * Usr_Tpa_Val;
g.pid_rate_roll.kP(TPA_roll_rp);
}

Please guys we need it bad , im pretty close to ditching my apm micro for a naze32 or something as the wobbles on throttle up are killing me

@lthall
Copy link
Contributor

lthall commented Feb 28, 2015

We will be including a throttle linearisation curve that is a significant improvement over TPA. However, this is only being included in the pixhawk release along with a bunch of other improvements to ACRO.

However, I have found that much of the oscillation we see in the pids isn't from this, it is from the dead zone at the top of the ESC range. If you calibrate your ESC with 10% more upper throttle you may find much of your oscillation go away. To do this I would set the radio with 10% higher throttle range to calibrate the esc and return it to the normal range to calibrate the APM.

@JSGordon
Copy link

This is one time where I would encourage at least investigating whether the upgrade can be made to the APM platform despite the known memory limitations. Or maybe a frame type firmware for a small quad t0 limit affecting firmware capability for larger craft not needing the feature.
Reason: This issue is most prevalent in the small multi-copter regime especially the small mini-quads used for racing and FPV. In general any very small quad flown aggressively or in fast forward flight. Many in this class are using some of the mini APM boards available because of the physical size limitations of the small craft. At the moment there is not a mini PixHawk available from 3DR or anyone else.

The work done elsewhere shows that even at lower levels of thrust that oscillation in small quads can happen even with a good amount of overhead allocated to stabilization. We make miniquads and it very evident on any platform NAZE, CC3D etc we use that attenuation at lower levels dramatically helps when in fast forward flight or with aggressive use of thrust. We use APM for more feature capable setups but the oscillation issue is a problem if used aggressively. We would use the a Arducopter platform more extensively if we could satisfy the more aggressive flight styles.

There is a significant section of the market moving to small aggressive copters. This may be a even larger market if there is a separate less strict ruling for less than 4.4 lb UAS by the FAA

@rotcehdnih
Copy link

@ lthall, i will try the esc calibration method and report back ,how much space does this new throttle linearisation take up ? could we drop autotune for the minis in favor for this or could we just add multiwii style tpa and leave it on 0% so no one would know it was there unless they needed it

[code]
// PITCH & ROLL only dynamic PID adjustemnt, depending on throttle value
if (rcData[THROTTLE] < cfg.tpa_breakpoint) {
prop2 = 100;
} else {
if (rcData[THROTTLE] < 2000) {
prop2 = 100 - (uint16_t)cfg.dynThrPID * (rcData[THROTTLE] - cfg.tpa_breakpoint) / (2000 - cfg.tpa_breakpoint);
} else {
prop2 = 100 - cfg.dynThrPID;
}
}

[/code]

might do more reading tomorrow night on what prop2 relates to and try adding it myself

@lthall
Copy link
Contributor

lthall commented Feb 28, 2015

I don't think there is the processing power to do it the way we have done it in the Pixhawk so the simple TPA is probably the only way we can do it.

The problem with the APM is there is a large work load to do a release and with all the new work being done on the Pixhawk everybody is flat out.

I would like to make some small changes to the APM code to incorporate my yaw control changes and add the TPA. Making time is the challenge.

@rotcehdnih
Copy link

ok i'll have ago at adding it then , but if you have the code to try im more then happy to build and test myself. about to go outside and try calibrating the esc's at 110% but am i correct in thinking if i've done radio calibration i should be able to set higher endpoints ,throttle up power on, power off, power on throttle down power off, reset endpoints & and all should be good yes?

@jschall
Copy link
Contributor

jschall commented Mar 1, 2015

We already have an interpolated throttle curve baked in. Currently only has
3 points, but you could add more.
On Feb 28, 2015 10:23 PM, "Hector Hind" notifications@github.com wrote:

ok i'll have ago at adding it then , but if you have the code to try im
more then happy to build and test myself. about to go outside and try
calibrating the esc's at 110% but am i correct in thinking if i've done
radio calibration i should be able to set higher endpoints ,throttle up
power on, power off, power on throttle down power off, reset endpoints &
and all should be good yes?


Reply to this email directly or view it on GitHub
#1261 (comment)
.

@lthall
Copy link
Contributor

lthall commented Mar 1, 2015

Hi rotcehdnih,
Yes that is correct.
Hi John,
I thought of that but it isn't a simple solution and it may be easer to remove it all together and add TPA.

@rotcehdnih
Copy link

Ok i gave that ago and it was marginally better , maybe 50% in fact however it did feel like i had lost a small amount of rpm from reviewing videos its hard to tell but i don't think 10% was all deadband.

the oscillation in on roll so i'll focus on tuning it better as there rough as guts
here's a peek
R.P 0.1200
R.I 0.1200
R.D 0.0100
R.IMAX 1800.0

@rotcehdnih
Copy link

Great news

my wobbles on throttle up are gone on 3s 5x3 👍 however now on decent its really bad "wobbles that is on roll and pitch " also it seems to yaw on decent aswell so ill have to look into that , ill need to tune in my 3s 6x4.5's and see how they feel and try 4s 5x3's aswell as it was really bad on those setups so all need very different tunes for example today on 3s 5x3 i was using 75-80w max throttle but on 3s 6x4.5 its more like 140-150 watts. & its a "zmr" so its top heavy to start with and i put spacers in to fit my esc's in the frame so its worse then normal but alot of people are doing mods like printing spacers ect that make there's look like a triple decker bus compared to mine

also while im here i see a lot of people complaining that the rate of rotation is still to slow even when its set to what they think is the max of 10 and there almost right is it way to slow for a mini quad but i bet most don't know they can set things out of range so ACRO_RP_P set to 13-19 is more what they want but think they cannot have so someone just need's to tell them ie in the wiki that values over 10 may be needed for acro mini quads

@lthall
Copy link
Contributor

lthall commented Mar 1, 2015

Hi all,
Can we open a thread on the forum on this. Github should be kept for bug a feature requests.

If someone can open a thread and post the link here that would be great. I will then answer all the questions I can over there.

I will do my best to get the dev's to do another release for the APM that has TPA and my yaw improvement. However, I will need testers!!!!!!

@JSGordon
Copy link

JSGordon commented Mar 1, 2015

We will gladly test !!!

@lthall
Copy link
Contributor

lthall commented Mar 1, 2015

I will need people to test everything, not just the ACRO, so the more help the better.

@thiagokern
Copy link

My APM 3.1 is about to arrive (It will be mounted on my ZMR 250). So in order to get this issue solved, I'm planning to mix the throttle and Chanel 6 on my radio (9x with Open TX). Then I'll set the Chanel 6 to lower the PIDs (on APM) when the throttle is on the on the high position. I'll try this until the TPA is added to the APM code =D.

What do you guys think, will it work?

@R-Lefebvre
Copy link
Contributor

Pretty sure this one is completed by Leonard.

@teslahed
Copy link

If it is completed, any chance you can clue us in as to where the setting is or what the variable name is in the full parameter list please?
Usuable TPA would be a MAJOR advantage to anyone flying a smaller high power miniquad. People will be talking about it all over various forums. I haven't seen any of that so if it's there is must be a secret! Help get the word out and there will be a lot of happy APM users :-)

@lthall
Copy link
Contributor

lthall commented May 16, 2015

It has been done and is working beautifully!

If you give me a list of locations that would like to see a write up I will put one together. There are a couple of features of interest to the fpv racers.

@teslahed
Copy link

Please start by telling me where the setting is here. Then i will know and i can tell other people and then they'll know too!
At the moment it's a bit frustrating to keep hearing people saying it works without anyone actually giving the useful information the rest of us need to use it...

@lthall
Copy link
Contributor

lthall commented May 16, 2015

This isn't the appropriate place for detailed instructions. I am on my mobile so don't have the parameter name on me. It all happens under the Mot_XXXXXX parameters.

If there isn't any discussions you can point me to then the next best thing is the post release wiki update. I think I have already put a brief description on the 3.3 thread. I might do a blog post on it too.

@teslahed
Copy link

When you get the chance later please come back and post the variable name. I don't need a detailed instruction. Just the actual variable name please.
The idea that we can talk about TPA in this thread but shouldn't actually go so far as stating the name of the single variable that solves the problem has to be some kind of bizare kafkaesque psychological torture!

@lthall
Copy link
Contributor

lthall commented May 16, 2015

It isn't done the same as TPa so it needs more explanation. It is also a much more thorough solution.

The variable is something like mot_thr_expo or _curve. But it is important to also specify the _maximum correctly.

@rmackay9
Copy link
Contributor

yes, we need to add wiki instructions for many of the new features in AC3.3.
Closing this issue.

@lthall
Copy link
Contributor

lthall commented May 17, 2015

There are 4 main parameters:
MOT_THST_BAT_MAX - Maximum battery voltage for gain scaling
MOT_THST_BAT_MIN - Minimum battery voltage for gain scaling
MOT_THST_EXPO - This is the throttle curve 0 is linear, 1 is x^2
MOT_THST_MAX - This is the maximum output sent to each esc 1 is 100%

The oscillations are caused by 4 main reasons.

  1. The first is that the dead band at the top of the throttle range causes oscillations because when the throttle is in this range it is like setting all the gains to zero. MOT_THST_MAX fixes this problem.
  2. The thrust vs throttle is not linear. It is somewhere between T = x and T = x^2. (T being Thrust and x being pwm output). This is what causes the gain of the pids to increase with throttle setting. It is also why decent wobbles are as bad as they are. MOT_THST_EXPO addresses this problem. The more efficient the prop the higher the number. 0.5 to 0.65 for 5 inch props depending on the brand, 0.65 for 10" APC props, 0.8 for larger quality props.
  3. Thrust and therefore PID gain increases with battery voltage. So on a fresh charge the copter might vibrate while at the end of the flight the pids start getting a little blunt. MOT_THST_BAT_MAX and MOT_THST_BAT_MIN are the battery voltage settings that limit how much the gain can be changed based on the battery voltage measured by the battery monitor.
  4. The yaw tune is a regular offender when it comes to gello and high frequency vibrations. The new Yaw controller has a filter setting that replaces the D term to account for the inertia of the motors and props. It is this inertia and instant response of the yaw controller that causes these very high frequency oscillations.

teslahed as you can see this isn't as simple as TPA because it is a much more complete solution. There are also a number of specific FPV racer features added to this release. So if you are aware of a place this discussion is taking place I would appreciate it if you would let me know so I can help those people get the most out of this code.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

No branches or pull requests

10 participants