ArduCopter: Changing from PI to PID to improve stability

Hi,

I changed the attitude control loop a little bit to achieve more stability. Rate control with a PID(T1) instead of a PI controller. Here I present the necessary changes in the code to do this.

Pro:

  1. Much more attitude stability
  2. Much faster response on disturbances or new setpoints

Con:

  1. You need to tune the control loop again after this change
  2. This change is experimental, it works for me but you do it on your own risk ;)


I'm starting from Software AC 2.1. First I modified the library "PID" to save calculating time. I saved the following floating point operations per call to "get_pid": 2 x division, 4 x multiplication. You can download the modified library here. Unzip it and put the folder "PID_fast" in the "libraries" folder.

In file "ArduCopter.pde":

Add this line to the includes:

#include <PID_fast.h>            // PID library

For the following 4 blocks, I post it like the diff you get in GIT. The "-" means that you should look for this line and remove it. Replace it with the following lines starting with the "+". Of cause, the lines in the code have no "-" or "+". It's just to show what to remove and what to add instead.

-                g.pi_rate_roll.reset_I();
-                g.pi_rate_pitch.reset_I();
+                g.pid_rate_roll.reset_I();
+                g.pid_rate_pitch.reset_I();

-            g.pi_rate_roll.kP(tuning_value);
-            g.pi_rate_pitch.kP(tuning_value);
+            g.pid_rate_roll.kP(tuning_value);
+            g.pid_rate_pitch.kP(tuning_value);
 
-            g.pi_rate_roll.kI(tuning_value);
-            g.pi_rate_pitch.kI(tuning_value);
+            g.pid_rate_roll.kI(tuning_value);
+            g.pid_rate_pitch.kI(tuning_value);
 
-            g.pi_rate_yaw.kP(tuning_value);
+            g.pid_rate_yaw.kP(tuning_value);

In file "Attitude.pde":

In function "get_stabilize_roll(int32_t target_angle)":
 
-    rate         = g.pi_rate_roll.get_pi(error, G_Dt);
+    rate         = g.pid_rate_roll.get_pid(error, G_Dt);

In function "get_stabilize_pitch(int32_t target_angle)":

-    rate         = g.pi_rate_pitch.get_pi(error, G_Dt);
+    rate         = g.pid_rate_pitch.get_pid(error, G_Dt);

In function "get_stabilize_yaw(int32_t target_angle)":


-        rate     = g.pi_rate_yaw.get_pi(error, G_Dt);
+        rate     = g.pid_rate_yaw.get_pid(error, G_Dt);

-    rate         = g.pi_rate_yaw.get_pi(error, G_Dt);
+    rate         = g.pid_rate_yaw.get_pid(error, G_Dt);

In function "get_rate_pitch(int32_t target_rate)":
 
-    target_rate = g.pi_rate_yaw.get_pi(error, G_Dt);
+    target_rate = g.pid_rate_yaw.get_pid(error, G_Dt);

In file "Parameters.h":

Increase the number after "static const uint16_t k_format_version" by one. Warning: This will make the APM erase your EEPROM and Log after flashing the new compiled firmware. So save your settings first! After this, you have to reload your settings and level the copter again.

Later on in the file:

-    k_param_pi_rate_roll = 235,
-    k_param_pi_rate_pitch,
-    k_param_pi_rate_yaw,
+    k_param_pid_rate_roll = 235,
+    k_param_pid_rate_pitch,
+    k_param_pid_rate_yaw,

-    APM_PI        pi_rate_roll;
-    APM_PI        pi_rate_pitch;
-    APM_PI        pi_rate_yaw;
+    PID_fast    pid_rate_roll;
+    PID_fast    pid_rate_pitch;
+    PID_fast    pid_rate_yaw;

-    pi_rate_roll        (k_param_pi_rate_roll,            PSTR("RATE_RLL_"),    RATE_ROLL_P,        RATE_ROLL_I,        RATE_ROLL_IMAX * 100),
-    pi_rate_pitch        (k_param_pi_rate_pitch,            PSTR("RATE_PIT_"),    RATE_PITCH_P,        RATE_PITCH_I,        RATE_PITCH_IMAX * 100),
-    pi_rate_yaw            (k_param_pi_rate_yaw,            PSTR("RATE_YAW_"),    RATE_YAW_P,            RATE_YAW_I,            RATE_YAW_IMAX * 100),
-
+    pid_rate_roll        (k_param_pid_rate_roll,            PSTR("RATE_RLL_"),    RATE_ROLL_P,        RATE_ROLL_I,        RATE_ROLL_D,        RATE_ROLL_IMAX * 100),
+    pid_rate_pitch        (k_param_pid_rate_pitch,        PSTR("RATE_PIT_"),    RATE_PITCH_P,        RATE_PITCH_I,        RATE_PITCH_D,        RATE_PITCH_IMAX * 100),
+    pid_rate_yaw        (k_param_pid_rate_yaw,            PSTR("RATE_YAW_"),    RATE_YAW_P,            RATE_YAW_I,            RATE_YAW_D,            RATE_YAW_IMAX * 100),

