You are on page 1of 14

12/1/2015

UnderactuatedRobotics

UNDERACTUATEDROBOTICS
AlgorithmsforWalking,Running,Swimming,Flying,andManipulation

RussTedrake
RussTedrake,2015
Howtocitethesenotes

Note:TheseareworkingnotesthatwillbeupdatedthroughouttheFall2015semester.
Previouschapter

Tableofcontents

APPENDIXD
Drake

D.1WHATISDRAKE?
Drake("dragon"inMiddleEnglish)isatoolboxmaintainedbytheRobotLocomotionGroup
at the MIT Computer Science and Artificial Intelligence Lab (CSAIL) which contains
implementations of many of the ideas from these notes. It was designed with the goal of
rapidly prototyping advanced control ideas, but has also been optimized (in places) for
performance it provides the complete planning and control backend for most of our
research robots, including MIT's entry into the DARPA Robotics Challenge, and now has
usersfromacademiaandindustryaroundtheworld.
DRAKEisimplementedusingahierarchyofsoftwareclasses(inMATLABandC++)which
are designed to expose and exploit available structure in inputoutput dynamical systems.
While some algorithms are available for general nonlinear systems, specialized algorithms
http://underactuated.csail.mit.edu/underactuated.html?chapter=26

1/14

12/1/2015

UnderactuatedRobotics

areavailableforpolynomialdynamicalsystems,lineardynamicalsystems,...,andespecially
rigidbody mechanical systems many of those algorithms operate symbolically on the
governingequations.Thetoolboxdoesalotofworkbehindthescenestomakesurethat,for
instance, feedback or cascade combinations of polynomial systems remain polynomial.
Anothermajorfocusisonnumericaloptimizationbaseddesignandanalysisforinstance,
in addition to providing a full rigidbody dynamics engine the software also provides
analyticalgradientsforthosedynamics.DRAKEparsesanumberofrobotdescriptionformats
(such as "URDF"), uses the Simulink solvers for simulation of dynamical systems, and
connectswithanumberofexternaltoolstofacilitatedesignandanalysis.
D.1.1RelativetoSimulinkandSimMechanics
Roughly speaking, MATLAB's Simulink provides a very nice interface for describing
dynamical systems (as SFunctions), a graphical interface for combining these systems in
verynontrivialways,andanumberofpowerfulsolversforsimulatingtheresultingsystems.
Forsimulationanalysis,itprovideseverythingweneed.HowevertheSFunctionabstraction
which makes Simulink powerful also hides some of the detailed structure available in the
equations governing a dynamical system for the purposes of control design and analysis I
wouldliketobeabletodeclarethataparticularsystemisgovernedbyanalyticequations,or
polynomialequations,orevenlinearequations,andformanyofthetoolsitisimportanttobe
abletomanipulatetheseequationssymbolically.
YoucanthinkofDRAKEasalayerbuiltontopoftheSimulinkenginewhichallowsyouto
defined structured dynamical systems. Every dynamical system in DRAKE can be simulated
using the Simulink engine, but DRAKE also provides a number of tools for analysis and
controllerdesignwhichtakeadvantageofthesystemstructure.Whileitispossibletousethe
Simulink GUI with DRAKE, the standard workflow makes use of commandline methods
which provide a restricted set of tools for combining systems in ways that, whenever
possible,preservethestructureintheequations.
LikeSimMechanics,DRAKEprovidesanumberoftoolsforworkingspecificallywithmulti
linkrigidbodysystems.InSimMechanics,youcandescribethesystemdirectlyintheGUI
whereasinDRAKEyoudescribethesysteminanXMLfile.SimMechanicshasanumberof
nice features, such as integration with SolidWorks, and almost certainly provides more
richnessandfastercodeforsimulatingcomplexrigidbodysystems.DRAKEontheotherhand
willprovidemoresophisticatedtoolsforanalysisanddesign,butlikelywillneversupportas
manygears,frictionmodels,etc.asSimMechanics.
D.1.2Forcontrollingrealhardware
DRAKEalsohasmanyinterfaceswhichallowittoconnecttoothercomponentsofarobotic/
controlsystem.Inputsandoutputsofthedynamicalsystems,orstaticmatlabfunctions(e.g.
for trajectory planning), can be connected directly to network interfaces. We primarily use
Lightweight Communications and Marshalling (LCM) [100] to make these connections
support for other protocols (such as ROS) can be added easily or accomplished via an
independent network translator. This approach has been used extensively on real hardware
experiments at MIT, and formed the foundation of our solution for controlling a complex
humanoidforMIT'sentryintotheDARPARoboticsChallenge(withDrakenodesrunningin
desktopMATLABinstancesinsidetherealtimefeedbackloops).Inadditiontotheprimary
MATLAB front end, a number of methods for kinematics and dynamics of rigidbody
systemsarealsoavailabledirectlyasaC++library.

