You are on page 1of 12

The (Passive) Dynamics of Walking

Russ Tedrake February 24, 2007


Announcements: PS1 due today (get them to Alec)

Goals for this lecture


Stability of Oscillations (Limit Cycles) Return-map analysis Simple models for impacts Simplied walking models (ballistic walker, rimless wheel, compass gait, kneed walker)

1 The Ballistic Walker


McMahon[9] argued that humans use a mostly ballistic (passive) gait. COM trajectory looks like a pendulum (roughly walking by vaulting). EMG activity in stance legs is high, but EMG in swing leg is very low, except for very beginning and end of swing. Proposed a three-link ballistic walker model, which models a single swing phase (but not transitions to the next swing nor stability). McGeer[7] followed up with a series of walking machines. Show the kneed walker simulation, run kneedWalker.m. Were going to work up to understanding that system. But let me start by showing you a phase plot. open limitCycle.fig in matlab.

2 Closed-Orbits in the Phase Plane


Recall the phase portrait of the simple pendulum. Depending on the parameters of this system, we could nd a variety of system orbits, or trajectories. For the case where b > 0, these orbits all (eventually) converge on some xed point of the system, on the line x = 0. For the special case where b = 0, the xed points of the system were no longer asymptotically stable (though they were still stable i.s.L.). But another

6.881 - Underactuated Robots

Lecture 5

Figure 1: Phase portrait of a damped simple pendulum important feature emerged - the closed-orbit. In fact, there are many closed-orbits in this system, circling around the stable xed point, up to the homoclinic orbit. Understanding these closed-orbits is going to be important for understanding walking. A nominal walking gait, on at terrain, results in a periodic motion of the joints. As well see, this is nothing more than a closed orbit in the phase plane. Closed-orbits in the phase plane are called limit cycles1 . We have already developed a language to talk about the stability of the xed points, so our rst goal for today will be to develop a similar language to talk about the stability of a limit cycle. I think your intuition will tell you that the closed-orbits in the (undamped) pendulum are not asymptotically stable. Are they stable in the sense of Lyapunov? Yes, even in the case when u = 0, and the orbits are not symmetrical, I would still think that theyd meet this denition (for any , I can choose a , ...). Example 1 (Van der Pol Oscillator) x + (x2 1)x +x=0 Nonlinear damping. Adds energy when |x| < 1, dissipates energy when |x| > 1. Might expect to nd a stable solution where the energy addition and dissipation balance. Run vanderPol.m with plotting in time domain, then phase plot. Converges to a stable, closed orbit. Note (by running in time domain with hold on) that individual trajectories do not converge (not stable along the limit cycle). It is this fact that neighboring trajectories do not actually converge with each other that makes dening stability of a limit cycle difcult.
1 Note that some people restrict the term limit cycles for trajectories which are isolated, e.g. either asymptotically stable or unstable, but not marginally stable.

6.881 - Underactuated Robots

Lecture 5

Let me make one point about the existence of closed orbits. If we can dene a closed region of phase space which does not contain any xed points, then it must contain a closed-orbit[11]. By closed, I mean that any trajectory which enters the region will stay in the region. (this is the Poincare-Bendixson Theorem) Gradient potential elds (e.g. Lyapunov functions) cannot have a closed-orbit[11].

3 Poincar e Maps
One denition for the stability of a limit cycle uses the method of Poincar e. Lets = f (x). Dene an n 1 dimensional consider an n dimensional dynamical system, x surface of section, S . We will also require that S is tranverse to the ow (i.e., all trajectories starting on S ow through S , not parallel to it). The Poincar e map (or return map) is a mapping from S to itself. k+1 = P(xk ). x Example 2 (Return map for the Van der Pol Oscillator) Since the full system is two dimensional, the return map dynamics are one dimensional. One dimensional maps, like one dimensional ows, are amenable to graphical analysis. Let S be the line segment where x = 0, x > 0. A numerical reconstruction of P (x) is implemented in vanderPol.m. If P (x) exists, this method turns the stability analysis for a limit cycle into the stability analysis of a xed point on a discrete map. Unfortunately, it is rarely possible to nd P analytically in practice. Well show one counter-example.

