4
$\begingroup$

Good day,

I would like to ask why is it that when I add the Yaw control to my PID controller for each motor. The quadcopter refuses to take off or maintain its altitude. I am curently using a Cascaded PID controller for attitude hold using an Accelerometer, a Magnetometer and a Gyroscope, and a 40Hz Ultrasonic Sensor for Altitude Hold. Since the scope is indoor I have done away with the barometer due to its +-12m error.

Resulting Response

Without Yaw Control, the plot below shows the response of the quadrotor. enter image description here

With Yaw Control, the plot below shows the response of the quadrotor. enter image description here

Debugging

I found out that each of the outputs from each PID's give a too high of a value such that when summed together goes way over the PWM limit of 205 or Full Throttle.

  1. Without yawPID contribution The limiter kicks in without damaging the desired response of the system thus is still able to fly albeit with oscillatory motion along the z axis or height enter image description here enter image description here

    1. With yawPID contribution The added yaw components increases the sum of the PID's way above the limit thus the limiter compesates the excess too much resulting in an over all lower PWM output for all motors thus the quad never leaves the ground. enter image description here enter image description here

    //Motor Front Left (1) float motorPwm1 = pitchPID + rollPID + yawPID + baseThrottle + baseCompensation;

    //Motor Front Right (2) float motorPwm2 = pitchPID - rollPID - yawPID + baseThrottle + baseCompensation;

    //Motor Back Left (3) float motorPwm3 = -pitchPID + rollPID - yawPID + baseThrottle + baseCompensation;

    //Motor Back Right (4) float motorPwm4 = -pitchPID - rollPID + yawPID + baseThrottle + baseCompensation;

Background

The PID parameters for the Pitch, Yaw and Roll were tuned individually meaning, the base throttle was set to a minimum value required for the quadcopter to be able to lift itself.

The PID parameters for the Altitude Sensor is tuned with the other controllers active (Pitch and Roll).

Possible Problem

  1. Limiter algorithm

A possible problem is that the algorithm I used to limit the maximum and the minimum throttle value may have caused the problem. The following code is used to maintain the ratio of the motor values instead of limiting them. The code is used as a two stage limiter. In the 1st stage, if one motorPWM is less than the set baseThrottle, the algorithm increases each motor PWM value until none of them are below that. In the 2nd stage, if one motorPWM is more than the set maxThrottle, the algorithm decreases each motor PWM value until none of them are above that.

//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;
}

This was obtained from pixhawk. However the difference is that they employ only upper bound compensation limiting, while mine also performs lower bound compensation limiting which may cause more saturation once it reaches the second stage.

enter image description here From:https://pixhawk.org/dev/mixing

  1. Gains are set too high.

It is also possible that I've set my P gains too high thus exceeding the max RPM limit of the motors causing the Limiter algorithm to overcompensate.

Current PID Settings:

The minimum motor value for the quad to lift itself is 160 while the maximum limit is 200 from the PWM time high of 2000ms

  1. Pitch (Cascaded P-PID controller) Rate P = 0.07 Rate I = 0.03 Rate D = 0.0001 Stabilize P = 2
  2. Roll (Cascaded P-PID controller) Rate P = 0.09 Rate I = 0.03 Rate D = 0.0001 Stabilize P = 2
  3. Yaw (Cascaded P-PID controller) Rate P = 0.09 Rate I = 0.03 Rate D = 0.0001 Stabilize P = 2
  4. Hover (Single loop PD controller) P = 0.7 D = 35

Possible Solution

I think I have set the PID parameters particularly the P or D gain too high that the computed sum of the outputs of the controller is beyond the limit. Maybe retuning them would help.

I would just like to ask if anyone has encountered this problem or if you have any suggestions. Thank you :)

EDIT

I have added the plots of the response when the control loop is fast (500Hz) and Slow (300Hz)

500Hz: Does not fly enter image description here

300Hz: Flies enter image description here

$\endgroup$
8
  • $\begingroup$ How are you adding the yaw controller output to the motors? Are you assigning the values to the correct motors? $\endgroup$
    – Chuck
    Apr 14, 2016 at 10:06
  • $\begingroup$ @Chuck yup I have checked the response with the yaw controller only given a setpoint. It goes to the setpoint even when inflicting rotational disturbances along the yaw. I also checked the rotation of the propellers given a direction of rotation I want to go (CCW/CW). I am debugging my controller right now. I am checking the contributions of each component (motorPWM2 = pitchPID + yawPID - rollPID + basethrottle + altitudePID;) to see if it is going over the limit and overcompensating $\endgroup$ Apr 14, 2016 at 11:38
  • $\begingroup$ I'm no expert at this. There's not much between 160 min value and 200 max. In either case, you are constantly hitting the limit as I see it in your diagram. The more often you limit the controller value, the more it is actually limiter acting as a (nonlinear!) controller and not the controller itself. A limiter should kick in occasionally and not all the time. Strap a belt tightly around your breast and run a marathon. I'd try to use stronger motors so that your controller has enough air to do its job and not hit the limit so often. Only then try to control multiple variables. $\endgroup$ Apr 15, 2016 at 12:45
  • $\begingroup$ @Chuck May I ask what happens to the P gain contribution to the output if the speed of the control loop is decreased (dT increased). Does it have any significant effect like on the I and D gain which is time dependent (D decreases I increases). $\endgroup$ Apr 16, 2016 at 3:33
  • 1
    $\begingroup$ @user123456098 - If you're 15 meters from your target, how does that change if you measure it for an hour or a minute? It doesn't - time isn't a factor in a distance measurement. Similarly, time isn't a factor in a proportional measurement. You're not measuring the any rates when you're getting proportional error, so sample time doesn't matter for proportional error. $\endgroup$
    – Chuck
    Apr 18, 2016 at 11:59