D.2GETTINGSTARTED
http://underactuated.csail.mit.edu/underactuated.html?chapter=26

2/14

12/1/2015

UnderactuatedRobotics

Foreverythingyouneedtogetstarted,includinginstallationinstructions,adiscussionforum,
and a (modest but growing) gallery of examples, please visit the DRAKE website:
http://drake.mit.edu.
The remainder of this chapter will give you an important conceptual overview of defining
andworkingwithdynamicalsystemsindrake,andwillgiveanumberofsimpleexamples
foryoutostartwith.
If you have questions, please search the previous questions on the githubissuespage, and
postanewquestionifyouaren'tabletofindthesolution.

D.3MODELINGINPUTOUPUTDYNAMICALSYSTEMS
ThefundamentalobjectinDRAKEisadynamicalsystem.Robots,controllers,stateestimators,
etc. are all instances of dynamical systems. Algorithms in DRAKE operate on dynamical
systems.Thischapterintroduceswhatyouneedtoknowtoinstantiatethedynamicalsystems
thatyouareinterestedin,andtosimulateandvisualizetheiroutputs.
DynamicalsystemsinDRAKEarerepresentedbytheirdynamicsinstatespaceform,with x
denotingthestatevector.Inaddition,everydynamicalsystemcanhaveaninputvector, u ,
andanoutputvectory .

As we will see, dynamical systems in DRAKE can be instantiated in a number of different


ways.AsystemcanbedescribedbyasmallblockofMATLABorC++codederivingfrom
our DrakeSystem class interface, or in the case of rigidbody systems even by simple
XML file (see the section below on the URDF format) that can be parsed by our existing
classimplementations.
D.3.1WritingyourowndynamicsinMATLAB
Inthissection,wewilldescribehowyoucanwriteyourowndynamicsclassinMATLABby
derivingfromtheDrakeSysteminterfaceclass.
ContinuousTime Systems. Consider a basic continuoustime nonlinear inputoutput
dynamicalsystemdescribedbythefollowingstatespaceequations:
= f (t, x, u),
x
y = g(t, x, u).

InDRAKE,youcaninstantiateasystemofthisformwhere f ()and g() areanythingthatyou


canwriteintoaMATLABfunction.Thisisaccomplishedbyderivingfromthe DrakeSystem
class, defining the size of the input, state, and output vectors in the constructor, and
overloadingthedynamicsandoutputmethods,asillustratedbythefollowingexample:
D.3.1Asimplecontinuoustimesystem)
Considerthesystem

http://underactuated.csail.mit.edu/underactuated.html?chapter=26

3/14

12/1/2015

UnderactuatedRobotics
3

= x + x ,
x
y = x.

This system has zero inputs, one (continuous) state variable, and one output. It can be
implementedinDRAKEusingthefollowingcode:
classdefSimpleCTExample<DrakeSystem
methods
functionobj=SimpleCTExample()
%calltheparentclassconstructor:
obj=obj@DrakeSystem(...
1,...%numberofcontinuousstates
0,...%numberofdiscretestates
0,...%numberofinputs
1,...%numberofoutputs
false,...%becausetheoutputdoesnotdependonu
true);%becausethedynamicsandoutputdonotdependont
end
functionxdot=dynamics(obj,t,x,u)
xdot=x+x^3;
end
functiony=output(obj,t,x,u)
y=x;
end
end
end

