forked from RussTedrake/underactuated
-
Notifications
You must be signed in to change notification settings - Fork 0
/
simple_legs.html
991 lines (803 loc) · 52.6 KB
/
simple_legs.html
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
<!DOCTYPE html>
<html>
<head>
<title>Underactuated Robotics: Simple Models
of Walking and Running</title>
<meta name="Underactuated Robotics: Simple Models
of Walking and Running" content="text/html; charset=utf-8;" />
<link rel="canonical" href="http://underactuated.mit.edu/simple_legs.html" />
<script src="https://hypothes.is/embed.js" async></script>
<script type="text/javascript" src="htmlbook/book.js"></script>
<script src="htmlbook/mathjax-config.js" defer></script>
<script type="text/javascript" id="MathJax-script" defer
src="https://cdn.jsdelivr.net/npm/mathjax@3/es5/tex-chtml.js">
</script>
<script>window.MathJax || document.write('<script type="text/javascript" src="htmlbook/MathJax/es5/tex-chtml.js" defer><\/script>')</script>
<link rel="stylesheet" href="htmlbook/highlight/styles/default.css">
<script src="htmlbook/highlight/highlight.pack.js"></script> <!-- http://highlightjs.readthedocs.io/en/latest/css-classes-reference.html#language-names-and-aliases -->
<script>hljs.initHighlightingOnLoad();</script>
<link rel="stylesheet" type="text/css" href="htmlbook/book.css" />
</head>
<body onload="loadChapter('underactuated');">
<div data-type="titlepage">
<header>
<h1><a href="index.html" style="text-decoration:none;">Underactuated Robotics</a></h1>
<p data-type="subtitle">Algorithms for Walking, Running, Swimming, Flying, and Manipulation</p>
<p style="font-size: 18px;"><a href="http://people.csail.mit.edu/russt/">Russ Tedrake</a></p>
<p style="font-size: 14px; text-align: right;">
© Russ Tedrake, 2021<br/>
Last modified <span id="last_modified"></span>.</br>
<script>
var d = new Date(document.lastModified);
document.getElementById("last_modified").innerHTML = d.getFullYear() + "-" + (d.getMonth()+1) + "-" + d.getDate();</script>
<a href="misc.html">How to cite these notes, use annotations, and give feedback.</a><br/>
</p>
</header>
</div>
<p><b>Note:</b> These are working notes used for <a
href="http://underactuated.csail.mit.edu/Spring2021/">a course being taught
at MIT</a>. They will be updated throughout the Spring 2021 semester. <a
href="https://www.youtube.com/channel/UChfUOAhz7ynELF-s_1LPpWg">Lecture videos are available on YouTube</a>.</p>
<table style="width:100%;"><tr style="width:100%">
<td style="width:33%;text-align:left;"><a class="previous_chapter" href=acrobot.html>Previous Chapter</a></td>
<td style="width:33%;text-align:center;"><a href=index.html>Table of contents</a></td>
<td style="width:33%;text-align:right;"><a class="next_chapter" href=humanoids.html>Next Chapter</a></td>
</tr></table>
<!-- EVERYTHING ABOVE THIS LINE IS OVERWRITTEN BY THE INSTALL SCRIPT -->
<chapter style="counter-reset: chapter 3"><h1>Simple Models
of Walking and Running</h1>
<p>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
fundamental 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 -- but Boston Dynamics and other companies have made
incredible progress here. The control systems implemented on these systems,
though, are still surprisingly heuristic -- they require dramatically higher
bandwidth and lower latency that the human motor control system and still
perform worse in challenging environments.<p>
<p>The control of walking robots is fundamentally 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 they 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: <b>controlling
through contact</b>. 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†<sidenote>†I've
had some interesting arguments with folks on this point, because it's possible
to write contact models that smooth the discontinuity, and/or to model systems
that have neglible collision events. But replacing a discontinuity in the
vector field with a stiff but smooth transition does not remove the need to
decide whether or not your robot should make contact to accomplish a
task.</sidenote>.</p>
<p>Contact is fundamental 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?</p>
<p>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.
</p>
<section><h1>Limit Cycles</h1>
<p> A limit cycle is an periodic orbit that is a <a
href="https://en.wikipedia.org/wiki/Limit_set">limit set</a> 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...</p>
<example><h1>Van der Pol Oscillator</h1>
<p>The Van der Pol oscillator is described by a second-order differential
equation in one variable: $$\ddot{q} + \mu (q^2 - 1)\dot{q} + q = 0, \quad
\mu>0$$ One can think of this system as almost a simple spring-mass-damper
system, except that it has nonlinear damping. In particular, the velocity
term dissipates energy when $|q|>1$, and adds energy when $|q|<1$.
Therefore, it is not terribly surprising to see that the system settles
into a stable oscillation from almost any initial conditions (the
exception is the state $q=0,\dot{q}=0$). This can be seen nicely in the
phase portrait below.</p>
<figure>
<table width="100%"><tr><td width="50%">
<img width="100%" src="figures/vanderPol_phase.svg"/>
</td><td width="50%">
<img width="100%" src="figures/vanderPol_time.svg"/>
</td></tr></table>
<figcaption>System trajectories of the Van der Pol oscillator with $\mu
=.2$. (Left) phase portrait. (Right) time domain.</figcaption>
</figure>
<p>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, $\lim_{t\rightarrow \infty} |\bx(t)
- \bx^*(t)| = 0$, is not satisfied here for any $\bx^*(t)$. Although the
phase portrait clearly reveals that all trajectories converge to the same
orbit, the time domain plot reveals that these trajectories do not
necessarily synchronize in time.</p>
</example> <!-- end of VdP example -->
<p>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,
$\bx^*(t)$, using \[ \min_\tau || \bx(t) - \bx^*(\tau) ||.\] Here the
quantity of interest is the distance between our trajectory and the
<i>closest point</i> on the orbit. Depending on exactly how this distance
evolves with time, we can define <i>orbital stability</i>: for every small
$\epsilon>0$, we can find a $\delta>0$ such that $\min_\tau||\bx(t_0) -
\bx^*(\tau)|| < \delta$ implies $\forall t, \min_\tau ||\bx(t) -
\bx^*(\tau)|| < \epsilon$). The definitions for asymptotic orbital
stability, exponential orbital stability, finite-time orbital stability
follow naturally, as does the definition of an unstable orbit. In the case
of limit cycles, this $\bx^*(t)$ is a periodic solution with
$\bx^*(t+t_{period}) = \bx^*(t)$. </p>
<p>As we begin to extend our notions of stability, allow me to make a few
quick connections to the discussion of stability in the <a
href="lyapunov.html">chapter on Lyapunov analysis</a>. It's interesting to
know that if we can find an <a href="lyapunov.html#lasalle">invariant
set</a> in state space which does not contain any fixed points, then this
set must contain a closed orbit (this is the Poincaré-Bendixson
Theorem)<elib>Strogatz94</elib>. It's also interesting to note that
gradient potential fields (and Lyapunov functions with $\dot{V}(\bx) \prec
0$) cannot have a closed orbit<elib>Strogatz94</elib>, and consequently we
will also have to slightly modify the Lyapunov analysis we have introduced
so far to handle limit cycles. We'll discuss this in some details in an <a
href="limit_cycles.html#lyapunov">upcoming chapter</a>.</p>
<subsection><h1>Poincaré Maps</h1>
<p>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, $\dot{\bx} = {\bf f}(\bx),$ with $\bx \in \Re^n.$ Define an $n-1$
dimensional <em>surface of section</em>, $S$. We will also require that
$S$ is transverse to the flow (i.e., all trajectories starting on $S$ flow
through $S$, not parallel to it). The Poincaré map (or return map)
is a mapping from $S$ to itself: $$\bx_p[n+1] = {\bf P}(\bx_p[n]),$$
where $\bx_p[n]$ is the state of the system at the $n$th crossing of the
surface of section. Note that we will use the notation $\bx_p$ to
distinguish the state of the discrete-time system from the continuous-time
system; they are related by $\bx_p[n] = \bx(t_c[n])$, where $t_c[n]$ is
the time of the $n$th crossing of $S$.</p>
<p>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.</p>
<example><h1>Return map for the Van der Pol Oscillator</h1>
<p>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 $S$
to be the line segment where $q = 0$, $\dot{q} \ge 0$. It is easy to
see that all trajectories that start on S are transverse to it.</p>
<p>One dimensional maps, like one dimensional flows, are amenable to
graphical analysis.
</p>
<figure> <table><tr><td> <img width="100%"
src="figures/vanderPol_section.svg" /> </td><td> <img width="100%"
src="figures/vanderPol_retmap.svg" /> </td></tr></table>
<figcaption>(Left) Phase plot with the surface of section, $S$, drawn
with a black dashed line. (Right) The resulting Poincaré
first-return map (blue), and the line of slope one (red).</figcaption>
</figure>
</example>
<p>If we can demonstrate that ${\bf P}(\bx_p)$ exists for all $\bx_p \in
S$, (all trajectories that leave $S$ eventually return to $S$), then
something remarkable happens: we can reduce the stability analysis for a
limit cycle in the original coordinates into the stability analysis of a
fixed point on the discrete map. If $\bx^*_p$ is a stable (or unstable)
fixed point of the map ${\bf P}$, then there exists a unique periodic
orbit $\bx^*(t)$ which passes through $\bx^*_p$ that is a (stable, or
unstable) limit cycle. If we are able to upper-bound the time it takes
for trajectories leaving $S$ to return, then it is also possible to infer
asympotitic orbital or even exponential orbital stability.</p>
<p>In practice it is often difficult or impossible to find ${\bf P}$
analytically, but it can be sampled quite reasonably numerically. Once a
fixed point of ${\bf P}$ is obtained (by finding a solution to$\bx^*_p =
{\bf P}(\bx^*_p)$), we can infer local limit cycle stability with an
eigenvalue analysis. If this eigen-analysis is performed in the original
coordinates (as opposed to the $n-1$ dimensional coordinates of $S$), then
there will always be a at least one zero eigenvalue - corresponding to
perturbations along the limit cycle which do not change the state of first
return. The limit cycle is considered locally exponentially stable if all
remaining eigenvalues, $\lambda_i$, have magnitude less than one,
$|\lambda_i|<1$.</p>
<p>It is sometimes possible to infer more global stability properties of
the return map by examining ${\bf P}$. We will study computational
methods in the <a href="limit_cycles.html">later chapter</a>.
<elib>Koditschek91</elib> describes some less computational stability
properties known for <em>unimodal</em> maps which are useful for the
simple systems we study in this chapter.</p>
<p>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 $x_p[n]$ vs $x_p[n+1]$ -- and also the
line of slope one. In order to "iterate" the map, take an initial
condition on the plot as a point $\left( x_p[k], x_p[k] \right)$, and move
vertically on the plot to the point $\left( x_p[k], x_p[k+1] = f(x_p[k])
\right)$. Now move horizontally to the next point $\left( x_p[k+1],
x_p[k+1] \right)$ and repeat.</p>
<figure id="staircase">
<img width="70%" src="figures/vanderpol_staircase.svg"/>
<figcaption>The "staircase" on the return map of the Van der Pol
Oscillator with $\mu = 0.2$, starting from two initial conditions
($\dot{q}_p[0] = .5$ and $\dot{q}_p[0] = 3.5$).</figcaption>
</figure>
<p>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 ($|\lambda| < 1$). The figure above illustrates the stability of
the Van der Pol limit cycle; it also illustrates the (one-sided)
instability of the fixed point at the origin. Understanding the regions
of attraction of fixed points on an iterated map (or any discrete-time
system) graphically requires a little more care, though, than the
continuous-time flows we examined before. The discrete maps can jump a
finite distance on each step, and will in fact oscillate back and forth
from either side of the fixed point when $\lambda < 0.$</p>
</subsection> <!-- end of Poincare -->
</section> <!-- end of Limit Cycles -->
<section><h1>Simple Models of Walking</h1>
<p>Much of fundamental work in the dynamics of legged robots was done originally in the context of studying <i>passive-dynamic walkers</i> (often just "passive walker"). We've already seen my favorite example of a passive walker, in the first chapter, but here it is again:</p>
<figure>
<p>
<video width="80%" controls title="If your browser cannot play this video, then download it using the link below.">
<source src="http://ruina.tam.cornell.edu/research/topics/locomotion_and_robotics/3d_passive_dynamic/from_angle.mpg" type="video/mp4"/>
<source src="figures/passive_angle.ogg" type="video/ogg"/>
</video>
</p>
<figcaption>A 3D passive dynamic walker by Steve Collins and Andy Ruina<elib>Collins01</elib>.</figcaption>
</figure>
<p>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, we believe that the
periodic gait you see in the video is actually a stable limit cycle!</p>
<p>Well before the first passive walkers, one of the earliest models of
walking was proposed by McMahon<elib>McMahon80</elib>, who argued that
humans use a mostly ballistic (passive) gait. He observed that muscle
activity (recorded via <a
href="https://en.wikipedia.org/wiki/Electromyography">EMG</a>) in the
"stance leg" is relatively high, but muscle activity in the "swing leg" is
very low, except for at the very beginning and end of swing. He proposed a
"ballistic walker" model -- a three-link pendulum in the <a
href="https://en.wikipedia.org/wiki/Sagittal_plane">sagittal plane</a>, with
one link from the ankle to the hip representing a straight "stance leg", the
second link from the hip back down to the "swing leg" knee, and the final
link from the knee down to the swing foot -- and argued that this model
could largely reproduce the kinematics of gait. This model of "walking by
vaulting" is considered overly simplistic today, as we now understand much
better the role of compliance in the stance leg during walking. His model
was also restricted to the continuous portion of gait, not the actual
dynamics of taking a step. But it was the start. Nearly a decade later,
McGeer<elib>McGeer90</elib> followed up with a series of similarly inspired
walking machines, which he coined "passive-dynamic walkers".</p>
<subsection id="rimless_wheel"><h1>The Rimless Wheel</h1>
<figure>
<img width="40%" src="figures/rimlessWheel.svg"/>
<figcaption>The rimless wheel. The orientation of the stance leg,
$\theta$, is measured clockwise from the vertical axis. </figcaption>
</figure>
<p>Perhaps the simplest possible model of a legged robot, introduced as
the conceptual framework for passive-dynamic walking by
McGeer<elib>McGeer90</elib>, is the rimless wheel. This system has rigid
legs and only a point mass at the hip as illustrated in the figure above.
To further simplify the analysis, we make the following modeling
assumptions:</p> <ul> <li>
Collisions with ground are inelastic and impulsive (only angular momentum
is conserved around the point of collision).</li> <li> The stance foot
acts as a pin joint and does not slip.</li> <li> The transfer of support
at the time of contact is instantaneous (no double support phase).</li>
<li> $0 \le \gamma < \frac{\pi}{2}$, $0 < \alpha < \frac{\pi}{2}$, $l >
0$.</li> </ul>
<p>Note that the coordinate system used here is slightly different than
for the simple pendulum ($\theta=0$ is at the top, and the sign of
$\theta$ has changed).</p> <todo> update the coordinates (here and in
drake)</todo>
<p> The most comprehensive analysis of the rimless wheel was done by
<elib>Coleman98a</elib>.</p>
<subsubsection><h1>Stance Dynamics</h1>
<p>The dynamics of the system when one leg is on the ground are given by
$$\ddot\theta = \frac{g}{l}\sin(\theta).$$ If we assume that the system
is started in a configuration directly after a transfer of support
($\theta(0^+) = \gamma-\alpha$), then forward walking occurs when the
system has an initial velocity, $\dot\theta(0^+) > \omega_1,$ where
$$\omega_1 = \sqrt{ 2 \frac{g}{l} \left[ 1 - \cos \left (\gamma-\alpha
\right) \right]}.$$ $\omega_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 $\gamma = \alpha$ and does not exist
for $\gamma > \alpha$ (because when $\gamma > \alpha$ the mass is always
ahead of the stance foot, and the standing fixed point disappears). The
next foot touches down when $\theta(t) = \gamma+\alpha$, at which point
the conversion of potential energy into kinetic energy yields the
velocity $$\dot\theta(t^-) = \sqrt{\dot\theta^2(0^+) + 4\frac{g}{l}
\sin\alpha \sin\gamma }.$$ $t^-$ denotes the time immediately before the
collision.</p>
</subsubsection>
<subsubsection><h1>Foot Collision</h1>
<figure> <img width="50%" src="figures/rimlessWheel_collision.svg"/>
<figcaption>Angular momentum is conserved around the point of
impact</figcaption> </figure>
<p> The angular momentum around the point of collision at time $t$ just
before the next foot collides with the ground is $$L(t^-) =
-ml^2\dot\theta(t^-) \cos(2\alpha).$$ The angular momentum at the same
point immediately after the collision is $$L(t^+) =
-ml^2\dot\theta(t^+).$$ Assuming angular momentum is conserved, this
collision causes an instantaneous loss of velocity: $$\dot\theta(t^+) =
\dot\theta(t^-) \cos(2\alpha).$$</p>
</subsubsection>
<subsubsection><h1>Forward simulation</h1>
<p>Given the stance dynamics, the collision detection logic ($\theta =
\gamma \pm \alpha$), and the collision update, we can numerically
simulate this simple model. Doing so reveals something remarkable...
the wheel starts rolling, but then one of two things happens: it either
runs out of energy and stands still, or it quickly falls into a stable
periodic solution. Convergence to this stable periodic solution appears
to happen from a huge range of initial conditions. Try it yourself.</p>
<example><h1>Numerical simulation of the rimless wheel</h1>
<jupyter>examples/simple_legs.ipynb</jupyter>
<p>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! (I recommend using Binder instead
of Colab so you get the interactive features)</p>
<p><a
href="https://github.com/RobotLocomotion/drake/blob/e08fc2bb0d289deddb5d76d0235f3a75ef3795d3/examples/rimless_wheel/rimless_wheel.h"
target="_blank">The rimless wheel model</a> actually uses a number of
the more nuanced features of <drake></drake> in order to simulate the
hybrid system accurately (as do many of the examples in this chapter).
It actually registers the collision events of the system -- the
simulator uses zero-crossing detection to ensure that the time/state
of collision is obtained accurately, and then applies the reset
map.</p>
<figure>
<img width="80%" src="figures/rimless_wheel_phase.svg"/>
<figcaption>Phase portrait of the rimless wheel
($m=1$, $l=1$, $g=9.8$, $\alpha=\pi/8$, $\gamma=0.08$).</figcaption>
</figure>
<p>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.</p>
</example>
</subsubsection> <!-- end of forward simulation -->
<subsubsection><h1>Poincaré Map</h1>
<p>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 $\gamma \le \alpha$
and $\dot\theta_n^+ > \omega_1$. The "step-to-step return map",
factoring losses from a single collision, the resulting map is:
$$\dot\theta^{+}_{n+1} = \cos(2\alpha) \sqrt{ ({\dot\theta_n}^{+})^{2} +
4\frac{g}{l}\sin\alpha \sin\gamma}.$$ where the $\dot{\theta}^{+}$
indicates the velocity just <em>after</em> the energy loss at impact has
occurred.</p>
<p>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 $$\omega_2 = - \sqrt{2 \frac{g}{l} [1 - \cos(\alpha + \gamma)]}.$$
For $\omega_2 < \dot\theta_n^{+} < \omega_1,$ we have
$$\dot\theta_{n+1}^{+} = -\dot\theta_n^{+} \cos(2\alpha).$$ Finally, for
$\dot\theta_n^{+} < \omega_2$, we have $$\dot\theta_{n+1}^{+} = -
\cos(2\alpha)\sqrt{(\dot\theta_n^{+})^2 - 4 \frac{g}{l} \sin\alpha
\sin\gamma}.$$ Altogether, we have (for $\gamma \le \alpha$)
$$\dot\theta_{n+1}^{+} = \begin{cases} \cos(2\alpha)
\sqrt{(\dot\theta_n^{+})^2 + 4 \frac{g}{l} \sin\alpha \sin\gamma}, &
\text{ } \omega_1 < \dot\theta_n^{+} \\ -\dot\theta_n^{+} \cos(2\alpha),
& \text{ } \omega_2 < \dot\theta_n^{+} < \omega_1 \\ -\cos(2\alpha)
\sqrt{(\dot\theta_n^{+})^2 - 4\frac{g}{l} \sin\alpha \sin\gamma}, &
\dot\theta_n^{+} < w_2 \end{cases}.$$ </p>
<p>Notice that the return map is undefined for $\dot\theta_n = \{
\omega_1, \omega_2 \}$, because from these configurations, the wheel
will end up in the (unstable) equilibrium point where $\theta = 0$ and
$\dot\theta = 0$, and will therefore never return to the map.</p>
<p>This return map blends smoothly into the case where $\gamma >
\alpha$. In this regime, $$\dot\theta_{n+1}^{+} = \begin{cases}
\cos(2\alpha) \sqrt{(\dot\theta_n^{+})^2 + 4 \frac{g}{l} \sin\alpha
\sin\gamma}, & \text{ } 0 \le \dot\theta_n^{+} \\ -\dot\theta_n^{+}
\cos(2\alpha), & \text{ } \omega_2 < \dot\theta_n^{+} < 0 \\
-\cos(2\alpha) \sqrt{(\dot\theta_n^{+})^2 - 4\frac{g}{l} \sin\alpha
\sin\gamma}, & \dot\theta_n^{+} \le w_2 \end{cases}.$$ Notice that the
formerly undefined points at $\{\omega_1,\omega_2\}$ are now
well-defined transitions with $\omega_1 = 0$, because it is
kinematically impossible to have the wheel statically balancing on a
single leg.</p>
</subsubsection> <!-- poincare map -->
<subsubsection><h1>Fixed Points and Stability</h1>
<p>For a fixed point, we require that $\dot\theta_{n+1}^{+} =
\dot\theta_n^{+} = \omega^*$. Our system has two possible fixed points,
depending on the parameters: $$ \omega_{stand}^* = 0,~~~ \omega_{roll}^*
= \cot(2 \alpha) \sqrt{4 \frac{g}{l} \sin\alpha\sin\gamma}.$$ The limit
cycle plotted above illustrates a state-space trajectory in the vicinity
of the rolling fixed point. $\omega_{stand}^*$ is a fixed point whenever
$\gamma < \alpha$. $\omega_{roll}^*$ is a fixed point whenever
$\omega_{roll}^* > \omega_1$. It is interesting to view these
bifurcations in terms of $\gamma$. For small $\gamma$, $\omega_{stand}$
is the only fixed point, because energy lost from collisions with the
ground is not compensated for by gravity. As we increase $\gamma$, 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 $\gamma$ further to $\gamma > \alpha$, it becomes
impossible for the center of mass of the wheel to be inside the support
polygon, making standing an unstable configuration.</p>
<figure> <img width="100%" src="figures/rw_retmap.svg"/>
<figcaption>Limit cycle trajectory of the rimless wheel
($m=1,l=1,g=9.8,\alpha=\pi/8,\gamma=0.15$). All hatched regions
converge to the rolling fixed point, $\omega_{roll}^*$; the white
regions converge to zero velocity ($\omega_{stand}^*$).</figcaption>
</figure>
</subsubsection>
<subsubsection><h1>Stability of standing still</h1>
<p>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. It's a little subtle. [Coming soon.]</p>
<todo>call out to the fact that I left the origin OUT of the poincare map on the van der pol.</todo>
</subsubsection>
</subsection> <!-- end rimless wheel -->
<subsection id="compass_gait"><h1>The Compass Gait</h1>
<p>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 ($\bu = 0$).</p>
<figure>
<img width="45%" src="figures/compass_gait.svg"/>
<figcaption>The compass gait</figcaption>
</figure>
<p>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 <elib>Goswami96a+Goswami99+Spong03</elib>, but relatively little
is known about it analytically.</p>
<p>The state of this robot can be described by 4 variables:
$\theta_{st},\theta_{sw},\dot\theta_{st}$, and $\dot\theta_{sw}$. The
abbreviation $st$ is shorthand for the stance leg and $sw$ for the swing
leg. Using $\bq = [ \theta_{st}, \theta_{sw} ]^T$ and $\bu = \tau$, we can
write the dynamics as $$\bM(\bq)\ddot\bq + \bC(\bq,\dot\bq)\dot\bq =
\btau_g(q) + \bB\bu,$$ with \begin{gather*} \bM = \begin{bmatrix}
(m_h+m)l^2 + ma^2 & -mlb\cos(\theta_{st}-\theta_{sw}) \\
-mlb\cos(\theta_{st}-\theta_{sw}) & mb^2 \end{bmatrix}\\ \bC =
\begin{bmatrix} 0 & -mlb\sin(\theta_{st}-\theta_{sw})\dot\theta_{sw} \\
mlb\sin(\theta_{st}-\theta_{sw})\dot\theta_{st} & 0 \end{bmatrix} \\
\btau_g(q) = \begin{bmatrix} (m_hl + ma + ml)g\sin(\theta_{st}) \\
-mbg\sin(\theta_{sw}) \end{bmatrix},\\ \bB = \begin{bmatrix} -1 \\ 1
\end{bmatrix} \end{gather*} and $l=a+b$.</p>
<!-- My derivation is here: https://www.wolframcloud.com/objects/02914093-8fcd-4bd2-abb3-e76ca196b393 -->
<p>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 <a href="multibody.html#impulsive_collision">derived in the
appendix</a>. To use it, we proceed with the following steps:</p>
<ul> <li>Add a "floating base" to the system by adding a free (x,y) joint
at the pre-impact stance toe, $\bq_{fb} =
[x,y,\theta_{st},\theta_{sw}]^T.$</li> <li>Calculate the mass matrix for
this new system, call it $\bM_{fb}$.</li> <li>Write the position of the
(pre-impact) swing toe as a function $\bphi(\bq_{fb})$. Define the
Jacobian of this function: $\bJ = \frac{\partial \bphi}{\partial
\bq_{fb}}.$</li> <li>The post-impact velocity that ensures that $\dot\bphi
= 0$ after the collision is given by $$\dot\bq^+ = \left[ \bI -
\bM_{fb}^{-1}\bJ^T[\bJ\bM_{fb}^{-1}\bJ^T]^{-1}\bJ\right] \dot\bq^-,$$
noting that $\dot{x}^- = \dot{y}^- = 0$, and that you need only read out
the last two elements of $\dot{\bq}^+$. The velocity of the post-impact
stance foot will be zero by definition, and the new velocity of the
pre-impact stance foot can be completely determined from the minimal
coordinates.</li> <li>Switch the stance and swing leg positions and
velocities.</li> </ul>
<!-- My derivation is here:
https://www.wolframcloud.com/objects/60e3d6c1-156f-4604-bf70-1e374f471407
-->
<example><h1>Numerical simulation of the compass gait</h1>
<p>You can simulate the passive compass gait using:</p>
<jupyter>examples/simple_legs.ipynb</jupyter>
<p>Try playing with the initial conditions. You'll find this system is
<i>much</i> more sensitive to initial conditions than the rimless wheel.
It actually took some work to find the initial conditions that make it
walk stably.</p>
</example>
<p>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 <elib>Goswami96a</elib>.</p>
<figure> <img width="90%" src="figures/compass_gait_limit_cycle.svg"/>
<figcaption>Passive limit cycle trajectory of the compass gait. ($m=5$kg,
$m_h=10$kg, $a=b=0.5$m, $\phi=0.0525$rad. $\bx(0)=[0,0,0.4,-2.0]^T$).
Drawn is the phase portait of the left leg angle, which is recovered from
$\theta_{st}$ and $\theta_{sw}$ in the simulation with some simple
book-keeping.</figcaption> </figure>
<p>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 difficult to implement on a physical device.</p>
</subsection>
<subsection id="kneed_walker"><h1>The Kneed Walker</h1>
<p>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<elib>Hsu07</elib>. The mathematical modeling
would be simpler if we used a single link for the stance leg, but we'll go
ahead and use two links for each leg (and each with a point mass) because
this robot can actually be built!</p>
<figure>
<img width="60%" src="figures/kneedwalker.svg"/>
<figcaption>The Kneed Walker</figcaption>
</figure>
<p>At the beginning of each step, the system is modeled as a three-link
pendulum, like the ballistic
walker<elib>McMahon80+Mochon80+Spong03</elib>. The stance leg is the one
in front, and it is the first 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 knee-strike is modeled as a discrete inelastic
collision, conserving angular momentum and changing velocities
instantaneously.</p>
<p>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.</p>
<figure>
<img width="100%" src="figures/kwcycle1.svg"/>
<figcaption>Limit cycle trajectory for kneed walker</figcaption>
</figure>
<p>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.</p>
<figure>
<img width="90%" src="figures/kwLimitCycle.svg"/>
<figcaption>Limit cycle (phase portrait) of the kneed walker</figcaption>
</figure>
<todo>reproduce this model in drake.</todo>
</subsection>
<subsection><h1>Curved feet</h1>
<p>The region of attraction of the kneed-walking limit cycle can be improved considerably by the addition of curved feet...</p>
<todo>also knee "de-bouncers" (suction cups). Simulation model?</todo>
<figure>
<iframe width="560" height="315" src="https://www.youtube.com/embed/WOPED7I5Lac" frameborder="0" allow="accelerometer; autoplay; encrypted-media; gyroscope; picture-in-picture" allowfullscreen></iframe>
<figcaption>Tad McGeer's kneed walker. <a href="https://www.youtube.com/watch?v=Uv7gDLWCZug">Here is</a> Matt Haberland's guide to launching it successfully. It's nontrivial!</figcaption>
</figure>
</subsection>
<subsection id="strandbeest"><h1>And beyond...</h1>
<p>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 <a
href="https://www.strandbeest.com/">Strandbeest</a>. There are many
variations of these amazing machines -- including his <a href="https://youtu.be/LewVEF2B_pM" target="_blank">beach walkers which
are powered only by the wind</a> (I've actually been able to visit Theo's
workshop once; it is <i>very</i> windy there).</p>
<p>These results are very real. Robin Deits (an exceptionally talented
student who felt particularly inspired once on a long weekend) once
reproduced one of his most early creations in <drake></drake>.</p>
<figure>
<iframe width="560" height="315"
src="https://www.youtube.com/embed/H6fL-8ScUnU?rel=0" frameborder="0"
allow="autoplay; encrypted-media" allowfullscreen></iframe>
<figcaption>Robin Deits' <a href="https://github.com/RobotLocomotion/drake/tree/last_sha_with_original_matlab/drake/examples/Strandbeest">simulation of the Strandbeest</a>.</figcaption>
</figure>
</subsection>
</section> <!-- end of walking -->
<section><h1>Simple Models of Running</h1>
<p>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.</p>
<p>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.</p>
<p>Shortly after Raibert built his machines, Dan Koditschek and Martin
Buehler started analyzing them with simpler models
<elib>Koditschek91</elib>. Years later, in collaboration with biologist Bob
Full, they started to realize that the simple models used to describe the
dynamics of Raibert's hoppers could also be used to describe experimental
data obtained from running animals. In fact, they described an incredible
range of experimental results, for animals ranging in size from a cockroach
up to a horse<elib>Full99</elib> (I think the best overall summary of this
line of work is <elib>Holmes06</elib>). The most successful of the simple
models was the so-called "spring-loaded inverted pendulum" (or "SLIP", for
short).</p>
<subsection><h1>The Spring-Loaded Inverted Pendulum</h1>
<p>The model is a point mass, $m$, on top of a massless, springy leg with
rest length of $l_0$, and spring constant $k$. The state of the system
is given by the $x,y$ position of the center of mass, and the length,
$l$, and angle $\theta$ of the leg. Like the rimless wheel, the dynamics
are modeled piecewise - with one dynamics governing the flight phase, and
another governing the stance phase.</p>
<p>Flight Phase. State variables: $\bx = [x,y,\dot{x},\dot{y}]^T.$
Dynamics are $$\dot{\bx} = \begin{bmatrix} \dot{x} \\ \dot{y} \\ 0 \\ - g
\end{bmatrix}.$$</p>
<p>Stance Phase. State variables: $\bx = [r, \theta, \dot{r},
\dot\theta]^T.$ Kinematics are $$x = \begin{bmatrix} - r \sin\theta \\ r
\cos\theta \end{bmatrix},$$ Energy is given by $$T = \frac{m}{2}
(\dot{r}^2 + r^2 \dot\theta^2 ), \quad U = mgr\cos\theta +
\frac{k}{2}(r_0 - r)^2.$$ Plugging these into Lagrange yields:
\begin{gather} m \ddot{r} - m r \dot\theta^2 + m g \cos\theta - k (r_0 -
r) = 0 \\ m r^2 \ddot{\theta} + 2mr\dot{r}\dot\theta - mgr \sin\theta = 0
\end{gather}</p>
<example><h1>Simulation of the SLIP model</h1>
<p>You can simulate the spring-loaded inverted pendulum using:</p>
<jupyter>examples/spring_loaded_inverted_pendulum.ipynb</jupyter>
<p>Make sure that you take time to interpret the apex-to-apex map that is plotted in the notebook.</p>
</example>
</subsection>
<subsection id="leglab"><h1>Hopping Robots from the MIT Leg Laboratory</h1>
<figure>
<iframe width="560" height="315"
src="https://www.youtube.com/embed/Bd5iEke6UlE" frameborder="0"
allow="accelerometer; autoplay; encrypted-media; gyroscope;
picture-in-picture" allowfullscreen></iframe>
</figure>
<subsubsection><h1>The Planar Monopod Hopper</h1>
<p>A three-part control strategy: decoupling the control of hopping
height, body attitude, and forward velocity <elib>Raibert86a</elib>.</p>
</subsubsection>
<subsubsection><h1>Running on four legs as though they were
one</h1>
<p>bipeds, quadrupeds, and backflips...<elib>Raibert86</elib></p>
</subsubsection>
</subsection>
</section> <!-- end of running -->
<section><h1>A Simple Model That Can Walk and Run</h1>
</section> <!-- end of walk+run -->
<section><h1>Exercises</h1>
<exercise><h1>Searching for Limit Cycles via Trajectory Optimization</h1>
<p>In this exercise we use trajectory optimization to identify a limit
cycle for the compass gait. We use a rather general approach: the robot
dynamics is described in floating-base coordinates and frictional contacts
are accurately modeled. <a href="https://colab.research.google.com/github/RussTedrake/underactuated/blob/master/exercises/simple_legs/compass_gait_limit_cycle/compass_gait_limit_cycle.ipynb" target="_blank">In this notebook</a>,
you are asked to code many of the constraints this optimization
problem requires:</p>
<ol type="a">
<li>Enforce the contact between the stance foot and the ground at all
the break points.</li>
<li>Enforce the contact between the swing foot and the ground at the
initial time.</li>
<li>Prevent the penetration of the swing foot in the ground at all
the break points. (In this analysis, we will neglect the scuffing
between the swing foot and the ground which arises when the swing leg
passes the stance leg.)</li>
<li>Ensure that the contact force at the stance foot lies in the
friction cone at all the break points.</li>
<li>Ensure that the impulse generated by the collision of the swing foot
with the ground lies in the friction cone.</li>
</ol>
</exercise>
<exercise><h1>One-Dimensional Hopper</h1>
<p>In this exercise we implement a one-dimensional version of the controller proposed in <elib>Raibert84</elib>. The goal is to control the vertical motion of a hopper by generating a stable resonant oscillation that causes the system to hop off the ground at a given height. We accomplish this via a careful energy analysis of the hopping cycle: all the details are in <a href="https://colab.research.google.com/github/RussTedrake/underactuated/blob/master/exercises/simple_legs/one_d_hopper/one_d_hopper.ipynb" target="_blank">this notebook</a>. Besides understanding in detail the dynamics of the hopping system, in <a href="https://colab.research.google.com/github/RussTedrake/underactuated/blob/master/exercises/simple_legs/one_d_hopper/one_d_hopper.ipynb" target="_blank">the notebook</a>, you are asked to write two pieces of code:</p>
<ol type="a">
<li>A function that, given the state of the hopper, returns its total mechanical energy.</li>
<li>The hopping controller class. This is a <drake></drake> VectorSystem that, at each sampling time, reads the state of the hopper and returns the preload of the hopper spring necessary for the system to hop at the desired height. All the necessary information for the synthesis of this controller are given in <a href="https://colab.research.google.com/github/RussTedrake/underactuated/blob/master/exercises/simple_legs/one_d_hopper/one_d_hopper.ipynb" target="_blank">the notebook</a>.</li>
</ol>
</exercise>
</section>
</chapter>
<!-- EVERYTHING BELOW THIS LINE IS OVERWRITTEN BY THE INSTALL SCRIPT -->
<div id="references"><section><h1>References</h1>
<ol>
<li id=Strogatz94>
<span class="author">Steven H. Strogatz</span>,
<span class="title">"Nonlinear Dynamics and Chaos: With Applications to Physics, Biology, Chemistry, and Engineering"</span>,Perseus Books
, <span class="year">1994</span>.
</li><br>
<li id=Koditschek91>
<span class="author">Daniel E. Koditschek and Martin Buehler</span>,
<span class="title">"Analysis of a Simplified Hopping Robot"</span>,
<span class="publisher">International Journal of Robotics Research</span>, vol. 10, no. 6, pp. 587-605, Dec, <span class="year">1991</span>.
</li><br>
<li id=Collins01>
<span class="author">Steven H. Collins and Martijn Wisse and Andy Ruina</span>,
<span class="title">"A Three-Dimensional Passive-Dynamic Walking Robot with Two Legs and Knees"</span>,
<span class="publisher">International Journal of Robotics Research</span>, vol. 20, no. 7, pp. 607-615, July, <span class="year">2001</span>.
</li><br>
<li id=McMahon80>
<span class="author">Simon Mochon and Thomas A. McMahon</span>,
<span class="title">"Ballistic walking: An improved model"</span>,
<span class="publisher">Mathematical Biosciences</span>, vol. 52, no. 3-4, pp. 241-260, December, <span class="year">1980</span>.
</li><br>
<li id=McGeer90>
<span class="author">Tad McGeer</span>,
<span class="title">"Passive Dynamic Walking"</span>,
<span class="publisher">International Journal of Robotics Research</span>, vol. 9, no. 2, pp. 62-82, April, <span class="year">1990</span>.
</li><br>
<li id=Coleman98a>
<span class="author">Michael J. Coleman</span>,
<span class="title">"A Stability Study of a Three-Dimensional Passive-Dynamic Model of Human Gait"</span>,
PhD thesis, Cornell University, <span class="year">1998</span>.
</li><br>
<li id=Goswami96a>
<span class="author">Ambarish Goswami and Benoit Thuilot and Bernard Espiau</span>,
<span class="title">"Compass-Like Biped Robot Part {I} : Stability and Bifurcation of Passive Gaits"</span>,
Tech. Report, RR-2996, October, <span class="year">1996</span>.
</li><br>
<li id=Goswami99>
<span class="author">A. Goswami</span>,
<span class="title">"Postural stability of biped robots and the foot rotation indicator ({FRI}) point"</span>,
<span class="publisher">International Journal of Robotics Research</span>, vol. 18, no. 6, <span class="year">1999</span>.
</li><br>
<li id=Spong03>
<span class="author">Mark W. Spong and Gagandeep Bhatia</span>,
<span class="title">"Further Results on Control of the Compass Gait Biped"</span>,
<span class="publisher">Proc. IEEE International Conference on Intelligent Robots and Systems (IROS)</span>, pp. 1933-1938, <span class="year">2003</span>.
</li><br>
<li id=Hsu07>
<span class="author">Vanessa Hsu</span>,
<span class="title">"Passive dynamic walking with knees: A Point-foot model"</span>,
, February, <span class="year">2007</span>.
[ <a href="http://groups.csail.mit.edu/robotics-center/public_papers/Hsu07.pdf">link</a> ]
</li><br>
<li id=Mochon80>
<span class="author">Simon Mochon and Thomas A. McMahon</span>,
<span class="title">"Ballistic Walking"</span>,
<span class="publisher">Journal of Biomechanics</span>, vol. 13, pp. 49-57, <span class="year">1980</span>.
</li><br>
<li id=Full99>
<span class="author">R.J. Full and D.E. Koditschek</span>,
<span class="title">"Templates and anchors: neuromechanical hypotheses of legged locomotion on land"</span>,
<span class="publisher">Journal of Experimental Biology</span>, vol. 202, no. 23, pp. 3325-3332, <span class="year">1999</span>.
</li><br>
<li id=Holmes06>
<span class="author">Philip Holmes and Robert J. Full and Dan Koditschek and John Guckenheimer</span>,
<span class="title">"The Dynamics of Legged Locomotion: Models, Analyses, and Challenges"</span>,
<span class="publisher">Society for Industrial and Applied Mathematics (SIAM) Review</span>, vol. 48, no. 2, pp. 207--304, <span class="year">2006</span>.
</li><br>
<li id=Raibert86a>
<span class="author">Marc H. Raibert</span>,
<span class="title">"Legged Robots That Balance"</span>,The MIT Press
, <span class="year">1986</span>.
</li><br>
<li id=Raibert86>
<span class="author">Raibert and M. H. and Chepponis and M. and Brown and H. B.</span>,
<span class="title">"Running on four legs as though they were one"</span>,
<span class="publisher">IEEE Journal of Robotics and Automation</span>, vol. 2, no. 2, pp. 70--82, <span class="year">1986</span>.
</li><br>
<li id=Raibert84>
<span class="author">Marc H. Raibert</span>,
<span class="title">"Hopping in legged systems: Modeling and simulation for the 2D one-legged case"</span>,
<span class="publisher">IEEE Trans. Systems, Man, and Cybernetics</span>, vol. 14, pp. 451-463, <span class="year">1984</span>.
</li><br>
</ol>
</section><p/>
</div>
<table style="width:100%;"><tr style="width:100%">
<td style="width:33%;text-align:left;"><a class="previous_chapter" href=acrobot.html>Previous Chapter</a></td>
<td style="width:33%;text-align:center;"><a href=index.html>Table of contents</a></td>
<td style="width:33%;text-align:right;"><a class="next_chapter" href=humanoids.html>Next Chapter</a></td>
</tr></table>
<div id="footer">
<hr>
<table style="width:100%;">
<tr><td><a href="https://accessibility.mit.edu/">Accessibility</a></td><td style="text-align:right">© Russ
Tedrake, 2021</td></tr>
</table>
</div>
</body>
</html>