Leonard's current limiting, voltage scaling and new thrust curve in master -- be careful!

608 views
Skip to first unread message

Randy Mackay

unread,
Mar 3, 2015, 2:07:48 AM3/3/15
to drones-...@googlegroups.com, leonar...@gmail.com

 

     As discussed on the dev call, Leonard’s current limiting, battery voltage scaling (for roll, pitch, yaw) and new thrust curve are in master.  This is the first batch of changes from Leonard, there’s another batch related to autotune for yaw coming within the next week.

 

     The relevant parameters are:

 

          Current limiting

          MOT_CURR_MAX (default 0=disabled): maximum allowed current in amps.  For example I set this to 20 on my IRIS+ and now when I push the throttle to full in stabilize mode it initially draws up to perhaps 25amps but quickly drops back to a steady 20amps where it stays from then onwards.

 

          Battery Voltage Scaling

          MOT_THST_BAT_MAX (default 0=disabled):  maximum expected battery voltage (i.e. 13V for 3S).  Roll, pitch and yaw gains are scaled so that the vehicle will feel like it’s at this voltage even when it has dropped much lower.

          MOT_THST_BAT_MIN (default 0=disabled): minimum expected battery voltage (i.e. 10V for 3S).  Voltage gains will not be scaled up any further even if the battery voltage drops below this level.

 

          Thrust curve parameters

          MOT_THST_EXPO (default 0.5): controls shape of pwm->thrust curve.  0 = linear, 1 = very curved.  See attached pics for examples of shape of curve.

          MOT_THST_MAX (default 0.95): place where ESCs “top out” (i.e. ESCs don’t produce any additional thrust at very top of their range)

 

          Attitude vs throttle mixing

          MOT_THR_LOW_CMP (default 0.5) : controls who is favoured when the stability patch needs to decide between the pilot/autopilot throttle input vs the roll/pitch attitude controller.  A very low number favours the pilot’s input and leads to better landings but could result in a flip during aggressive maneuvers in which the pilot pulls the throttle low.  A very high number favours the attitude controller which leads to a bounce when landing but very solid attitude control even when throttle is low.  We don’t expect people to change this.

 

-Randy

MotThstExpo_graphs.png

Leonard Hall

unread,
Mar 3, 2015, 6:42:47 AM3/3/15
to drones-...@googlegroups.com, leonar...@gmail.com
Hi all,

Be careful as high powered copters with low hover throttle settings will tend to have higher rate gains that maybe unstable. This may cause oscillation on be careful on your first take off.

Battery Voltage Scaling

I tend to use 3.5 V/cell for minimum and 4.4 V/cell for maximum.
Like I mentioned above, this assumes your PID values are stable at your maximum voltage setting. If you set the maximum voltage to higher than your battery max voltage the code will assume you are flying on a flat battery and increase your pid gains to compensate. This may cause oscillation on be careful on your first take off.


Thrust curve parameters

I have analysed 122 thrust curves with different motor prop combinations ranging from 5" to 18". It works out that:
10" apc's use MOT_THST_EXPO = 0.65
Good quality 18" props MOT_THST_EXPO = 0.8 (but anything less expensive I would stick to 0.65)
5" props get a little ugly because the distortion of the props but for small floppy MOT_THST_EXPO = 0.65 and this is also the safe number.

Attitude vs throttle mixing

This is the one I am really interested in getting people to try during alt_hold land and auto land. I believe this will go a long way to fixing our landing detector issues.
Set MOT_THR_LOW_CMP = 0.5, This is the setting the the old code.
Set MOT_THR_LOW_CMP = 0.1, This will make the copter land like a wet towel on the bathroom flaw.
Set MOT_THR_LOW_CMP = 1.0, This should make the copter jump around like a jack rabbit. You will probably have to land in stabilize with this so be careful !!!!

My plan is to drop this down to 0.1 when we want to land. Say below 1/4 throttle in stabilize and Alt_Hold and while roll, pitch, and yaw are centred. If we are in land and lateral speed is below 0.25 m/s. After playing with this, any ideas and feedback would be great!!!

And as Randy said, be careful.

Robert Lefebvre

unread,
Mar 3, 2015, 8:54:07 AM3/3/15
to drones-discuss, Leonard Hall
Are any of these changes going to affect Tradheli accidentally?  I just had a quick look, I see most of them are in the MotorsMatrix, but some of them are in the "motors" parent class.

--
You received this message because you are subscribed to the Google Groups "drones-discuss" group.
To unsubscribe from this group and stop receiving emails from it, send an email to drones-discus...@googlegroups.com.
For more options, visit https://groups.google.com/d/optout.

Randy Mackay

unread,
Mar 3, 2015, 8:42:38 PM3/3/15
to drones-...@googlegroups.com, Leonard Hall

 

     I was careful to think about all the other vehicle types including tradheli so I think it’s ok.  None of the features will work for tradheli I suspect but if left disabled they should have no effect.

 