DiscreteTime Systems. Implementing a basic discretetime system in DRAKE is very


analogoustoimplementingacontinuoustimesystem.Thediscretetimesystemgivenby:
x[n + 1] = f (n, x, u),
y[n] = g(n, x, u),

can be implemented by deriving from DrakeSystem and defining the update and output
methods,asseeninthefollowingexample.
D.3.1Asimplediscretetimesystem)
Considerthesystem
3

x[n + 1] = x [n],
y[n] = x[n].

This system has zero inputs, one (discrete) state variable, and one output. It can be
implementedinDRAKEusingthefollowingcode:
classdefSimpleDTExample<DrakeSystem
methods
functionobj=SimpleDTExample()
%calltheparentclassconstructor:
obj=obj@DrakeSystem(...
0,...%numberofcontinuousstates
1,...%numberofdiscretestates
0,...%numberofinputs
1,...%numberofoutputs
http://underactuated.csail.mit.edu/underactuated.html?chapter=26

4/14

12/1/2015

UnderactuatedRobotics

false,...%becausetheoutputdoesnotdependonu
true);%becausetheupdateandoutputdonotdependont
end
functionxnext=update(obj,t,x,u)
xnext=x^3;
end
functiony=output(obj,t,x,u)
y=x;
end
end
end

Mixed Discrete and Continous Dynamics. It is also possible to implement systems that
havebothcontinuousdynamicsanddiscretedynamics.Therearetwosubtletiesthatmustbe
addressed.First,we'lldenotethediscretestatesas x andthecontinuousstatesas x ,and
the entire state vector x = [x , x ] . Second, we must define the timing of the discrete
dynamicsupdaterelativetothecontinuoustimevariable twe'lldenotethisperiodwith .
Thenamixedsystemcanbewrittenas:
d

T
d

T
c

c = f (t, x, u),
x
c

x d (t + t ) = f d (t, x, u),

t {0, t , 2 t , . . . }, t

(0, t ]

y = g(t, x, u).

Notethat,unlikethepurleydiscretetimeexample,thesolutionofthediscretetimevariable
isdefinedforallt.Toimplementthis,derivefromDrakeSystemandimplementthe dynamics,
update,outputmethodsfor f (),f (),and g() ,respectively.Todefinethetiming,youmust
also implement the getSampleTime method. Type help DrakeSystem/getSampleTime at the
MATLAB prompt for more information. Note that currently DRAKE only supports a single
DTsampletimeforeachindividualDrakeSystem(butmultiplesystemscanbecombinedwith
differentsamplingtimes).
c

D.3.1Amixeddiscreteandcontinuoustimeexample)
Considerthesystem

x 1 (t + t ) = x (t),
1

t {0, 1, 2, . . }, t

(0, 1],

2 = x 2 (t) + x (t),
x
2

which is the combination of the previous two examples into a single system. It can be
implementedinDRAKEusingthefollowingcode:
classdefSimpleMixedCTDTExample<DrakeSystem
methods
functionobj=SimpleMixedCTDTExample()
%calltheparentclassconstructor:
obj=obj@DrakeSystem(...
1,...%numberofcontinuousstates
1,...%numberofdiscretestates
0,...%numberofinputs
2,...%numberofoutputs
false,...%becausetheoutputdoesnotdependonu
true);%becausetheupdateandoutputdonotdependont
end
functionts=getSampleTime(obj)
ts=[[0;0],...%continuousanddiscretesampletimes
http://underactuated.csail.mit.edu/underactuated.html?chapter=26

5/14

12/1/2015

UnderactuatedRobotics

[1;0]];%withdt=1
end
functionxdnext=update(obj,t,x,u)
xdnext=x(1)^3;%theDTstateisx(1)
end
functionxcdot=dynamics(obj,t,x,u);
xcdot=x(2)+x(2)^3;%theCTstateisx(2)
end
functiony=output(obj,t,x,u)
y=x;
end
end
end

