Tuning a Vertical Elevator with Motion Profiling
In this section, we will tune a simple position controller for a vertical elevator. In addition, we will discuss the advantages of using motion profiling for this situation.
About the Profiler
A Motion Profiler is the software logic which, given a goal, commands a changing position, velocity, acceleration which are physically realistic for how a mechanism can move. These position/velocity/acceleration commands can be passed to feedforward and feedback controllers to cause the mechanism to actually achieve the commands.
In this specific example: We assume there are one or more fixed positions that our elevator needs to move to. The operator commands which position is desired.
In one periodic loop, the operator’s commanded position might instantly snap from one value to a different one. Naturally, we don’t expect the elevator to physically move that fast.
Since it is not physically plausible for the elevator to move in that manner, using a motion profiler is useful.
Constraining to realistic motion is a generally good principle for robust controls: don’t ask the physical system to do something it physically can’t. Having desired velocity and acceleration signals are also useful for supporting a more complex feedforward model.
The result is now two setpoint concepts: An “unprofiled” input setpoint which is allowed to change freely, and a “profiled” intermediate setpoint which is constrained to move in a more physically realistic manner.
Elevator Model Description
Vertical elevators are commonly used to lift gamepieces from the ground up to a scoring position. Other similar examples include shooter hoods and vertical arms.
Our “vertical elevator” consists of:
A mass on a carriage, under the force of gravity, traveling up and down in a constrained vertical path
A motor and gearbox driving a linear chain, to which the mass-on-a-carriage is attached
The simulation assumes the plant (the elevator itself) is controlled by motion profiling, feedforward and feedback controllers, composed in this fashion:
Where:
The plant’s output \(y(t)\) is the elevator’s height
The controller’s setpoint \(r_f(t)\) is the unprofiled, final desired height of the elevator
The Motion Profiler’s position setpoint \(r(t)\) is where the elevator should currently be positioned
The Motion Profiler’s velocity setpoint \(r'(t)\) is how fast the elevator should currently be moving
The Motion Profiler’s accelerator setpoint \(r''(t)\) is how fast the elevator should currently be accelerating
The controller’s control effort, \(u(t)\) is the voltage applied to the motor driving the elevator
Picking the Control Strategy for a Vertical Elevator
Applying voltage to the motor causes a force on the mechanism that drives the elevator up or down. If there is no voltage, gravity still acts on the elevator to pull it downward. Generally, it is desirable to fight this effect, and keep the elevator at a specific height.
The tutorials below will demonstrate the behavior of the system under just feedback (PID), and then combined feedforward-feedback with motion profiling control strategies. Follow the instructions to learn how to manually tune these controllers, and expand the “tuning solution” to view an optimal model-based set of tuning parameters. Even though WPILib tooling can provide you with optimal gains, it is worth going through the manual tuning process to see how the different control strategies interact with the mechanism.
Feedback Only Control
Interact with the simulation below to examine how the vertical elevator system responds when controlled only by a feedback (PID) controller.
Note
To change the elevator setpoint, click on the desired height along the vertical support.
Perform the following:
Set \(K_p\), \(K_i\), and \(K_d\) to zero.
Increase \(K_p\) until the mechanism responds to a sudden change in setpoint by moving sharply to the new position. If the controller oscillates too much around the setpoint, reduce \(K_p\) until it stops.
Increase \(K_i\) when the output gets “stuck” before converging to the setpoint.
Increase \(K_d\) to help the system track smoothly-moving setpoints and further reduce oscillation.
Note
Feedback-only control is not a good control scheme for vertical elevators! Do not be surprised if/when the simulation below does not behave consistently, even when the “correct” constants are used.
Tuning solution
There is no perfect tuning solution for this control strategy. Values of \(K_p = 10.0\), \(K_i = 2.5\) and and \(K_d = 0.0\) yield a possible solution, but with overshoot and large settling times. Additionally, it will act very differently depending on the setpoint - aggressively overshooting at the top and undershooting at the bottom.
Motion Profiled, Feedforward, and Feedback Control
Interact with the simulation below to initially examine how the elevator system responds when controlled only by a feedforward controller and then transition to using a little bit of feedback to correct any leftover error.
Note
To change the elevator setpoint, click on the desired height along the vertical support.
To tune the feedforward controller, perform the following:
Start with fairly slow maximum velocity and maximum acceleration. 0.3 for both is a good guess.
Set \(K_g\), \(K_v\), \(K_a\), \(K_p\), \(K_i\), and \(K_d\) to zero.
Increase \(K_g\) as much as you can without the elevator moving upward. You will have to zero in on \(K_g\) fairly precisely (at least two decimal places).
Increase the velocity feedforward gain \(K_v\) until the straight segments of the elevator actual motion have the same slope as the desired motion.
Increase the acceleration feedforward gain \(K_a\) until the curved segments of the elevator actual motion have the same curvature as the desired motion.
At this point, note how with no sensors involved, the elevator motion is fairly consistent. With the exception of a small amount of error, we are almost controlling the mechanism without issue.
Only as a last step, add in a bit of feedback gain.
Increase \(K_p\) until the actual position starts to overshoot the target, then back it off by 20%.
Finally, start to increase the maximum velocity and acceleration. Tweak your feed forward gains if needed.
Tuning solution
\(K_g = 2.28\), \(K_v = 3.07\), \(K_a = 0.41\), \(K_p = 2.0\) will behave quite well for a range of acceleration, velocities, and setpoints, even in the presence of system noise.
A Note on Feedforward and Static Friction
For the sake of simplicity, the simulations above omit the \(K_s\) term from the WPILib SimpleMotorFeedforward equation. On actual mechanisms, however, this can be important - especially if there’s a lot of friction in the mechanism gearing.
In the case of a vertical arm or elevator, \(K_s\) can be somewhat tedious to estimate separately from \(K_g\). If your arm or elevator has enough friction for \(K_s\) to be important, it is recommended that you use the WPILib system identification tool to determine your system gains.