Iterations on a One-Dimensional Maps


Cartoon Van der Pol return map on the board. Fixed points are the crossings with the unity line. Asymptotically stable if || < 1. Draw stair cases. Unlike one dimensional ows, one dimensional maps can have oscillations (happens whenever < 0).

4 The Rimless Wheel


The most elementary model of passive dynamic walking, rst used in the context of walking by [7], is the rimless wheel. This simplied system has rigid legs and only a point mass at the hip as illustrated in Figure 2. To further simplify the analysis, we make the following modeling assumptions: Collisions with ground are inelastic and impulsive (only angular momentum is conserved around the point of collision). The stance foot acts as a pin joint and does not slip. The transfer of support at the time of contact is instantaneous (no double support phase). 3

6.881 - Underactuated Robots

Lecture 5

2 l m g
Figure 2: The rimless wheel. The orientation of the stance leg, , is measured clockwise from the vertical axis. 0<
2,

0<<

2,

l > 0.

The most comprehensive analysis of the rimless wheel was done by [1]. The analysis presented here simplies and extends that work with a novel method for deriving the basins of attraction using contraction analysis [6].

4.1

Stance Dynamics
= g sin(). l

The dynamics of the system when one leg is on the ground are given by

If we assume that the system is started in a conguration directly after a transfer of support ((0+ ) = ), then forward walking occurs when the system has an initial (0+ ) > 1 , where velocity, 1 = g 2 [1 cos ( )]. l

1 is the threshold at which the system has enough kinetic energy to vault the mass over the stance leg and take a step. This threshold is zero for = and does not exist for > . The next foot touches down when (t) = , at which point the conversion of potential energy into kinetic energy yields the velocity (t ) = 2 (0+ ) + 4 g sin sin . l

t denotes the time immediately before the collision.

6.881 - Underactuated Robots

Lecture 5

4.2

Foot Collision

The angular momentum around the point of collision at time t just before the next foot collides with the ground is (t ) cos(2). L(t ) = ml2 The angular momentum at the same point immediately after the collision is (t+ ). L(t+ ) = ml2 Assuming angular momentum is conserved, this collision causes an instantaneous loss of velocity: (t+ ) = (t ) cos(2). The deterministic dynamics of the rimless wheel produce a stable limit cycle solution with a continuous phase punctuated by a discrete collision, as shown in Figure 3. The red dot on this graph represents the initial conditions, and this limit cycle actually moves counter-clockwise in phase space because for this trial the velocities were always negative. The collision represents as instantaneous change of velocity, and a transfer of the coordinate system to the new point of contact.
4 roll 3 = d/dt +
0 *

3 = d/dt

1 2

2 0
+ *

roll
1

0.2

0.2

0.4

0.6

0.2

0.2

0.4

0.6