Systems with Constraints. Nonlinear inputoutput systems with constraints can also be
defined.There are two distinct types of constraints supported: state constraints that can be
modeled as a function (x) = 0 and input constraints which can be modeled as
u
u u
.For instance, we would write a continuoustime system with state and
inputconstraintsas:
min

max

= f (t, x, u),
x

y = g(t, x, u),

subject to(x) = 0, u min u u max .

Thesetwotypesofconstraintsarehandledquitedifferently.
Inputconstraintsaredesignedtoactinthesamewaythatanactuatorlimitmightworkfora
mechanicalsystem.Theseactasasaturationnonlinearitysystemattachedtotheinput,where
foreachelement:

yi =

u max,i

ifu i > u max,i

u min,i

ui

ifu i < u min,i


otherwise.

Theadvantageofusingtheinputlimitsinsteadofimplementingthesaturationinyourown
codeisthatthediscontinuityassociatedwithhittingorleavingasaturationiscommunicated
tothesolvercorrectly,allowingformoreefficientandaccuratesimulations.Inputconstraints
aresetbycallingthesetInputLimitsmethod.
Stateconstraintsareadditionalinformationthatyouareprovidingtothesolverandanalysis
routines.Theyshouldbereadas"thisdynamicalsystemwillonlyevervisitstatesdescribed
by (x) = 0 ".Evaluating the dynamics at a vector x for which (x) 0 may lead to an
undefinedornonsensibleoutput.TellingDRAKEaboutthisconstraintwillallowittoselect
initialconditionswhichsatisfytheconstraint,simulatethesystemmoreaccurately(withthe
constraint imposed), and restrict attention during analysis to the manifold defined by the
constraints.However,\emph{thestateconstraintsfunctionshouldnotbeusedtoenforcean
additionalconstraintthatisnotalreadyimposedonthesystembythegoverningequations.}.
Thestateconstraintshouldbesimplyannouncingapropertythatthesystemalreadyhas,if
simulatedaccurately.Examplesmightincludeapassivesystemwithaknowntotalenergy,or
afourbarlinkageinarigidbodywhosdynamicsarewrittenasakinematictree+constraint
forces. State constraints are implemented by overloading the stateConstraints method
\emph{and} by calling setNumStateConstraints to tell the solver what to expect in that
method.
Hybrid (EventDriven) Systems. DRAKE supports systems that are modeled as smooth,
discrete or continuous time systems which transition between discrete modes based on
http://underactuated.csail.mit.edu/underactuated.html?chapter=26

6/14

12/1/2015

UnderactuatedRobotics

some event. Simulink calls these models "State Machines". Examples include a walking
robotmodelwhichundergoesadiscreteimpulsivecollisionevent(andpossiblyachangetoa
differentmodel)whenafoothitstheground,ortheswitchingcontrollerforswingingupthe
underactuateddoublependulum(Acrobot)whichswitchesfromanenergyshapingswingup
controller to a linear balancing controller at the moment when the state arrives in a pre
specified neighborhood around the upright. An example hybrid system is illustrated in the
figurebelow.Notethattheinternalmodedynamicscouldalsohavediscretetimedynamics
ormixeddiscreteandcontinuoustimedynamics.

Eventdriven systems in DRAKE are described using the language from the Hybrid Systems
community. Transitions between individual modes are described by a guard function,
denotedby(t, x, u) inthefigure,whichtriggersatransitionoutofthecurrentmodewhen
0.The dynamics of the transition are given by the reset function, x
= (t, x , u) .
Eventdriven systems are constructed by creating (or inheriting from) an empty
HybridDrakeSystem, then populating the system with modes (nodes in the graph) by calling
addMode, and populating the system with transitions (edges in the graph) by calling
addTransition. Note that it is often useful to create guard out of a logical combination of
smooth guards (e.g. x(1) > 0 and x(2) < .5 ) to accomplish this you should use the
andGuard and notGuard methods. The output of a HybridDrakeSystem is the output of the
activemode.
+