1 Answer 1

1
$\begingroup$

disclaimer: This is more of a longer comment than an answer. I'm not sure what the problem is. There is a lot going on here (thankfully a lot of information is provided, too) and my attention shifted around from one thing to others.

my original thought

from the comments

There's not much between 160 min value and 200 max. In either case (with or without the yaw controller), you are constantly hitting the limit as I see it in your diagram. The more often you limit the controller value, the more it is actually the limiter acting as a (nonlinear!) controller and not the controller itself. A limiter should kick in occasionally and not all the time.

This is mostly based on how clearly the limit cuts down the PWM:

limited PWM

hence the following analogy came to my mind:

Strap a belt tightly around your breast and run a marathon.

And I concluded that:

I'd try to use stronger motors so that your controller has enough air to do its job and not hit the limit so often.

A stronger motor would not have run at full power and would not hit the limit so often. Hitting the limit is not bad in of itself. Imagine your PWM would be either at the upper or the lower limit. You'd have a (nonlinear) bang-bang controller. Such a controller isn't bad in of itself either, but it somewhat overrides the PID controller.

It can happen that you can manipulate the PID parameters at will and nothing changes. One reason for that can be a limit that makes your changes irrelevant. New parameters might change the output from 260 to 280 or to 220, which will have to effect if they are all going to be limited to 200. This is why constantly hitting the limit can be a bad thing.

With the yaw part, the phenomenon seems to be more pronounced, but not by much. I guess this is something to be aware of especially when summing up controller values, but not the actual problem.

Anyway, from the given diagrams I cannot tell why one would fly and the other would not.

500Hz -> 300Hz

Then another attempt was made and again one configuration works and the other does not.

I have tried to run the control loop at a slower rate and noticed that there is a drastic change in each of the PID components such that it is not exceeding the limit too much and now its flying again.

I tried to find differences between both diagrams. You are right, the limit is not exceeded as often as before in the flying operation. But what else is different?

May I ask what happens to the P gain contribution to the output if the speed of the control loop is decreased (dT increased). Does it have any significant effect like on the I and D gain which is time dependent (D decreases I increases)

Now I had a look at the separate controller error values. I combined them into the following image for comparison:

error values

The first thing that I notice is that there's a steady state error and thus $I_{error}$ constantly grows aka the red is the integral of blue and blue is bigger than zero all the time. This is not a good thing.

If there's a steady state error that the P gain cannot compensate, the integral part should grow and compensate the constant offset error.

The integral part should converge to some value. At least if it's compensating for a constant offset. I don't know what integral error from what controller this is, but an error that keeps growing is undesirable.

But maybe there is something inherently different between fly and nofly? The diagrams are a little hard to read because the axis are of different scale.

I tried to scale the images in gimp to fit and this is the result:

flynoflynofly

The pixelated plots are those two when it did not fly. Their overall $P_{error}$ is bigger and thus the $I_{error}$ is steeper.

But I don't think this is the problem. Look at the difference between the two $I_{error}$ of the cases when it flew. (the non-pixelated ones)

I'd say there's no other significant difference between the two cases.

conclusion

There's a constant error in the system. The controller cannot reduce that error. It looks as if the control loop is not closed properly.

Take a step back. Even in your first image, the height value oscillates and $I_{error}$ increases constantly. Inspect what's going on there.

Then create the angle controller separately. Put the quadcopter onto a pivot point or pole and see if it can maintain its angle. The height controller should be turned off.

When both controllers work on their own, try to combine both controllers in a weighted sum. $PID_{total} = 0.5 PID_{yaw} + 0.5PID_{height}$ Change the ratio as you see fit.

$\endgroup$
2
  • $\begingroup$ I changed my limiting algorithm to a threshold based one and retuned the PID's now it is flying again :) Thank you so much for you help. $\endgroup$ Apr 24, 2016 at 11:31
  • 1
    $\begingroup$ I found the culprit, it was the mounting of my sensor. When I screwed the sensor in place, the noise was minimized, the PID output was cleaner and no longer saturates. Now it flies beautifully with lateral drift which I plan to fix using X-Y position integration on the accelerometer and an optical flow sensor. The mounting was previously relying on a very soft foam which turns out introduces more vibrations as it was too soft (gels are more preferrable or orange foams from 3M). $\endgroup$ May 1, 2016 at 8:51

Your Answer

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

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