2
$\begingroup$

Good day,

I am currently creating an autonomous quadcopter using a cascading PID controller specifically a P-PID controller using angle as setpoints for the outer loop and angular velocities for the inner loop. I have just finished tuning the Roll PID last week with only +-5 degrees of error however it is very stable and is able to withstand disturbances by hand. I was able to tune it quickly on two nights however the pitch axis is a different story.

Introduction to the Problem: The pitch is asymmetrical in weight (front heavy due to the stereo vision cameras placed in front). I have tried to move the battery backwards to compensate however due to the constraints of the DJI F450 frame it is still front heavy.

In a PID controller for an asymmetrical quadcopter, the I-gain is responsible for compensating as it is the one able to "remember" the accumulating error.

Problem at Hand I saw that while tuning the pitch gains, I could not tune it further due to irregular oscillations which made it hard for me to pinpoint whether this is due to too high P, I or D gain. The quadcopter pitch PID settings are currently at Prate=0.0475 Irate=0.03 Drate=0.000180 Pstab=3 giving an error from the angle setpoint of 15degrees of +-10degrees. Here is the data with the corresponding video.

RATE Kp = 0.0475, Ki = 0.03, Kd = 0.000180 STAB Kp=3 Video: https://youtu.be/NmbldHrzp3E

Plot: enter image description here

Analysis of Results It can be seen that the controller is saturating. The motor controller is currently set to limit the pwm pulse used to control the ESC throttle to only 1800ms or 180 in the code (The maximum is 2000ms or 205) with the minimum set at 155 or 1115ms (enough for the quad to lift itselft up and feel weightless). I did this to make room for tuning the altitude/height PID controller while maintaining the throttle ratio of the 4 motors from their PID controllers.

Is there something wrong on my implementation of limiting the maximum throttle?

Here is the implementation:

 //Check if PWM is Saturating - This method is used to fill then trim the outputs of the pwm that gets fed into the gpioPWM() function to avoid exceeding the earlier set maximum throttle while maintaining the ratios of the 4 motor throttles. 
    float motorPWM[4] = {motorPwm1, motorPwm2, motorPwm3, motorPwm4};
    float minPWM = motorPWM[0];
    int i;
    for(i=0; i<4; i++){ // Get minimum PWM for filling
        if(motorPWM[i]<minPWM){
            minPWM=motorPWM[i];
        }
    }

    cout << " MinPWM = " << minPWM << endl;

    if(minPWM<baseThrottle){
        float fillPwm=baseThrottle-minPWM; //Get deficiency and use this to fill all 4 motors
        cout << " Fill = " << fillPwm << endl;
        motorPwm1=motorPwm1+fillPwm;
        motorPwm2=motorPwm2+fillPwm;
        motorPwm3=motorPwm3+fillPwm;
        motorPwm4=motorPwm4+fillPwm;
    }

    float motorPWM2[4] = {motorPwm1, motorPwm2, motorPwm3, motorPwm4};
    float maxPWM = motorPWM2[0];
    for(i=0; i<4; i++){ // Get max PWM for trimming
        if(motorPWM2[i]>maxPWM){
            maxPWM=motorPWM2[i];
        }
    }

    cout << " MaxPWM = " << maxPWM << endl;

    if(maxPWM>maxThrottle){
        float trimPwm=maxPWM-maxThrottle; //Get excess and use this to trim all 4 motors
        cout << " Trim = " << trimPwm << endl;
        motorPwm1=motorPwm1-trimPwm;
        motorPwm2=motorPwm2-trimPwm;
        motorPwm3=motorPwm3-trimPwm;
        motorPwm4=motorPwm4-trimPwm;
    }

Possible solution I have two possible solutions in mind

  1. I could redesign the camera mount to be lighter by 20-30 grams. to be less front heavy

  2. I could increase the maximum throttle but possibly leaving less room for the altitude/throttle control.

Does anyone know the optimum solution for this problem?

Additional information The quadcopter weighs about 1.35kg and the motor/esc set from DJI (e310) is rated up to 2.5kgs with the recommended thrust per motor at 350g (1.4kg). Though a real world test here showed that it is capable at 400g per motor with a setup weighing at 1600g take-off weight