D.3.1Thebouncingball:ahybridsystemexample)
ThedynamicsofaverticallybouncingballcanbedescribedbyaHybridDrakeSystemwitha
single continuous mode to model the flight of the ball through the air and a discrete
collisioneventatthemomentthattheballhittheground.Thiscanbeaccompishedwiththe
followingtwoclasses(whichcanbefoundintheexamples/BouncingBalldirectory):
classdefBallFlightPhasePlant<DrakeSystem
methods
functionobj=BallFlightPhasePlant()
obj=obj@DrakeSystem(...
2,...%numberofcontinuousstates
0,...%numberofdiscretestates
0,...%numberofinputs
1,...%numberofoutputs
false,...%notdirectfeedthrough
true);%timeinvariant
end
functionxdot=dynamics(obj,t,x,u)
xdot=[x(2);obj.g];%qddot=g;x=[q,qdot]
end
functiony=output(obj,t,x,u)
y=x(1);%heightoftheball
http://underactuated.csail.mit.edu/underactuated.html?chapter=26

7/14

12/1/2015

UnderactuatedRobotics

end
end
properties
g=9.81;%gravity
end
end

classdefBallPlant<HybridDrakeSystem
methods
functionobj=BallPlant()
obj=obj@HybridDrakeSystem(...
0,...%numberofinputs
1);%numberofoutputs
%createflightmodesystem
sys=BallFlightPhasePlant();
obj=setInputFrame(obj,sys.getInputFrame);
obj=setOutputFrame(obj,sys.getOutputFrame);
[obj,flight_mode]=addMode(obj,sys);%addthesinglemode
g1=inline('x(1)obj.r','obj','t','x','u');%qr<=0
g2=inline('x(2)','obj','t','x','u');%qdot<=0
obj=addTransition(obj,...
flight_mode,...%frommode
andGuards(obj,g1,g2),...%qr<=0&qdot<=0
@collisionDynamics,...%transitionmethod
false,...%notdirectfeedthrough
true);%timeinvariant
end
function[xn,m,status]=collisionDynamics(obj,m,t,x,u)
xn=[x(1);obj.cor*x(2)];%qdot=cor*qdot
if(xn(2)<0.01)status=1;%stopsimulatingifballhasstopped
elsestatus=0;end
end
end
properties
r=1;%radiusoftheball
cor=.8;%coefficientofrestitution
end
end

Stochastic Systems. DRAKE also provides limited support for working with stochastic
systems.Thisincludescontinuoustimestochasticmodelsoftheform
(t) = f (t, x(t), u(t), w(t))
x
y(t) = g(t, x(t), u(t), w(t)),

wherew(t) isthevectoroutputofarandomprocesswhichgeneratesGaussianwhitenoise.It
alsosupportsdiscretetimemodelsoftheform
x[n + 1] = f (n, x[n], u[n], w[n])
y[n] = g(n, x[n], u[n], w[n]),

[ ]
http://underactuated.csail.mit.edu/underactuated.html?chapter=26

8/14

12/1/2015

UnderactuatedRobotics

where w[n] is Gaussian i.i.d. noise, and mixed continuous and discretetime systems as
described above. These are quite general models, since nearly any distribution can be
approximated by a white noise input into a nonlinear dynamical system. Note that for
simulation purposes, any continuoustime white noise, w(t) , is approximated by a band
limitedwhitenoisesignal.
StochasticmodelscanbeimplementedinDRAKEbyderivingfromStochastiDrakeSystemand
implementingthestochasticDynamics,stochasticUpdate,andstochasticOutputmethods.
D.3.1Asimplecontinuoustimestochasticsystem)
Considerthesystem
= x + w,
x
y = x.

This system has zero inputs, one (continuous) state variable, and one output. It can be
implementedinDRAKEusingthefollowingcode:
classdefLinearGaussianExample<StochasticDrakeSystem
methods
functionobj=LinearGaussianExample
obj=obj@StochasticDrakeSystem(...
1,...%numberofcontinuousstates
0,...%numberofdiscretestates
0,...%numberofinputs
1,...%numberofoutputs
false,...%notdirectfeedthrough
true,...%timeinvariant
1,...%numberofnoiseinputs
.01);%timeconstantofw(t)
end
functionxcdot=stochasticDynamics(obj,t,x,u,w)
xcdot=x+w;
end
functiony=stochasticOutput(obj,t,x,u,w);
y=x;
end
end
end

