ZERO_PID Tunes for Multirotors Part#2

Introduction

 

                From more than a month from now Aug 2014, I posted a blog titled ZERO_PID Tune for Multicopter, It was about an algorithm I developed that allows quadcopter pilot to reset Gyro PIDs to ZERO, and fly! Using this algorithm, the quadcopter was able to generate valid values for P & I, and can successfully fly, the demo was on Multiwii code. Since then I was working on enhancing this algorithm, as I discovered some opportunities for improvment.

 Multiwii_GTune1.0.2.zip

First Version Issues

                 Although as you can see in the video that quadcopter really flies, there was a devil in the details. P-factor & I-factor would saturate if you fly long enough – I discovered this later few days after the video-. Although quadcopter was safely taking off, but flying for a long time -1 to 2 min- in this mode will make P & I saturate especially if you play with sticks hard.

Another issue I have discovered in the first version was calculating I-factor assuming it is a percentage of P-factor. Although it was calculated separately from P-factor, it ended up as a percentage of P-factor.

ZERO_PID Model

 

       Although my background is engineering, but I am not a big fan of mathJ, so I started to simplify the problem as much as possible, and avoid complex math. The model depends on angular velocity of gyros only. It assumes there is no interference between different axes –which is true theoretically at least- as actual Gyro MEMS has slight interactions between axes.  

3689610228?profile=original

       First, let us start by a quad arm with a motor on it as in the figure, initially the motor is running, but you do not know if it is running fast enough to generate exact thrust to keep the arm with angular velocity zero. Again let’s assume that the motor is not producing enough thrust, so when reading the gyro we will get V1 = v1. With single value you cannot judge, you need to read two values, so you wait until the next IMU loop and read V2=v2.

       Now assume that both V1 & V2 have the same signs. This means the same direction, which is falling down –counter clockwise in the figure-.

Condition#1:     If V2 > V1 : this means the arm is accelerating and the quad in danger of flip. So let us reduce the P value by one if the difference is high enough.

Condition#2:     If V2 < V1 : this means the arm is decelerating and the quad is trying to adjust itself to reach angular velocity zero. However there is a danger here that the deceleration is so fast so that it will not only stop the arm but will move in the other direction and start oscillations. So let’s decrease P value by one if the difference is high enough.

Please note that by design, quad stability is active stability, i.e. you need to monitor and adjust to keep it stable, so whatever the P value is, it will oscillate, the idea here is the oscillation amplitude should be minimal.

Condition#3: What if V1 & V2 has different signs, i.e. our quad arm has reversed its rotation direction. This case is ignored as it will always happen due to oscillations as I mentioned in the previous paragraph. And we rely on condition 2 to minimize oscillations.    

What if the arm –in the figure- rotation direction is clockwise, in this case we are calculating the right arm that is falling down. That is why we use abs(Error) . So we always consider the falling arm.

ZERO_PID algorithm can be written now as follows:

void G_Tune (Error)  {

                If (Sign(Error) == Sign (OldError))

               {

                       If ((abs(Error) - abs (OldError)) > High_Enough _1) // we are falling down.
                      {

                           P = P + 1;
                      }

                      If ((abs(Error) - abs (OldError)) <  - High_Enough_2 ) // we may oscillate.
                     {

                         P = P - 1;
                     }

                }

               OldError = Error;

}

 

Simple :) and yet it works. Well almost :)

As we can see the above algorithm changes P-factor only. In the first version I used a parallel condition for I-factor that increases and decreases it with 0.1 steps. Later I discovered this was not the best approach.

 

Challenges