How I tune the roll PID gains

I had set first the Rate PID gains. at a setpoint of zero dps

  1. Set all gains to zero.
  2. Increase P gain until response of the system to disturbances is in steady oscillation.
  3. Increase D gain to remove the oscillations.
  4. Increase I gain to correct long term errors or to bring oscillations to a setpoint (DC gain).
  5. Repeat until desired system response is achieved

When I was using the single loop pid controller. I checked the data plots during testing and make adjustments such as increasing Kd to minimize oscillations and increasing Ki to bring the oscillations to a setpoint. I do a similar process with the cascaded PID controller.

The reason why the rate PID are small because rate Kp set at 0.1 with the other gains at zero already started to oscillate wildy (a characteristic of a too high P gain). https://youtu.be/SCd0HDA0FtY

I had set the Rate pid's such that it would maintain the angle I physically placed it to (setpoint at 0 degrees per second)

I then used only P gain at the outer loop stabilize PID to translate the angle setpoint to velocity setpoint to be used to control the rate PID controller.

Here is the roll axis at 15 degrees set point https://youtu.be/VOAA4ctC5RU Rate Kp = 0.07, Ki = 0.035, Kd = 0.0002 and Stabilize Kp = 2 enter image description here

It is very stable however the reaction time/rise time is too slow as evident in the video.

$\endgroup$
1
  • $\begingroup$ When this question was posted, a mistake can be seen in the video when doing the tuning. The thrust/base throttle that I've set when I tune the PID parameters was not enough and as said by Ian and Chuck, the quad is sitting on the strings which will cause a pendulum effect $\endgroup$ Mar 29, 2016 at 15:31

1 Answer 1

2
$\begingroup$

I feel like I make the same comments every time you ask a question about your controller:

  1. How are you tuning the gains?
  2. I think your slack line is interfering with your results.

Your quadcopter is not pulling on the slack line, it's sitting on it. This is introducing a floating inverted (unstable!) pendulum on system to your quadcopter. The motors aren't making enough thrust to lift the quadcopter because it's sitting on the tether.

That said, I think your statement,

I could not tune it further due to irregular oscillations

is revealing because I think that those oscillations are due to your tether. Not helping anything - you're pulling on the tether. So, extra forces your quadcopter shouldn't have to account for, that is being added to it:

  1. Spring force in the tether material itself.
  2. You are reacting to motion, so you're applying a time-varying force.
  3. The wooden pillar wobbles (I can see it at 34 seconds into your video), which is applying a time-varying force.

Your gains look very, very low, and I would be surprised that they're doing much of anything. To demonstrate, consider the quick simulation I ran in Simulink:

PID Loop

PID Output

The second figure above is the output of a step response to a PID controller with your PID gains. It is far too slow of a response for you to get meaningful control of an aerial vehicle.

So, I reiterate: How are you tuning the gains? I suggested a couple months ago a method you could you to do your tuning. I would expect your gains to be probably 100x larger than they are. Kp somewhere about 10-20 maybe, Ki at 5 or 10% of that, maybe 1 or 2, and Kd maybe 25% of the Ki gain, somewhere maybe 0.25 or 0.5. Those gains would look more along the lines of what I would expect, at least.

:EDIT:

I forgot to add that it does not look like anything is saturating. Your motors never appear to hit a sustained full-speed output and your integral error never reaches a point where it is clipped, either.

$\endgroup$
3
  • $\begingroup$ As a comment - Zeigler-Nichols relies on getting to the ultimate gain (oscillations) based on the gains and gains alone - i.e., oscillations from a tether don't count. $\endgroup$
    – Chuck
    Feb 25, 2016 at 14:39
  • $\begingroup$ I have made edits in the post to address the questions on how I tune my PID's $\endgroup$ Feb 25, 2016 at 15:30
  • $\begingroup$ So, basically I should increase my minimum thrust and my maximum thrust? I also followed Ian's advice to move the pivot as close as possible to the center of lift. I also increased the tensions on the lines before and I saw noticable improvements while tuning $\endgroup$ Feb 25, 2016 at 15:32

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge that you have read and understand our privacy policy and code of conduct.

Not the answer you're looking for? Browse other questions tagged or ask your own question.