ImportantSpecialCases.Therearemanyspecialcasesofdynamicalsystemswithstructure
in the dynamics which can be exploited by our algorithms. Special cases of dynamical
systemsimplementedinDRAKEinclude
Secondorder systems, given by q = f (t, q, q , u), y = g(t, q, q , u) , and
and (q, q ) = 0.
Rigidbodysystems,governedbythemanipulatorequations,

(q) = 0

+ C (q, q
)q
+ G(q) = Bu +
H (q)q

q
1 (q) = 0,

http://underactuated.csail.mit.edu/underactuated.html?chapter=26

1 +

) = 0
2 (q, q

9/14

12/1/2015

UnderactuatedRobotics

where and areforcesdefinedimplicitlybytheconstraints.


= f (t, x, u) ,y =
(Rational)polynomialsystems,givenbye(x)x
(x) = 0 ,wheree(), f (), g(), and() areallpolynomial.
Lineartimeinvariantsystems,givenby
1

g(t, x, u)

,subjectto

c = A c x + B c u,
x
x d [n + 1] = A d x + B d u,
y = C x + Du,

and(x)

= {}

These special cases are implemented by classes derived from DrakeSystem. You should
alwaysattempttoderivefromthedeepestclassinthehierarchythatdescribesyoursystem.
In some cases it is possible to convert between these derived classes. For example, it is
possible to convert a rigidbody system to a rational polynomial system (e.g., by changing
coordinatesthroughastereographicprojection).Methodswhichimplementtheseconversions
areprovidedwheneverpossible.
D.3.2DescribingarigidbodysystemwithURDF

URDF=UniversalRobotDescriptionFormat.Detailscomingsoon.
D.3.3UsingexistingSimulinkmodels/blocks

Although most users of Drake never open a Simulink GUI, DRAKE is built on top of the
MATLAB Simulink engine. As such, DRAKE systems can be used in any Simulink model,
andanyexistingSimulinkblockorSimulinkmodel(anentireSimulinkdiagram)whichhasa
single(vector)inputandsingle(vector)outputcanbeusedwiththeDRAKEinfrastructure.
D.3.4CombinationsofSystems

FigureD.1Feedbackcombination

FigureD.2Cascadecombination
Whenever possible, structure in the equations is preserved on combination. A polynomial
system that is feedback combined with another polynomial system produces a new
polynomialsystem.However,ifapolynomialsystemisfeedbackcombinedwithaSimulink
Block,thenthenewsystemisaDynamicalSystem,butnotaPolynomialSystem.
Acombinationoftwosystemsshouldreturnasystemofthetypethatistheleastcommon
ancestorintheclasshierarchy.Therearetwoexceptions:combinationswithahybridsystem
http://underactuated.csail.mit.edu/underactuated.html?chapter=26

10/14

12/1/2015

UnderactuatedRobotics

stayhybrid,andcombinationswithastochasticsystemstaystochastic.
D.3.5Coordinateframes
Every dynamical system in Drake has a number of coordinate frames associated with it,
including frames which describe the inputs, states, and outputs of the system. These
coordinate frames provide extra information about the vector signals, including a name for
each element. Must match to allow combination. Hybrid modes automatically inherit the
inputandoutputcoordinateframeofthehybridsystemthehybridsystemdoesnothavea
coordinateframeforthestate.

D.3.6
Simulation
OnceyouhaveacquiredaDynamicalSystemobjectdescribingthedynamicsofinterest,the
most basic thing that you can do is to simulate it. This is accomplished with the simulate
methodintheDynamicalSystemclass,whichtakesthetimespanofthesimulationasa1x2
vector of the form [t0 tf] and optionally a vector initial condition as input. Type help
DynamicalSystem/simulateforfurtherdocumentationaboutsimulationoptions.
EverysimulatemethodoutputsainstanceoftheTrajectoryclass.Toinspecttheoutput,you
maywanttoevaluatethetrajectoryatanysnapshotintimeusing eval,plottheoutputusing
fnplt,orhandthetrajectorytoavisualizer(describedbelow).
D.3.6
Simulatingthesimplesystemsandplottingtheresults)
UsethefollowingcodetoinstantiatetheSimpleCTExample,simulateit,andplottheresults:
sys=SimpleCTExample;
traj=simulate(sys,[010],.99);
fnplt(traj);