Algorithm idea looks simple; however we need to consider some points that affect the performance of the algorithm.

  1. Aerodynamic Factor:  The above algorithm updates OldError = Error, actually it is not reasonable to assume that applying the updated P factor once in the PID and read the very next value will reflect the instant correct response, we need to consider motor acceleration and deceleration, as well as frame/propellers inertia, a lot of factor that makes our assumption not solid enough.3689610274?profile=original In the first version I tried to use complementary filter, and give a large weight for the new value, however keeping the old values so that we can have idea of the average performance. However we still read the very next action and update P-factor after one read. In the latest version I have defined time_skip parameter that make sure that the algorithm is executed one time each ntimes of PID calls. See the figure, the curve are the values from gyro while the bar chart shows samples taken by the algorithm. In practice I found time_skip  from 7 to 20 i.e. 14ms to ms gives the correct response, out of this range the quad still flies but the model assumption is not valid and it either saturate or stay in Zero. For low value of time_skip it stays in zero because V2 – V1 is small and within a safe range so quad assumes that this is a normal speed. Also V2 in this case does not represent the effect of previous updated P. also when time_skip is high, quad reads random values with large difference, and in this case condition #1 wins and P saturates, also still this is a fake reading. So time_skip is a critical parameter, which works well as long as we are in this range 7 – 20.
  2. Taking-Off & Landing: When you land with your quadcopter, once the quad hit the ground –even smoothly-, you will be able to see sudden peeks on the accelerometer graph. It is more clear on the Acc-Z, and this means calculated P could be corrupted during take-off or landing especially. Handling this was relatively easy. I just added a condition not to calculate P when Thrust is less than one third throttle. So now you can land and then switch from G_Tune to ACRO mode, you don’t need to do that in the air, however you can still do it safely as in the first version.

     
  3. What is Error Input Parameter: PID takes Error as an input, error could be gyro reading as in hefnycopter firmware , or as in multiwii it is the difference between stick value and correspondent gyro, i.e. between aileron value and the x-axes gyro. In the first version as used the same Error value as in multiwii, but this was not very good, as it means that when you make sudden stick change it will give error and the algorithm will correct P accordingly, although the current P value could be enough and correct. First I tried to define high and low boundaries for Error values, but after more thinking I was convinced that we need to consider only gyro reading as an input, and leave stick for multiwii algorithm.  

     
  4. Condition #2: Please re-read that condition again “However there is a danger here that the deceleration is so fast so that it will not only stop the arm” there is a vague word “danger”. Well how can we know if the deceleration is healthy and arm is slowing down in a proper speed, or it is slowing down too fast, well I don’t J. I tried some ranges and I found thatHigh_Enough _2 should be 1.5 to 2 times larger than High_Enough _1. Lower value for High_Enough_2 will make P always ZERO which is logic. And high value of it will make P saturate as condition #2 is hardly achieved because of the large barrier value.

 

Calculating I-Factor

               

                As I mentioned in the beginning of this article, I was calculating I as a percentage of P. Well in an article about sensors & PIDs I mentioned that I component in PID for gyro is used for restoring, it acts as a memory, because it is based on many values not the most recent one as P or the difference as D. I think about I component as the DC current in a signal or as a trim in your TX. Try to fly in Acro mode with I factor equal to Zero, you will find that if you tilt your try then take your hand of the sticks it will not get back, if you add some values to I-factor, it will tend to restore itself. And this is obvious because the I-component –i.e. the integration value not the I factor value- that was accumulated to overcome your stick need to be reduced back to zero. To have this effect I used a simple average variable to calculate the average value of gyro readings in a time window, and if the value is not Zero –higher or lower than a certain range- I is incremented otherwise it is decremented.

 

A Workable Code

 

                I attached a working code, you can use it to fly in ACRO mode only, as I used other PID parameters to as ZERO_PIDs parameters in order to study the effects above.

 

                LEVEL_P: represents High_Enough _1

                LEVEL _I: represents High_Enough_2

                ALT_P: represents time_skip counts.

                ALT_I: represents number of samples used for averaging Error for calculating I factor.

Note: if you put value ALT_I = 0.01 this means actually 10, as the minimum value is 0.001 which is 1. Same for other values, for example LEVEL_P = 1.0 means 10 and value 0.1 means 1 as there is no 0.001 and this is the minimum value for P, so take care when you play with values.

 

My Samples

              These figures are taken from MultiWii EZ-GUI for 3 flights:

3689610073?profile=original

                 as we can see High_Enough_1 = 10 & High_Enough_2 = 15 works very nice. time_skip here is 10 and values that are read for averaging to calculate I-factor is 100.

                 as I increased High_Enough_2 to 20 P values started to raise, especially in the third trial where I played more aggressive with quad compared to the calm first two flights.

Final Notice

                Still everything is experimental, and try it on your OWN RISK, try to fly smoothly and dont take off suddenly, let it leave ground easy.

 Latest Code is Here

E-mail me when people leave their comments –

You need to be a member of diydrones to add comments!

Join diydrones

Comments

  • I have just updated the wobble detection, it is now based only on oscillation frequency.

    I made some measures that ended up that 30ms oscillation is the upper limit upon which P should be decreased.

    the saturation is far better by now.

    chk my githubif u r interested.

    HefnySco/Multiwii_GTune
    Implementation of ZERO_PID algorithm on multiwii. Contribute to HefnySco/Multiwii_GTune development by creating an account on GitHub.
  • I think his approach is related to: http://en.wikipedia.org/wiki/Lyapunov_stability

  • @Tobias Simon 

    thanks for sharing this link.....yes it seems that code tries to reach the same objective....

    I checked the link and found:

    kpTuningIntergrator += (float)_kp*2*error*_gamma*deltaTime; //Euler intergrator

    kdTuningIntergrator += (float)_gamma*error*derivative*deltaTime; //Euler intergrator

    kiTuningIntergrator += (float)2*error*_gamma*integrator*deltaTime; //Euler intergrator Sum(f(Xn)*h)

    seems it tries to update P & I & D and using almost the same formula, not as my code that updates P & I only using two different approaches for each parameter.

    Thanks,

    M. Hefny

  • This seems to be similar to: https://code.google.com/r/litho23-ardupilot/source/browse/libraries...

  • Crashpilot1000

    Hi, I added wobble detection here .

    It mainly detects speed change wave length and peaks, so wobbles are low frequency oscillation, with high amplitude.

    still need some tuning. I will keep u updated.

    thanks,

    M.Hefny

  • Thanks for correting that, but I was just searching the condition where P was reduced in your explanation :) . However both of your cases are needed and the has changed sign condition as well. And it works!!!

    Here is the working (P only) version of "harakiri" https://github.com/Crashpilot1000/TestCode3/commit/155670d3b8b048b1...

    Thank you very much!

    Cheers Rob

    First working Gtune implementation in Harakiri · Crashpilot1000/TestCode3@155670d
    Contribute to Crashpilot1000/TestCode3 development by creating an account on GitHub.
  • The oscillation should occur because of condition#2 where V2 is less that V1 and this deceleration can be fast enough to make V3 actually has another sign -change direction- and start oscillation.

  • Condition#1:     If V2 > V1 : this means the arm is accelerating and the quad in danger of flip. So let us reduce the P value by one if the difference is high enough.

    This is wrong in writing .... the algorithm increases this P as the quad will flip, the current P cannot resist the falling down of this arm. in this step we increase P... the algorithm already does that ,.... it was a typo error..

    sorry

     

  • Did some further testing and it seems like "Condition#1" can be omitted and replaced by the wobbledetection.

  • Hi MHefny! Thank you very much for considering some of the changes!

    Just flew my altered code and it seems very much that the SATURATION PROBLEM IS SOLVED !!! It's working like a charm now, started copter with too high pids and it oscillated - but not for long, P was adjusted very quickly.

    Basically I did two things.

    1. Cleaner gyro signal. Filtered the gyrodata without letting them go out of phase by chopping off more bits and averaging them during time_skip (I use ca 50ms so adjustments at 20Hz).

    2. You already solved the problem in YOUR explanation! I just added the case if polarity changed (wobble) substract P. So we have now 2 occasions when the P is lowered. Since the code likes to saturate anyway it is not a problem but the threshold has to be low enough (so a little filtering is needed imho). I will do futher testing. Maybe the wobbledetection is enough and "Condition#1:" can be eliminated (don't think so). Will test around and publish the code hopefully late in the evening or tomorrow.

    Cheers Rob

This reply was deleted.