Developer

3689498825?profile=original

Hi all,

I thought I would attempt to draw up a couple of diagrams of the PID loop in the ArduCopter 2.9 release.

3689498771?profile=original

Alt Hold Controller3689498721?profile=original

What we are trying to do with this controller is remove the need for the different stages of altitude changing that was in there before. This controller can handle both the altitude hold function as well as the fast altitude changes. We have tested it up to 5 m/s. This lets us do the very fast reduction in altitude I think you were asking for. It also does this with very little overshoot.

We use the square root of distance relationship to slow the airframe at reasonable accelerations to remove the very large accelerations that a linear distance vs velocity relationship applied. We took this one step further by combining the linear relation P loop with the square root relationship. This provides a smooth transition between the two modes in both acceleration and velocity.

The linear distance calculation is the distance that the square root relationship needs to be moved in order for the linear velocity relationship to be a tangent to the square root velocity relationship. This provides a step free transition between the two at the linear distance x 2. Acceleration of the two curves is also equal at this distance meaning that the motors don't pulse as we swap between the two curves.

 

The graph below is for the default Alt Hold parameters.

3689498850?profile=originalThe 250 cm/s/s is the maximum acceleration that will be required of the copter while still allowing the copter to stop without overshoot. The copter will not reach these accelerations unless it is instructed to travel over approximately 125 cm/s. This shouldn't happen during Alt Hold but can happen during Altitude changes. This limit was chosen because it should be achievable for all reasonably designed copters. To not be capable of this acceleration the copter would have a cruise throttle of over 700.

Using this controller you can still move the requested altitude slowly however if we need to stop or change direction it is able to still follow that request. In fact, the controller is not limited in the acceleration it can ask for. In an emergency this controller will be able to do it in less than 1 second and 2.5m. (I realize these are simple calculations and this situation only occurs if the user asks for stupid things).

We now have different speed limits for up and down but currently they are set to the same thing. We did this because the controller can now handle much faster rates so we didn't think we needed to limit it to such small values going down. I assume this was done for safety.

The final thing I should mention is the design of the controller with respect to the pid loops. This is a (P/sqrt) -> PD -> PI (Position -> Velocity -> Acceleration) controller by default. However, there may be advantages to using (P/sqrt) -> PD -> PID with correct filtering.

 So why no I term in position. This is because the I terms in these loops will reduce the following error when using this controller with a moving set point. The current design of the controller ensures that the distance between the moving altitude request and the current altitude is enough for the controller to stop the aircraft in that distance without accelerating beyond 250 cm/s/s. This is how we achieve such a small overshoot from very fast decent rates. This is also why we don't use an I term in the Velocity controller, we don't want overshoots due to I term build up.

The other parameter that is critical in this function is the velocity D term. This has the effect of minimizing the error between the requested velocity and the desired velocity during deceleration. This is set as large as it can be without noticing any jerkiness or oscillation during altitude changes.

 

I hope this helps people understand how a number of these control loops work.

Enjoy,

Leonard

E-mail me when people leave their comments –

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

Join diydrones

Comments

  • At Last !!!! Thank you man you are a start.

  • Didn't know any useful altitude information could be derived from the accelerometer.  Past work only got noise. 

  • Really nice Leonard.

    The relationships and inner workings of the various PIDs in the APM are not easy to understand and your illustration of how they fit together will make it easier for all of us.

  • Thank you for compiling this for us. 

  • I've actually created a full quad copter flight simulator in simulink.  Pretty cool once you get it going

  • Developer

    No, but I did use Matlab. I haven't found time to fully learn Simulink. It is on my to do list though :)

  • Was this done in simulink?

  • Excellent work.

    Thanks a lot Leonard

  • 3D Robotics

    Fantastic work on this, Leonard! It's something many people have asked for. We'll include it in the new manual.

This reply was deleted.