In file "config.h":

You have to add a few lines. Lines to add are indicated by "+". Other lines are for reference to find the right place.

 #ifndef RATE_ROLL_I
 # define RATE_ROLL_I         0.0
 #endif
+#ifndef RATE_ROLL_D
+# define RATE_ROLL_D         0.0
+#endif

 #ifndef RATE_PITCH_I
 # define RATE_PITCH_I        0 //0.18
 #endif
+#ifndef RATE_PITCH_D
+# define RATE_PITCH_D         0.0
+#endif

 #ifndef RATE_YAW_I
 # define RATE_YAW_I     0.0
 #endif
+#ifndef RATE_YAW_D
+# define RATE_YAW_D     0.0
+#endif

In file "system.pde":

-    Log_Write_Data(12, g.pi_rate_roll.kP());
-    Log_Write_Data(13, g.pi_rate_pitch.kP());
+    Log_Write_Data(12, g.pid_rate_roll.kP());
+    Log_Write_Data(13, g.pid_rate_pitch.kP());

Now, all changes are done. Now save your current settings of the APM, compile and load the code... You will find 3 new parameters (RATE_RLL_D, RATE_PIT_D and RATE_YAW_D) you can edit like any other mavlink parameter. These are the D-Terms for all rate control loops.


Testing and tuning:

Be really carefull, propellers are dangerous!  I do the tuning of the control loops while I hold the copter in my hand and try if it compensates the disturbances without overshot or oscillation. You should decide for yourself if cou can hold your copter in one hand while you throttle up and test the stability. Even small propellers can harm your fingers! If you want to proceed, I do it like this:

  1. Reload your last setup and level the copter.
  2. Set all parameters for stabilize STB_***_P and STB_***_I to zero.
  3. Set all parameters for rate control RATE_***_P, RATE_***_I and RATE_***_D to zero.
  4. Hold the copter with one hand, throttle up until it becomes weightless, then turn it. Nothing should happen, because all control loop parameters are zero. You have just manual throttle control.
  5. Increase the D-Terms and test again while holding the copter in your hand. Remember, it can't fly with most parameters set to zero. Increase the D-Term and test again, until you got some oscillation. Let's call the value you found 100 percent. Now reduce it to 50..70 percent. Do this for ROLL and PITCH.
  6. Proceed with the P-Terms. Increase and test until it gets unstable. Then reduce it to 50..70 percent of the original value.
  7. Set the I-Terms to 30..50 percent of the P-Terms. Test again. If it is unstable, reduce P and I and maybe D a little bit.
  8. Now go to the STABILIZE control parameters. Increase the P-Term. Now the copter should return to level position automatically. Increasing of the P-Term will lead to a faster return to level position after disturbance or also to a fast respond to the desired angle by pilot input. Find a value where the copter returns fast from a disturbance without overshot or oscillation.
  9. Always leave the STABILIZE I-Term STB_***_I zero in this controller configuration!
  10. For YAW you can leave the D-Term zero and use your previous settings for STABILIZE and RATE control. Or you tune it, but I didn't try it at YAW yet.
  11. If everything works well and the copter returns to level position after disturbance or pilot input without overshot or oscillation, then you can try to hover and fly carefully. Not before!

Here are some controller parameters from my Tricopter (80 cm from motor to motor, 1440 g in flight weight), the D-Terms are quite small:

STB_PIT_I,0
STB_PIT_IMAX,1500
STB_PIT_P,9
STB_RLL_I,0
STB_RLL_IMAX,1500
STB_RLL_P,9
STB_YAW_I,0
STB_YAW_IMAX,1500
STB_YAW_P,4

RATE_PIT_D,0.015
RATE_PIT_I,0.02
RATE_PIT_IMAX,1000
RATE_PIT_P,0.09
RATE_RLL_D,0.012
RATE_RLL_I,0.02
RATE_RLL_IMAX,1000
RATE_RLL_P,0.09
RATE_YAW_D,0.004
RATE_YAW_I,0.002
RATE_YAW_IMAX,500
RATE_YAW_P,0.5

It would be really nice, if other people try this modification. For me, it was a significant increase in stability.

Regards, Igor

Views: 4300

Tags: PI, PID, arducopter, attitude, control loops, stabilize, tricopter


3D Robotics
Comment by Chris Anderson on January 18, 2012 at 1:46pm

