Algorithms for Walking, Running, Swimming, Flying, and Manipulation
© Russ Tedrake, 2024
Last modified 2024-11-11.
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 |
Practical legged locomotion is one of the fundamental problems in robotics; we've seen amazing progress over the last few years, but there are still some major unsolved problems. Much of the recent progress is due to improvements in hardware -- a legged robot must carry all of its sensors, actuators and power and traditionally this meant underpowered motors that act as far-from-ideal force/torque sources -- Boston Dynamics and other companies have made incredible progress here. The control systems implemented on these systems, though, are still more heuristic than you might think. They also require dramatically higher bandwidth and lower latency than the human motor control system and still perform worse in challenging environments.
The control of walking robots is definitely underactuated: assuming we
cannot pull on the ground (and barring any aerodynamic effects!), then no
matter how powerful my actuators are, there is nothing that we can do to
accelerate the center of mass of the robot towards the ground faster than
gravity. But beyond the underactuated systems we have studied so far, the
control of walking robots faces an additional complexity: controlling
through contact. The fact that we can get non-zero contact forces if and
only if two bodies are in contact introduces a fundamentally
discrete/combinatorial element into the problem†
Contact is essential for many aspects of robotics (manipulation is my other favorite example); it's sad to see so many robots going through life avoiding contact at any cost. Controlling contact means that your robot is capable of performing physical work on the environment; isn't that the point of robotics, afterall?
I like to start our discussion of contact with walking robots for a few important reasons. As you'll see in this chapter, there are a number of elegant "simple models" of walking that capture much of the essence of the problem with minimal complexity. But there is another, more subtle, reason: I want to continue to use the language of stability. At this point we've seen both finite-horizon and infinite-horizon problem formulations -- when we can say something about the behavior of a system in the limit as time goes to infinity, it's almost always cleaner than a finite-time analysis (because time drops away). Walking provides a very clean way to use the language of stability in studying behavior of systems that are sometimes in contact but sometimes out of contact in the limiting case; we just need to extend our notions from stability of a fixed point to the stability of a (periodic) cycle.
A limit cycle is an periodic orbit that is a limit set of the dynamical system; they can be stable (the limit set of neighboring trajectories as time goes to infinity) or unstable (the limit set of neighboring trajectories as time goes to negative infinity). One of the simplest models of limit cycle behavior is the Van der Pol oscillator. Let's examine that first...
The Van der Pol oscillator is described by a second-order differential
equation in one variable:
|
|
However, if we examine system trajectories in the time domain (see the
right panel of the figure above), then we can see that our traditional
notion for stability of a trajectory,
This example shows that stability of a trajectory (in time) is not the
definition we want. Instead we will define the stability of an orbit,
As we begin to extend our notions of stability, allow me to make a few
quick connections to the discussion of stability in the chapter on Lyapunov analysis. It's interesting to
know that if we can find an invariant
set in state space which does not contain any fixed points, then this
set must contain a closed orbit (this is the Poincaré-Bendixson
Theorem)
The first tool one should know for analyzing the stability of a limit
cycle, and one that will serve us quite well for the examples in this
chapter, is the method of Poincaré. Let's consider a dynamical
system,
For our purposes in this chapter, it will be useful for us to allow the Poincaré maps to also include fixed points of the original continuous-time system, and to define the return time to be zero. These points do not satisfy the transversality condition, and require some care numerically, but they do not compromise our analysis.
Since the state space of this system is two-dimensional, a return map
for the system must have dimension one. For instance, we can take
One dimensional maps, like one dimensional flows, are amenable to graphical analysis.
| |
If we can demonstrate that
In practice it is often difficult or impossible to find
It is sometimes possible to infer more global stability properties of
the return map by examining
A particularly graphical method for understanding the dynamics of a
one-dimensional iterated map is the "staircase method": Sketch the
Poincaré map -- a plot of
We can quickly recognize the fixed points as the points where the
return map crosses this line. We can infer local exponential stability if
the absolute value of the slope of return map at the fixed point is less
than one (
Much of the fundamental work in the dynamics of legged robots was done originally in the context of studying passive-dynamic walkers (often just "passive walker"). We've already seen my favorite example of a passive walker, in the first chapter, but here it is again:
This amazing robot has no motors and no controllers... it walks down a tiny ramp and is powered entirely by gravity. We can build up our understanding of this robot in a series of steps. As we will see, what is remarkable is that even though the system is passive, the periodic gait you see in the video is actually a stable limit cycle!
Well before the first passive walkers, one of the earliest models of
walking was proposed by McMahon
Perhaps the simplest possible model of a legged robot, introduced as
the conceptual framework for passive-dynamic walking by
McGeer
Note that the coordinate system used here is slightly different than
for the simple pendulum (
The most comprehensive analysis of the rimless wheel was done by
The dynamics of the system when one leg is on the ground are given by
The angular momentum around the point of collision at time
Given the stance dynamics, the collision detection logic (
I've setup the notebook to make it easy for you to try a handful of interesting initial conditions. And even made an interactive widget for you to watch the simulation phase portrait as you change those initial conditions. Give it a try!
The rimless wheel model actually uses a number of
the more nuanced features of
One of the fantastic things about the rimless wheel is that the dynamics are exactly the undamped simple pendulum that we've thought so much about. So you will recognize the phase portraits of the system -- they are centered around the unstable fixed point of the simple pendulum.
We can now derive the angular velocity at the beginning of each
stance phase as a function of the angular velocity of the previous
stance phase. First, we will handle the case where
Using the same analysis for the remaining cases, we can complete the
return map. The threshold for taking a step in the opposite direction
is
Notice that the return map is undefined for
This return map blends smoothly into the case where
For a fixed point, we require that
I opened this chapter with the idea that the natural notion of stability for a walking system is periodic stability, and I'll stand by it. But we can also examine the stability of a fixed-point (of the original coordinates; no Poincaré this time) for a system that has contact mechanics. For a legged robot, a fixed point means standing still. This can actually be a little subtle in our hybrid models: in the rimless wheel, standing still is the limiting case where we have infinitely frequent collisions. [Details coming soon.]
The rimless wheel models only the dynamics of the stance leg, and
simply assumes that there will always be a swing leg in position at the
time of collision. To remove this assumption, we take away all but two of
the spokes, and place a pin joint at the hip. To model the dynamics of
swing, we add point masses to each of the legs. I've derived the
equations of motion for the system assuming that we have a torque actuator
at the hip - resulting in swing dynamics equivalent to an Acrobot
(although in a different coordinate frame) - but let's examine the passive
dynamics of the system first (
In addition to the modeling assumptions used for the rimless wheel, we
also assume that the swing leg retracts in order to clear the ground
without disturbing the position of the mass of that leg. This model, known
as the compass gait, is well studied in the literature using numerical
methods
The state of this robot can be described by 4 variables:
The foot collision is an instantaneous change of velocity caused by a impulsive force at the foot that brings the foot to rest. The update to the velocities can be calculated using the derivation for impulsive collisions derived in the appendix. To use it, we proceed with the following steps:
You can simulate the passive compass gait using:
Try playing with the initial conditions. You'll find this system is much more sensitive to initial conditions than the rimless wheel. It actually took some work to find the initial conditions that make it walk stably.
Numerical integration of these equations reveals a stable limit cycle,
plotted below. Notice that when the left leg is in stance (top part of
the plot), the trajectory quite resembles the familiar pendulum dynamics
of the rimless wheel. But this time, when the leg impacts, it takes a
long arc around as the swing leg before returning to stance. The impacts
are also clearly visible as discontinuous changes (decreases) in velocity.
The dependence of this limit cycle on the system parameters has been
studied extensively in
The basin of attraction of the stable limit cycle is a narrow band of states surrounding the steady state trajectory. Although the simplicity of this model makes it attractive for conceptual explorations, this lack of stability makes it difficult to implement on a physical device.
To achieve a more anthropomorphic gait, as well as to acquire better
foot clearance and ability to walk on rough terrain, we want to model a
walker that includes a knee
At the beginning of each step, the system is modeled as a three-link
pendulum, like the ballistic
walker
After this collision, the knee is locked and we switch to the compass gait model with a different mass distribution. In other words, the system becomes a two-link pendulum. Again, the heel-strike is modeled as an inelastic collision. After the collision, the legs switch instantaneously. After heel-strike then, we switch back to the ballistic walker's three-link pendulum dynamics. This describes a full step cycle of the kneed walker, which is shown above.
By switching between the dynamics of the continuous three-link and two-link pendulums with the two discrete collision events, we characterize a full point-feed kneed walker walking cycle. After finding appropriate parameters for masses and link lengths, a stable gait is found. As with the compass gait's limit cycle, there is a swing phase (top) and a stance phase (bottom). In addition to the two heel-strikes, there are two more instantaneous velocity changes from the knee-strikes as marked in the figure. This limit cycle is traversed clockwise.
The region of attraction of the kneed-walking limit cycle can be improved considerably by the addition of curved feet...
In
The world has seen all sorts of great variations on the passive-dynamic walker theme. Almost certainly the most impressive are the creations of Dutch artist Theo Jansen -- he likes to say that he is creating "new forms of life" which he calls the Strandbeest. There are many variations of these amazing machines -- including his beach walkers which are powered only by the wind (I've actually been able to visit Theo's workshop once; it is very windy there).
These results are very real. Robin Deits (an exceptionally talented
student who felt particularly inspired once on a long weekend) once
reproduced one of Theo's earliest creations in
Just like walking, our understanding of the dynamics and control of running has evolved by a nice interplay between the field of biomechanics and the field of robotics. But in running, I think it's fair to say that the roboticists got off the starting blocks first. And I think it's fair to say that it started with a series of hopping machines built by Marc Raibert and the Leg Laboratory (which was first at CMU, but moved to MIT) in the early 1980's. At a time where many roboticsts were building relatively clumsy walking robots that moved very slowly (when they managed to stay up!), the Leg Laboratory produced a series of hopping machines that threw themselves through the air with considerable kinetic energy and considerable flair.
To this day, I'm still a bit surprised that impressive running robots (assuming you accept hopping as the first form of running) appeared before the impressive walking robots. I would have thought that running would be a more difficult control and engineering task than walking. But these hopping machines turned out to be an incredibly clever way to build something simple and very dynamic.
Shortly after Marc Raibert built his machines, Dan Koditschek and Martin
Buehler started analyzing them with simpler models
The model is a point mass,
In SLIP, we actually use different state variables for each phase of
the dynamics. During the flight phase, we use the state variables:
During the "stance phase", we write the dynamics in polar coordinates,
with the foot anchored at the origin. Using the state variables:
Unlike the rimless wheel model, the idealization of a spring leg with
a massless toe means that no energy is lost during the collision with the
ground. The collision event causes a transition to a different state
space, and to a different dynamics model, but no instantaneous change in
velocity. The transition from flight to stance happens when
You can simulate the spring-loaded inverted pendulum using:
Take a moment to read the code that defines the
SpringLoadedInvertedPendulum
system. You can see that we
carefully register the hybrid guards (witness functions) and reset
maps, which tells the numerical integrator to use zero-crossing event
detection to isolate precisely the time of the event and to apply the
reset update at this event. It is quite elegant, and we've gone to
some length to make sure that the numerical integration routines in
We used the same witness functions and resets to simulate the walking models, but those were implemented in C++. This is a purely Python implementation, making it a bit easier to see those details.
The rimless wheel had only two state variables (
For this system, one can still make progress if we define the
Poincaré section to be at the apex of the hop (when
Importantly, at the apex, these two variables are linked -- when you
know one, you know the other. This is because no energy is ever added
or removed from the system. If you know the (constant) total energy in
the system, and you know the height at the apex, then you know the
horizontal velocity (up to a sign):
Putting all of these together, we can numerically evaluate the apex-to-apex return map given a known total energy of the system as a one-dimensional Poincaré map.
Numerically integrating the equations of motion from apex-to-apex, using zero-crossing event detection, can give us the apex-to-apex map.
Using our graphical staircase analysis (for discrete-time systems), we can see that there are two fixed points of this map: one "stable" fixed point around 0.87 meters, and one unstable fixed point around 0.92 meters.
As always, you should run this code yourself to make sure you understand:
I'd also recommend running the simulation using initial conditions
at various points on this plot. You should ask: why does the plot
cut off so abruptly just below the stable fixed point? Well the
apex-to-apex map becomes undefined if the apex is smaller that
The system's conservation of total energy is quite convenient for
our return map analysis, but it should give you pause. The rimless
wheel actually relied on the dissipation due to collisions with
the ground to acquire its stability. Is there any chance for a system
that is energy conserving to be stable? The apex-to-apex return maps
visualized above reveal "stable" fixed-points, but you must understand
that the projection from
Despite this limitation, it is quite interesting that such a simple
system converges to particular hopping heights from various initial
conditions. The observation that these "piecewise-Hamiltonian" systems
(Hamiltonian because they conserve total energy) can exhibit this
partial stability generated quite a bit of interest from the
theoretical physics community. You can sense that enthusiasm when
reading
Our SLIP analysis was simplified considerably by the assumption that the leg is massless, and can be moved instantaneously during the flight phase into the desired touchdown position. This might sound to you like an offensive oversimplification, but in fact the strong trend in legged robots these days has been to build physical devices which make this sort of abstraction (approximately) valid. For quadrupeds especially, it's hard to fall over when you can move your foot instantaneously into the direction where your body is falling.
Assuming a massless leg also gives us a nice conceptual advantage --
it becomes natural to think about control design as making a control
decision once per step. This fits nicely with our Poincaré
analysis -- we can think of the apex-to-apex map of the SLIP model as
being parameterized by the (scalar) control decision
It turns out that for the SLIP model, there is a more interesting
approach available. If we set the cost on control effort to zero
(consistent with our massless leg assumption), then the optimal action
to pick is the one that drives the system exactly to the desired fixed
point in a single hop. This is the so-called deadbeat
controller. Not all systems can be stabilized in this way, but
Take a moment to reflect on this. In continuous time, if I were to remove the cost on control input, then the optimal actions would be unbounded, or bang-bang if there are input limits. But in discrete-time systems, this is not necessarily the case -- one can often achieve perfect convergence in a finite number of steps with bounded control input -- this corresponds to a finite-time convergence in continuous time. For this simple running model, what is particularly elegant is that this convergence can even be achieved in just one step.
In fact, the story for deadbeat control of the SLIP model gets even
better.
One would not expect to use the terms "blind", "running", "rough-terrain", and "deadbeat control" all at once to describe a control strategy. But there you have it. A very nice result! The authors went on to study whether this observation could help to explain the known phenomenon in biomechanics of "ground-speed matching" -- a human/animals' tendency to actively swing the leg around to meet the ground at the moment of touchdown.
The original SLIP model, perhaps inspired by the hopping robots
turned out to be quite effective in describing the vertical center of
mass dynamics of a wide range of animals
A three-part control strategy: decoupling the control of hopping
height, body attitude, and forward velocity
bipeds, quadrupeds, and backflips...
Although they are not technically legged robots, there is another beautiful set
of model systems that were developed alongside some of the results that we've been
describing here, making use of the same tools and analysis. Juggling in its full
generality is, of course, a very dynamic and dexterous task that requires great
skill. But clever roboticists have found a way to distill it down to its essence
The simplest possible model is called the "line juggler", because both the robot
(which here is just a simple paddle) and the single ball are constrained to move
only along a line -- imagine the ball being constrained in a vertical track. We will
write the robotics's configuration as
Once again, the intermittent dynamics of the juggler are most naturally expressed
on the Poincaré map. This map can be difficult to compute in general, but
there is a clever parameterization of the action space which mitigates all of the
potential complexity. In particular,
Planar juggler
In this exercise we implement a one-dimensional version of the controller proposed in
Previous Chapter | Table of contents | Next Chapter |