-Randy

Holger Steinhaus

unread,
Mar 7, 2015, 11:35:21 AM3/7/15
to drones-...@googlegroups.com, leonar...@gmail.com
Hi Leonard,

just flashed master on one of my copters, a well-powered quad with 15" props, 8s battery and about 1kW peak power, at a takeoff weight around 2kg and did a short test flight. Everything worked very well, even though I did not have the guts to enable the voltage-based PID scaling or to try autotune yet. 

But I am wondering about a couple of things related to the battery resistance logging: 
1. the battery resistance seems to be updated only in manual-throttle flight modes (see attachment).
2. the resistance seems to be rising all the time it is beeing logged - I would expect the opposite, as I did not pre-warm the batteries, and they should heat up during flight.

The log of my flight is available here: https://www.dropbox.com/s/52py7b0ttoqj5tj/35.BIN?dl=0

BTW, during this flight a second baro (UAVCAN) was installed.

Holger

Holger Steinhaus

unread,
Mar 7, 2015, 11:42:46 AM3/7/15
to drones-...@googlegroups.com, leonar...@gmail.com
Here is the promised attachment.

Holger
resistance.png

Leonard Hall

unread,
Mar 7, 2015, 8:04:32 PM3/7/15
to drones-...@googlegroups.com, leonar...@gmail.com
Hi Holger,

There are three phases of battery impedance measurement. The first is to establish a resting voltage and current and the second is to estimate the battery impedance and the third is where we assume battery impedance is constant and it is the cell voltage is dropping.

In the motor matrix this information is used to approximate the instantaneous resting voltage (zero current) off the battery. This voltage is then used to adjust the gains of the control loops to ensure constant response as the battery depletes.

The resting voltage and current is measured every time the copter is armed. 

After this the battery resistance is calculated to keep the voltage estimate constant until the copter reaches hover throttle. PID gains are calculated based on the initial resting voltage and therefore don't change.

Once Hover throttle is reached there is a 1 second period where the battery impedance is averaged (using a filter)  and after this it is kept constant. From this point on the batter voltage is estimated as:
Vrest = Vmeas+Imeas*Resistance.

Vrest is then used to scale the gains of roll, pitch, and yaw using the formulae:
lift_max = Vrest *(1-_thrust_curve_expo) + _thrust_curve_expo*Vrest .^2;

Gain scaling term is 1/lift_max  and _thrust_curve_expo is between 0.5 and 0.8 and defines the lift vs pwm (or voltage) curve.

So once the value for Resistance is fixed you can use this to approximate your battery pack condition. However, as you point out the resistance changes a little as the pack discharges and the estimation of pack resistance happens after the copter is armed.

Hope this makes sense.

Leonard

Luis Vale Gonçalves

unread,
Mar 8, 2015, 11:16:17 AM3/8/15
to drones-...@googlegroups.com, leonar...@gmail.com
Leonard

Do you know this document??


brgds

Luis

Jonathan Challinger

unread,
Mar 8, 2015, 6:39:27 PM3/8/15
to drones-...@googlegroups.com

I am working on a kalman filter to estimate battery resistance and resting voltage.

--

Leonard Hall

unread,
Mar 9, 2015, 2:13:01 AM3/9/15
to drones-...@googlegroups.com, leonar...@gmail.com
Thanks for the link Luis!!

I will have a good read.

Luis Vale Gonçalves

unread,
Mar 9, 2015, 11:33:18 AM3/9/15
to drones-...@googlegroups.com, leonar...@gmail.com
I was reading that doc when some months ago on the smart battery discussion I began implementing a way to estimate battery lifetime, but I was using a script on the radio to do it, but the scripting capabilities of the radio won't allow the necessary calculations to be done. 

Now, if one of the Stochastic models could be implemented on the APM, that would be a completely different scenario :)

brgds

Luis

Ilyas Demir

unread,
Jun 3, 2015, 10:16:47 AM6/3/15
to drones-...@googlegroups.com, leonar...@gmail.com
Hello Leonard Hall, Thank you allot for you create work for AC 3.3 i love you Improvements really very much.

i have one Question its very similar to you work voltage scaling and Thrust curve parameters

its Possible that if the Battery Full, the max pwm Throttle  to the Esc will be also Reduce like the dynamical Pid and if the Battery empty or because Voltage drop under Load the maximum throttle MOT_THST_MAX  range will be given to the Esc?

in my case: if my liio Battery have full 14,1 Volt 
but in the Load Condition and not complete full it has ~11 Volt

and i will buy/chose the Prop/esc/motor to the ~11 Volts but if not All Motors have the same Load like if i flip...>the Voltage Drop is Low and my Battery is full it will destroy my esc/Motors because with full throttle it give much more current in this specific situation than calculate before.

and the nice thing to, that you have the complete time the same Power Lifting capacity of the full range of the Battery.

thanks you.
greats ilyas from germany.
Reply all
Reply to author
Forward
0 new messages