Igor: thanks again for the smart suggestions. The only way to get this in the official code is to work directly with the dev team. We'd love to have you! Please PM me your email address (inked to a Google account) and we'll sign you up.

Comment by Igor van Airde on January 18, 2012 at 2:24pm

Developer
Comment by jasonshort on January 18, 2012 at 3:42pm

Igor, the stabilize controller in 2.1 has a D component. I actually have a slightly better on in my current revision which is not yet on the Trunk.

Jason


Developer
Comment by Randy on January 18, 2012 at 6:11pm

Great post!  I'm happy to see the D term making a comeback!  I'm using a D term for the optical flow stuff as well.

You know there's actually already a PID library which could have been used.  In fact, we unfortunately currently have 3 libraries already!  APM_PIPID and AP_PID.  It's a side point but we should probably combine these into a single library with multiple controllers inside the library.

Comment by Igor van Airde on January 18, 2012 at 11:43pm

@Jason: In ArduPlane, there is a PID, in ArduCopter 2.1, I can't find any usage of a PID libraby or any parameter related to a D term you can change via mavlink. Where is the D component you mention?

@Randy: I know. But the PID library had more functionality then I needed. I changed it to save floating point divisions. One bigger lib is a good idea of cause.

@All: lets do the discussion in this forum...

Comment by robert bouwens on January 19, 2012 at 4:31am

@jason

excuse me, there is no d term.

intentionally it might, but:

// D term

// I had tried this before with little result. Recently, someone mentioned to me that

// MultiWii uses a filter of the last three to get around noise and get a stronger signal.

// Works well! Thanks!

int16_t d_temp = (rate_d1 + rate_d2 + rate_d3) * g.stablize_d;

to me this is not a differential term but a proportional term.

actually you where creating a pip controller :)

you can use a P, PI, PD or PID controller.

Comment by Igor van Airde on January 19, 2012 at 10:11am

Hi,

the int16_t d_temp = (rate_d1 + rate_d2 + rate_d3) * g.stablize_d; might work as a D-Term if rate_d1 is already a D-Term. It's just averaging the last 3 terms multiplied with g.stablize_d. Ist this from MultiWii?

Using a PID is a bad idea because of the large impuls responses to noise. For this reason you have to use a PIDT1 instead (low pass filter on the D). In the PID and PID_fast libraries there is a fixed 20 Hz lowpass implemented. So the correct name is PIDT1.

Not every controller will work. P and PD will never level the copter completely, because they can't make the control error zero. Only if you have a I term somewhere, the error becomes zero. So PI works, but is slower than PIDT1. 

I tried different control structures, and for the rate control, the PIDT1 is the best from all traditional controllers. Then for the attitude control you can use a P, nothing else. If you add I to the attitude control, it can oscilate because you connect a I controller to an I controller. D for attitude is nearly the same as P for rate, it doesnt help to have two times the P term.

Please try the difference, how fast reacting and how stable you can get your copter with PI and with PIDT1!

Comment by Jonathan M on January 19, 2012 at 11:14am

Can you post your setup and what tuning you have pre and post your control structure modification? It would provide a good baseline for those attempting to re-tune their quads with the PIDT1 control loops.

Also, have you tried this setup with loiter?  If so, any improvements noticed?

Thanks,
Jonathan

Comment by robert bouwens on January 19, 2012 at 11:40pm

hi igor,

the D-Term variant misess the division through g_dt. your version calculates the d-term correctly as well as older implementations. jason did remove the pidt1 calculation because he didn't like it.

i have to admit that i removed the integral term on the dcm side.

thus a pid controller is not a bad idea.

once i told a mikrokopter.de that i use a pi controller - he answered why using the i-term, he use a pidt1 element and his copter was absolutley level.

you have to look at the dcm data - the data already shows an oscilating tendence. doing  so you can explain the  sinusoidale swing of an arducopter in the air. try also to generate step response diagram for the dcm filter.

 


Developer
Comment by Marco Robustini on January 20, 2012 at 4:15am

Hi Igor! I applied your changes to the release AC 2.2ß2XP2 and testing with sim.
I believe that reintroducing the "D-Term" is a very positive thing, if Mikrokopter using this system there must be an obvious reason, and everyone knows how to fly a MK... :-)
I think it still needs to create a multiplier because they work with parameters that vary from "0,001" to "0.015" is inaccurate and not easy for better D-term tuning.

Comment

You need to be a member of DIY Drones to add comments!

Join DIY Drones

Social Networking

Contests

Season Two of the Trust Time Trial (T3) Contest has now begun. The fourth round is an accuracy round for multicopters, which requires contestants to fly a cube. The deadline is April 14th.

A list of all T3 contests is here

Advertisement

© 2013   Created by Chris Anderson.   Powered by

Badges  |  Report an Issue  |  Terms of Service