Theargumentspassedto simulatesettheinitialtimeto t = 0 ,finaltimeto t


initialconditiontox = .99.ThecodelooksthesamefortheSimpleDTExample:
0

= 5

,and

sys=SimpleDTExample;
traj=simulate(sys,[010],.99);
fnplt(traj);

Thesegeneratetheplotsbelow

http://underactuated.csail.mit.edu/underactuated.html?chapter=26

11/14

12/1/2015

UnderactuatedRobotics

FigureD.3SimulationofSimpleCTSystem(left)andSimpleDTSystem(right).
The simulatemethod sets the input, u , to the system to zero. In order to simulate with an
input tape, you should cascade a Trajectory object describing u(t) with the system, then
simulate. If you do not specify the initial conditions on your call to simulate, then the
getInitialState() method is called on your DynamicalSystem object. The default
getInitialStatemethodsets x = 0 youshouldconsideroverloadingthismethodinyour
DynamicalSystemclass.Inspecialcases,youmayneedtosetinitialconditionsbasedonthe
initialtimeorinputinthiscaseyoushouldoverloadthemethodgetInitialStateWInput.
0

Bydefault,DRAKEusestheSimulinkbackendforsimulation,andmakesuseofanumberof
Simulink's advanced features. For example, input limits can cause discontinuities in the
derivative of a continuous time system, which can potenially lead to inaccuracy and
inefficiencyinsimulationwithvariablestepsolversDRAKEavoidsthisbyregistering"zero
crossings" for each input saturation which allow the solver to handle the derivative
discontinuity event explicitly, without reducing the stepsize to achieve the accuracy
tolerance. You can change the Simulink solver parameters using the setSimulinkParam
method. For DrakeSystems, you can optionally use the MATLAB's ode45 suite of solvers
using the method simulateODE, which can also understand (most of) the Simulink solver
parameters.
D.3.7
Visualization
Visualizersaredynamicalsystems,too.
Playback
Useballbouncingasanexample.
Cascading.Usetherealtimeblock.
Outputingtoamovieformat

Thereareanumberofoptionsforcreatingamoviefilefromyoursimulation,dependingon
whichVisualizeryouused.Givenatrajectory,traj,andaVisualizerobject,v,use
playbackMovie(v,traj);

If you specify an extension in your filename when you are prompted, then playbackMovie
willattempttowriteinthespecifiedformat.Ifyouspecifyafilenamewithnoextension,then
http://underactuated.csail.mit.edu/underactuated.html?chapter=26

12/14

12/1/2015

UnderactuatedRobotics

youwillbepromptedwiththeoutputformatssupportedbyyourcurrentvisualizer.

D.4LISTINGOFDRAKEEXAMPLESTHROUGHOUTTHISTEXT
ThebestoverviewwehavefortheremainingcapabilitiesinDRAKEarethemainchaptersof
thesenotes.Forconvenience,hereisalistofsoftwareexamplesthataresprinkledthroughout
thetext:
Chapter1:FullyactuatedvsUnderactuatedSystems
RobotManipulators
FeedbackCancellationDoublePendulum
Chapter3:Acrobots,CartPoles,andQuadrotors
TheAcrobotinMATLAB
TheCartPoleSysteminMATLAB
LQRfortheAcrobotandCartPole
LQRforaQuadrotors
Chapter4:WalkingandRunning
Numericalsimulationoftherimlesswheel
Chapter9:DynamicProgramming
GridWorld
DynamicProgrammingfortheDoubleIntegrator
DynamicProgrammingfortheSimplePendulum
Chapter11:LyapunovAnalysis
CommonLyapunovanalysisforlinearsystems
GlobalstabilityofthesimplependulumviaSOS
Regionofattractionfortheonedimensionalcubicsystem
Searchingfortheregionofattraction
RegionofattractionforthetimereversedVanderPoloscillator
Chapter12:TrajectoryOptimization
DirectTranscriptionfortheDoubleIntegrator
DirectCollocationfortheDoubleIntegrator
Chapter13:AlgorithmsforLimitCycles
FindingthelimitcycleoftheVanderPoloscillator
Chapter15:MotionPlanningasSearch
PlanningwithaRandomTree
AppendixD:Drake
Asimplecontinuoustimesystem
Asimplediscretetimesystem
Amixeddiscreteandcontinuoustimeexample
Thebouncingball:ahybridsystemexample
Asimplecontinuoustimestochasticsystem
Simulatingthesimplesystemsandplottingtheresults