Figure 3: Limit cycle trajectory of the rimless wheel (m = 1, l = 1, g = 9.8, = + /8, = 0.15). Two downhill trajectories are shown. At left, 1 < 0 < roll , and each successive step gets faster to approach roll . At right, the initial velocity + > roll ) and successive post-collision wheel velocities decrease exceeds roll (0 monotonically to approach the rolling xed point. (Discontinuous jumps between n + and n are shown as dashed lines. Since all velocities shown here are positive, each continuous part of the cycle moves from left to right.) All downhill velocities above 1 (i.e. on the vertical shown at .24) will converge to roll .

4.3

Return Map

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 5

6.881 - Underactuated Robots

Lecture 5

+ > 1 . The step-to-step return map can be computed by case where and n integrating the continuous stance dynamics over one step:
(T ) (0+ )

=1 2 (T ) 2 (0+ ) = g [ cos( + ) + cos( + )] d 2 l

Factoring in the losses from a single collision, the resulting map is: + = cos(2) n+1 g + 2 n ) + 4 sin sin . ( l

+ indicates the velocity just after the energy loss at impact has occurred. where the 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 g 2 = 2 [1 cos( + )]. l + < 1 , we have For 2 < n + = + cos(2). n n+1 + < 2 , we have Finally, for n + = cos(2) n+1 g + 2 n ( ) 4 sin sin . l

Notice that the formerly undened points at {1 , 2 } are now well-dened transitions with 1 = 0, because it is kinematically impossible to have the wheel statically balancing on a single leg.

n = {1 , 2 }, because from these Notice that the return map is undened for congurations, the wheel will end up in the (unstable) equilibrium point where = 0 = 0, and will therefore never return to the map. and This return map blends smoothly into the case where > . In this regime, g + 2 + 0 n cos(2) (n ) + 4 l sin sin , + + = + < 0 . cos(2 ) , < 2 n+1 n n cos(2) ( + 2 n + w2 ) 4 g sin sin ,
l n

4.4

Fixed Points and Stability

+ = . Our system has two possible xed + = For a xed point, we require that n n+1 points, depending on the parameters:
stand = 0, roll = cot(2)

g 4 sin sin . l

6.881 - Underactuated Robots

Lecture 5

The limit cycle plotted in Figure 3 illustrates a state-space trajectory in the vicinity of the rolling xed point. stand is a xed point whenever < . roll is a xed point whenever roll > 1 . It is interesting to view these bifurcations in terms of . For small , stand is the only xed point, because energy lost from collisions with the ground is not compensated for by gravity. As we increase , we obtain a stable rolling solution, where the collisions with the ground exactly balance the conversion of gravitational potential to kinetic energy. As we increase further to > , it becomes impossible for the center of mass of the wheel to be inside the support polygon, making standing an unstable conguration.
6

4 d+ /dt [ang. vel. after collision n+1] n+1

* roll * stand

4 Return map Reference line of slope 1 Fixed points 2 (left) and 1 6 4 2 0 2 4 6 d+ /dt [ang. vel. after collision n] n

8 8

Figure 4: Limit cycle trajectory of the rimless wheel (m = 1, l = 1, g = 9.8, = /8, = 0.15). All hatched regions converge to the rolling xed point, roll ; the white regions converge to zero velocity (stand ).

5 The Compass Gait


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. 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 [2, 10], but relatively little is known about it analytically. st , and sw . The The state of this robot can be described by 4 variables: st , sw ,

6.881 - Underactuated Robots

Lecture 5

b a sw

mh

m st

Figure 5: The compass gait abbreviation st is shorthand for the stance leg and sw for the swing leg. Using q = [sw , st ]T , we can write the dynamics as )q + G(q) = 0, H(q) q + B(q, q with H= B= mb2 mlb cos(st sw ) 0 sw mlb sin(st sw ) G= mlb cos(st sw ) (mh + m)l2 + ma2 st mlb sin(st sw ) 0

mbg sin(sw ) , (mh l + ma + ml)g sin(st )

and l = a + b. These equations come straight out of [3]. The foot collision is an instantaneous change of velocity governed by the conservation of angular momentum around the point of impact: + = Q ()q , Q+ ()q where Q () = Q+ () = mab 0 mab + (mh l2 + 2mal) cos(2) mab ml(l b cos(2) + ma2 + mh l2 mbl cos(2)

mb(b l cos(2)) mb2

st and = sw 2 . Numerical integration of these equations reveals a stable limit cycle, plotted in Figure 6. The cycle is composed of a swing phase (top) and a stance phase (bottom),

6.881 - Underactuated Robots

Lecture 5

punctuated by two instantaneous changes in velocity which correspond to the ground collisions. The dependence of this limit cycle on the system parameters has been studied extensively in [3].
2.5 2 1.5 1 dlPitch/dt 0.5 0 0.5 1 1.5 2 0.4 0.3 0.2 0.1 0 lPitch 0.1 0.2 0.3 0.4

Figure 6: Limit cycle trajectory of the compass gait. (m = 5kg,mh = 10kg,a = b = 0.5m, = 0.03deg. q(0) = [0, 0, 2, 0.4]T ). lP itch is the pitch angle of the left leg, which is recovered from st and sw in the simulation with some simple book-keeping. 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 analytically attractive, this lack of stability makes it difcult to implement on a physical device.

6 The Kneed Walker


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 knee[5]. For this, we model each leg as two links with a point mass each. At the beginning of each step, the system is modeled as a three-link pendulum, like the ballistic walker[9, 8, 10]. The stance leg is the one in front, and it is the rst link of a pendulum, with two point masses. The swing leg has two links, with the joint between them unconstrained until knee-strike. Given appropriate mass distributions and initial conditions, the swing leg bends the knee and swings forward. When the swing leg straightens out (the lower and upper length are aligned), knee-strike occurs. The kneestrike is modeled as a discrete inelastic collision, conserving angular momentum and changing velocities instantaneously. 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 9

6.881 - Underactuated Robots

Lecture 5

mH b2 mt q2

mt a2 L

b1 q3 a1 ms ms q1

Figure 7: The Kneed Walker switch instantaneously. After heel-strike then, we switch back to the ballistic walkers three-link pendulum dynamics. This describes a full step cycle of the kneed walker, which is shown in Figure 8.

3-link dynamics

2-link dynamics

Knee-strike

Heel-strike

Figure 8: Limit cycle trajectory for kneed walker 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 nding appropriate parameters for masses and link lengths, a stable gait is found. As with the compass gaits 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 Figure 9. This limit cycle is traversed clockwise.

10

6.881 - Underactuated Robots

Lecture 5

Right Leg 2.5 2 1.5 1 0.5 d/dt 0 0.5 1 1.5 2 2.5 0.3 0.2 stance leg while knee strikes switch to stance phase (heelstrike) switch to swing phase (heelstrike) swing leg while knee strikes

0.1

0.1

0.2

0.3

0.4

Figure 9: The Kneed Walker

References
[1] Michael J. Coleman. A Stability-Study of a Three-Dimensional Passive-Dynamic Model of Human Gait. PhD thesis, Cornell University, 1998. [2] A. Goswami. Postural stability of biped robots and the foot rotation indicator (FRI) point. International Journal of Robotics Research, 18(6), 1999. [3] Ambarish Goswami, Benoit Thuilot, and Bernard Espiau. Compass-like biped robot part I : Stability and bifurcation of passive gaits. Technical Report RR2996, INRIA, October 1996. [4] John Guckenheimer and Philip Holmes. Nonlinear Oscillations, Dynamical Systems, and Bifurcations of Vector Fields. Springer, 1983. [5] Vanessa Hsu. Passive dynamic walking with knees: A point-foot model. Masters thesis, Massachusetts Institute of Technology, February 2007. [6] Winfried Lohmiller and J.J.E. Slotine. On contraction analysis for non-linear systems. Automatica, 34(6):683696, June 1998. [7] Tad McGeer. Passive dynamic walking. International Journal of Robotics Research, 9(2):6282, April 1990. [8] Simon Mochon and Thomas A. McMahon. Ballistic walking. Journal of Biomechanics, 13:4957, 1980. [9] Simon Mochon and Thomas A. McMahon. Ballistic walking: An improved model. Mathematical Biosciences, 52(3-4):241260, December 1980.

11

6.881 - Underactuated Robots

Lecture 5

[10] Mark W. Spong and Gagandeep Bhatia. Further results on control of the compass gait biped. In Proceedings of the IEEE International Conference on Intelligent Robots and Systems (IROS), pages 19331938, 2003. [11] Steven H. Strogatz. Nonlinear Dynamics and Chaos: With Applications to Physics, Biology, Chemistry, and Engineering. Perseus Books, 1994.

12

You might also like