Feedback linearization
Most robots are nonlinear. Most controllers prefer linear. Feedback linearization is the trick that turns nonlinear robots into linear ones — for free, on the inside — so you can apply LQR or PID on top.
Robot dynamics are nonlinear. Coupling between joints, gravity that depends on configuration, Coriolis terms — none of it linear. Most control theory you'll learn (LQR, MPC, PID) is built for linear systems. Feedback linearization is the bridge: cancel the nonlinear terms with a clever inner controller, leaving a linear system to control with anything you like.
The setup
The standard rigid-body manipulator dynamics:
Where:
- = vector of joint angles
- = mass / inertia matrix (positive-definite, depends on configuration)
- = Coriolis and centrifugal forces
- = gravity torques
- = joint torques (the control input)
This is nonlinear. M, C, and g all depend on the current state. Apply a torque, get a complicated change in motion. PID per joint kinda works but fights the coupling.
The trick: solve for τ
Pick the torque that makes the joints accelerate exactly the way you want:
Substitute back into the dynamics:
The C and g terms cancel; M is invertible (positive-definite); we get:
That's a linear, decoupled system. n independent double integrators. You can control each joint as if it were a frictionless point mass on a track. Apply LQR, PID, MPC — anything you like — to design u.
What you bought, what you paid
Bought:
- Linear, decoupled dynamics. PID per joint actually works correctly.
- Same controller works in any configuration — gravity and inertia variations are pre-cancelled.
- Composable: stack any high-level controller (trajectory tracking, impedance) on top.
Paid:
- Need a model of M, C, g. Wrong model → cancellation incomplete.
- Need joint velocities and accelerations (or to estimate them).
- Need fast control rates (1+ kHz) — feedback linearization assumes the inner loop closes faster than the outer loop dynamics.
A worked example: 2-link planar arm
For a 2-link planar arm with link masses m₁, m₂ at lengths L₁, L₂:
The mass matrix changes with θ₂ — when the arm is folded vs extended, its inertia is different. Coriolis and gravity terms similarly depend on configuration.
Without feedback linearization, a PID tuned for one configuration over- or under-shoots in others. With feedback linearization, the same PID gains work everywhere.
Implementation in code
def control_step(theta, theta_dot, theta_des, theta_dot_des, theta_ddot_des, dt):
# Compute model terms for current configuration
M = mass_matrix(theta)
C = coriolis_matrix(theta, theta_dot)
g = gravity_torques(theta)
# Outer-loop control law in the "linear" world
err = theta_des - theta
err_dot = theta_dot_des - theta_dot
u = theta_ddot_des + Kp @ err + Kd @ err_dot
# Inner-loop: choose torques that produce the desired acceleration
tau = M @ u + C @ theta_dot + g
return tau
Twenty-five lines. Run at 1 kHz. The robot tracks any reference trajectory cleanly, regardless of configuration.
The model-error gotcha
Real robots aren't exact rigid bodies. Friction, joint stiction, motor torque ripple, link flexibility — all unmodeled. If the cancellation is imperfect, the "linear" inner loop has residual nonlinearities, and the outer PID has to absorb them.
Two pragmatic mitigations:
- Identify the model: estimate M, C, g parameters from data. System identification is the term.
- Robust outer loop: use a controller that tolerates residual disturbances. Sliding-mode, or a PID with high enough integral gain.
Where this lives in modern stacks
- Industrial arms (Franka, KUKA): the inner controller is feedback-linearized. The user-facing API operates on the linearized "double integrator" abstraction.
- Quadrotors: thrust-and-attitude inner loop linearizes the rotational dynamics; outer position controller is then linear (or LQR or MPC).
- Quadrupeds: whole-body controllers often use feedback-linearization-style cancellation for the joint-space task, with task-space PD on top.
When feedback linearization fails
- Underactuated systems: more degrees of freedom than actuators (e.g., a humanoid's whole-body, an acrobot). You can't cancel everything because you have fewer "knobs" than dimensions. Look up partial feedback linearization.
- Non-collocated control: the actuator and the thing you're trying to control are connected by a flexible link. Cancellation creates an unstable internal dynamics. Avoid.
- Unmodeled high-frequency dynamics: feedback linearization assumes you can change torque arbitrarily fast. With a slow actuator, the cancellation lags.
The Lyapunov-based alternative
For underactuated or strongly nonlinear systems, control engineers often skip feedback linearization and design controllers via Lyapunov analysis directly. The math is more involved (you construct an energy-like function and show its time-derivative is negative), but the controllers handle nonlinearity natively.
For most arms and quadrotors though, feedback linearization is the right tool — and it's the lens through which much commercial robotics control is written.
Exercise
Take a 2-link planar arm in MuJoCo (or any sim). First, control it with PD per joint, no feedback linearization — watch how tracking degrades when the arm extends vs folds. Now implement feedback linearization with the dynamics model. Same PD gains. Watch tracking become uniform across configurations.
Next
Impedance and admittance control — what to do when the robot has to make contact with the world. Position control breaks the moment the gripper touches anything; impedance control turns the arm into a programmable spring instead.
Comments
Sign in to post a comment.