D.5EXTERNALINTERFACES
ThissectionexplainsthemostcommonwaysthatweinterfaceDRAKEwithrealrobotsusing
simple network protocols. Typically one or more instances of (desktop) MATLAB are up
running methods/systems in DRAKE as nodes in a planning/estimation/control network.
However we are rapidly porting the more mature functionality down into C++ so that it is
availableasalibraryorforstandaloneapplications.
D.5.1LightweightCommunicationsandMarshalling(LCM)
http://underactuated.csail.mit.edu/underactuated.html?chapter=26

13/14

12/1/2015

UnderactuatedRobotics

LCM is a simple, elegant, and efficient network protocol developed at MIT during the
DARPAUrbanChallenge(http://lcmproj.github.io/)[101].ForDRAKE,weprimarilyinteract
with LCM via the MATLAB/Java interface and lcmjava. For some highperformance
applications,wewritecustomCmexfunctionwhichsendandreceiveLCMmessages.
LCMCoders

LCMpassesmessagesdefinedinanlcmtypefilewhichcandescribeanalmostarbitrarydata
structure.Draketrafficsprimarilyinsignals,whichare(timestamped)vectorsofdoubles.To
convertbetweenthetwo,wedefinean LCMCoderclasswhichdefineshowto encodeadouble
astherichdatastructureanddecodethedatastructurebackintoadouble.
You can implement your LCMCoder directly in MATLAB or in Java. The LCMCoderFromType
classcanalsoconstructoneautomaticallyusingJavareflectionitsimplyconcatenatesthe
elementsofthestructureintoadoublevectorintheorderthattheyappearinthelcmtypefile.
LCMCoordinateFrames

Any coordinate frame can be associated with an LCMCoder by deriving from the
LCMCoordinateFrameclass.
In order to use any DynamicalSystem as a node in the LCM network, simply call
runLCM(sys,...) instead of simulate(sys,...) this will automatically attach LCM input
blocks and LCM output blocks on any input/output frames of the system that are of type
LCMCoordinateFrame, and then simulate the system. The runLCM method takes a number of
optionalargumentsallowingyoutorefinethisinteraction.
D.5.2InterfacingwithROS
The Robot Operating System (ROS) is an immensely popular suite of tools for robotics
research. Nodes in the ROS network communicate with a very similar message passing
systemtoLCMoneprimarydifferentisthatROSisbasedonTCP/IPandaserver/client
networkconfiguration,whereLCMisbasedonalltoallmulticastUDP.Typicallywhenwe
needDraketoactasanodeinaROSnetwork(ortosubscribetoROSmessages),wesend
andreceiveLCMmessagesandhaveathin"ROSLCMtranslator"appthatconnectsthetwo
networks.
WiththeMathWork'srecentlyannouncedsupportforROS,implementingsomethinglikea
ROSCoordinateFrameisnowonourshorttermtodolist.

D.6THEONLINECOMMUNITY
Again,pleaseengageusontheforumsontheDRAKEwebsite,http://drake.mit.eduifyouhave
questions or find any problems with these examples. Andpleasemakesureyousearchthe
existingissuesfirst.
Previouschapter
UnderactuatedRobotics

http://underactuated.csail.mit.edu/underactuated.html?chapter=26

Tableofcontents
RussTedrake,2015

14/14

You might also like