Algorithms for Walking, Running, Swimming, Flying, and Manipulation
© Russ Tedrake, 2024
Last modified .
How to cite these notes, use annotations, and give feedback.
Note: These are working notes used for a course being taught at MIT. They will be updated throughout the Spring 2024 semester. Lecture videos are available on YouTube.
Previous Chapter | Table of contents | Next Chapter |
The passive dynamic walkers and hopping robots described in the last chapter capture the fundamental dynamics of legged locomotion -- dynamics which are fundamentally nonlinear and punctuated by impulsive events due to making and breaking contact with the environment. But if you start reading the literature on humanoid robots, or many-legged robots like quadrupeds, then you will find a quite different set of ideas taking center stage: ideas like the "zero-moment point" and footstep planning. The goal of this chapter is to penetrate that world.
Perhaps one of the most surprising thing about the world of complex (highly-articulated) legged robots is the dominant use of simple models for estimation, planning, and control. These abstractions become valuable when you have enough degrees of freedom to move your feet independently (to an extent) from how you move your body.
Since our robots are getting more complicated, I'm going to need a bit stronger notation. In Drake we use monogram notation and define its spatial algebra here for kinematics, differential kinematics (velocities) and here for force.
Let's start the discussion with a model that might seem quite far from the world of legged robots, but I think it's a very useful way to think about the problem.
Imagine you have a flying vehicle modeled as a single rigid body in a gravity field with some number of force "thrusters" attached. We'll describe the pose of the body in the world frame, ${}^WX^B$, parameterized by its position $(x,z)$ and orientation $\theta$, and take the center of mass to be at the origin of this body frame. The vector from the center of mass to thruster $i$ in the world frame is given by ${}^Bp^{B_i}_W$, yielding the equations of motion: \begin{align*} m\ddot{x} =& \sum_i f^{B_i}_{W_x},\\ m\ddot{z} =& \sum_i f^{B_i}_{W_z} - mg,\\ I\ddot\theta =& \sum_i \left[ {}^Bp^{B_i}_W \times f^{B_i}_W \right]_y, \end{align*} where I've used $f^{B_i}_{W_x}$ to represent the $x$-component of the force applied to $B$ at the location of thruster $i$, expressed in the world frame, and we take the $y$-axis component of the cross product on the last line.
Our goal is to move the spacecraft to a desired position/orientation and to keep it there. If we take the inputs to be $f^{B_i}_W$, then the dynamics are affine (linear plus a constant term). As such, we can stabilize a stabilizable fixed point using a change of coordinates plus LQR or even plan/track a desired trajectory using time-varying LQR. If I were to add additional linear constraints, for instance constraining $f_{min} \le f^{B_i}_W \le f_{max}$, then I can still use linear model-predictive control (MPC) to plan and stabilize a desired motion. By most accounts, this is a relatively easy control problem. (Note that it would be considerably harder if my control input or input constraints depend on the orientation, $\theta$, but we don't need that here yet).
Now imagine that you have just a small number of thrusters (let's say two) each with severe input constraints. To make things more interesting, let us say that you're allowed to move the thrusters, so ${}^B\text{v}^{B_i} = \frac{d}{dt} {}^Bp^{B_i}$ becomes an additional control input, but with some important limitations: you have to turn the thrusters off when they are moving (e.g. $f^{B_i}{}^B_{W_j} \text{v}^{B_i}_{W_j} = 0$) and there is a limit to how quickly you can move the thrusters $|{}^B\text{v}^{B_i}_{W_j}| \le \text{v}_{max}$. This problem is now a lot more difficult, due especially to the fact that constraints of the form $xy = 0$ are non-convex (the red area in the illustration below represents the feasible set for $x \ge 0, y \ge 0$).
I find this a very useful thought exercise; somehow our controller needs to make an effectively discrete decision to turn off a thruster and move it. The framework of optimal control should support this - you are sacrificing a short-term loss of control authority for the long-term benefit of having the thruster positioned where you would like, but we haven't developed tools yet that deal well with this discrete plus continuous decision making. We'll need to address that here.
Unfortunately, although the problem is already difficult, we need a few more constraints to make it relevant for legged robots. Now let's say additionally, that the thrusters can only be turned on in certain locations, as cartooned here:
Even if the individual regions are convex, the union of these regions need not form a convex set. Furthermore, these locations are often expressed in the world frame, not the robot frame, e.g. $${\bf A}\, {}^W p^{R_i}_W \le {\bf b}.$$
In my view, the spacecraft with thrusters problem above is a central component of the walking problem. If we consider a walking robot as our single rigid body, $B$, with massless legs, then the feet are exactly like movable thrusters. As above, they are highly constrained - they can only produce force when they are touching the ground, and (typically) they can only produce forces in certain directions, for instance as described by a "friction cone" (you can push on the ground but not pull on the ground, and with Coulomb friction the forces tangential to the ground must be smaller than the forces normal to the ground, as described by a coefficient of friction, e.g. $f^{B_i}_{C_z} \ge 0, |f^{B_i}_{C_x}| < \mu f^{B_i}_{C_z}$) where $C$ is the contact frame.
The constraints on where you can put your feet / thrusters will depend on the kinematics of your leg, and the speed at which you can move them will depend on the full dynamics of the leg -- these are difficult constraints to deal with. But the actual dynamics of the rigid body, $B$, are actually still affine, and still simple!
It turns out the specific equations that we used in our thought
experiment aren't restricted to a single body and massless legs. If we
simply repurpose the coordinates $x,z$ to describe the location of the
center of mass (CoM) of the entire robot (not just the center of mass of a
single body, $B$), and $m$ to represent the entire mass of the robot, then
the first two equations remain unchanged. The center of mass is a
configuration dependent point, and does not have an orientation, but one
important generalization of the orientation dynamics is given by the
centroidal momentum matrix, $A(\bq)$, where $A(\bq)\dot{\bq}$ captures the
linear and angular momentum of the robot around the center of mass
In the previous chapter we devoted relatively a lot of attention to dynamics of impact, characterized for instance by a guard that resets dynamics in a hybrid dynamical system. In those models we used impulsive ground-reaction forces (these forces are instantaneously infinite, but doing finite work) in order to explain the discontinuous change in velocity required to avoid penetration with the ground. This story can be extended naturally to the dynamics of the center of mass.
For an articulated robot, though, there are a number of possible strategies for the legs which can affect the dynamics of the center of mass. For example, if the robot hits the ground with a stiff leg like the rimless wheel, then the angular momentum about the point of collision will be conserved, but any momentum going into the ground will be lost. However, if the robot has a spring leg and a massless toe like the SLIP model, then no energy need be lost.
One strategy that many highly-articulated legged robots use is to keep their center of mass at a constant velocity, $$\dot{z} = c \quad \Rightarrow \quad \ddot{z} = 0,$$ and minimize their angular momentum about the center of mass (here $\ddot\theta=0$). Using this strategy, if the swinging foot lands roughly below the center of mass, then even with a stiff leg there is no energy dissipated in the collision - all of the momentum is conserved. This often (but does not always) justify ignoring the impacts in the center of mass dynamics of the system.
While not the only important case, it is extremely common for our robots to be walking over flat, or nearly flat terrain. In this situation, even if the robot is touching the ground in a number of places (e.g., two heels and two toes), the constraints on the center of mass dynamics can be summarized very efficiently.
First, on flat terrain $f^{B_i}_{W_z}$ represents the force that is normal to the surface at contact point $i$. If we assume that the robot can only push on the ground (and not pull), then this implies $$\forall i, f^{B_i}_{W_z} \ge 0 \Rightarrow \sum_i f^{B_i}_{W_z} \ge 0 \Rightarrow \ddot{z} \ge -g.$$ In other words, if I cannot pull on the ground, then my center of mass cannot accelerate towards the ground faster than gravity.
Furthermore, if we use a Coulomb model of friction on the ground, with friction coefficient $\mu$, then $$\forall i, |f^{B_i}_{W_x}| \le \mu f^{B_i}_{W_z} \Rightarrow \sum_i |f^{B_i}_{W_x}| \le \mu \sum_i f^{B_i}_{W_z} \Rightarrow |\ddot{x}| \le \mu (\ddot{z} + g).$$ For instance, if I keep my center of mass height at a constant velocity, then $\ddot{z}=0$ and $|\ddot{x}| \le \mu g$; this is a nice reminder of just how important friction is if you want to be able to move around in the world.
Even better, let us define the "center of pressure" (CoP) as the point on the ground where $$x_{cop} = \frac{\sum_i {}^Wp^{B_i}_{W_x} f^{B_i}_{W_z}}{\sum_i f^{B_i}_{W_z}},$$ and since all ${}^Wp^{B_i}_{W_z}$ are equal on flat terrain, $z_{cop}$ is just the height of the terrain. It turns out that the center of pressure is a "zero-moment point" (ZMP) -- a property that we will demonstrate below -- and moment-balance equation gives us a very important relationship between the location of the CoP and the dynamics of the CoM: \begin{equation} (m\ddot{z} + mg) (x_{cop} - x) = (z_{cop} - z) m\ddot{x} - I\ddot\theta. \label{eq:cop} \end{equation} If we use the strategy proposed above for ignoring collision dynamics, $\ddot{z} = \ddot{\theta} = 0$, and the result is the famous "ZMP equations": \begin{equation} \ddot{x} = g \frac{(x - x_{cop})}{(z - z_{cop})}. \label{eq:zmp} \end{equation} So the location of the center of pressure completely determines the acceleration of the center of mass, and vice versa! What's more, when $z - z_{cop}$ is a constant (the center of mass remains at a constant height relative to the ground) or following a predetermined schedule, the remaining relationship is affine -- a property that we can exploit in a number of ways.
As an example, we can easily relate constraints on the CoP to constraints on $\ddot{x}$. It is easy to verify from the definition that the CoP must live inside the convex hull of the ground contact points. Therefore, if we use the $\ddot{z}=\ddot\theta=0$ strategy, then this directly implies strict bounds on the possible accelerations of the center of mass given the locations of the ground contacts.
The zero-moment point (ZMP) is discussed very frequently in the current
literature on legged robots. It also has an unfortunate tendency to be
surrounded by some confusion; a number of people have defined the ZMP is
slightly different ways (see e.g.
First let us recall that for rigid body systems I can always summarize the contributions from many external forces as a single wrench (force and torque) on the object -- this is simply because the $F_i$ terms enter our equations of motion linearly. Specifically, the position $p^A$ of an arbitrary point $A$:
I can re-write the equations of motion as \begin{align*} m\ddot{x} =& \sum_i f^{B_i}_{W_x} = f^A_{net,W_x},\\ m\ddot{z} =& \sum_i f^{B_i}_{W_z} - mg = f^A_{net,W_z} - mg,\\ I\ddot\theta =& \sum_i \left[ {}^Bp^{B_i}_W \times f^{B_i}_W \right]_y = [{}^Bp^A_W \times f^A_{net,W}]_y + \tau^A_{net,W}, \end{align*} where $f^A_{net} = \sum_i f^{B_i}$ and the value of $\tau^A_{net}$ depends on the position, $p^A$. For some choices of $p^A$, we can make $\tau^A_{net}=0$. We'll call these points $\text{ZMP}$, for which we have \begin{equation} \left[ {}^Bp^{\text{ZMP}}_W \times f^{\text{ZMP}}_{net,W} \right]_y = {}^Bp^{\text{ZMP}}_{W_z} f^{\text{ZMP}}_{net,W_x} - {}^Bp^{\text{ZMP}}_{W_x} f^{\text{ZMP}}_{net,W_z} = \sum_i \left[ {}^Bp^{B_i}_W \times f^{B_i}_W \right]_y, \label{eq:zmp_def} \end{equation} we can see that whenever we have ground reaction forces ($f^{\text{ZMP}}_{net,W_z} \ne 0$) there is an entire line of solutions, ${}^Bp^{\text{ZMP}}_{W_x} = a\, {}^Bp^{\text{ZMP}}_{W_z} + b$, including one that will intercept the terrain. For walking robots, it is this point on the ground from which the external wrench can be described by a single force vector (and no moment) that is the famous "zero-moment point" (ZMP).
We can rewrite the equations of motion in terms of the ZMP. Substituting the equations of motion into equation \ref{eq:zmp_def}, to replace the individual terms of $f^{\text{ZMP}}_{net}$, we have \[ {}^Bp^{\text{ZMP}}_{W_z} m\ddot{x} - {}^Bp^{\text{ZMP}}_{W_x} (m\ddot{z} + mg) = I \ddot{\theta}. \] But this is precisely the equation \ref{eq:cop} presented above.
Furthermore, since \[\sum_i \left[ {}^Bp^{B_i}_W \times f^{B_i}_W \right]_y = \sum_i \left( {}^Bp^{B_i}_{W_z} f^{B_i}_{W_x} - {}^Bp^{B_i}_{W_x} f^{B_i}_{W_z} \right), \] and for flat terrain we have \[ \sum_i {}^Bp^{B_i}_{W_z} f^{B_i}_{W_x} = {}^Bp^{\text{ZMP}}_{W_z} \sum_i f^{B_i}_{W_x} = {}^Bp^\text{ZMP}_{W_z} f^\text{ZMP}_{net, W_x}, \] then we can see that this ZMP is exactly the CoP: \[ {}^Bp^\text{ZMP}_{W_x} = \frac{\sum_i {}^Bp^{B_i}_{W_x} f^{B_i}_{W_z}}{\sum_i f^{B_i}_{W_z} }. \]
In three dimensions, we solve for the point on the ground where $\tau^\text{ZMP}_{net,W_y} = \tau^\text{ZMP}_{net,W_x} = 0$, but allow $\tau^\text{ZMP}_{net,W_z} \ne 0$ to extract the analogous equations in the $y$-axis: \[ {}^Bp^{\text{ZMP}}_{W_z} m\ddot{y} - {}^Bp^{\text{ZMP}}_{W_y} (m\ddot{z} + mg) = I \ddot{\theta}. \]
Understanding the relationship between the center of pressure and the center of mass motion gives us a number of important tools for planning motions of our complex robots. I'll describe one of the most common pipeline for planning these motions, which decomposes the problem into:
Most notable here is the decision to separate the complicated planning problem into a sequence of simpler planning problems. Of course, one pays some price for the decomposition -- footstep plans tend to be conservative and kinematic because they do not reason directly about the dynamics of the robot. And the centroidal planning cannot accurately account for joint-level constraints, such as joint-position limits or effort limits. But these approximations enable dramatically simpler planning solutions.
Coming soon. For a description of our approach with Atlas, see
Coming soon. See, for instance,
Coming soon. See, for instance,
Coming soon. See, for instance,
In this exercise we implement a simplified version of the footstep
planning method proposed in
In this exercise we implement a simplified version of the footstep
planning problem formulated as a shortest path problem (SPP) in GCS
(proposed in
Previous Chapter | Table of contents | Next Chapter |