-
Notifications
You must be signed in to change notification settings - Fork 868
/
Copy pathcomputation.rst
1662 lines (1342 loc) · 109 KB
/
computation.rst
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
992
993
994
995
996
997
998
999
1000
Computation
===========
Introduction
------------
This chapter describes the mathematical and algorithmic foundations of MuJoCo. The overall framework is fairly standard
for readers familiar with modeling and simulation in generalized or joint coordinates. Therefore we summarize that
material briefly. Most of the chapter is devoted to how we handle contacts and other constraints. This approach is based
on our recent research and is unique to MuJoCo, so we take the time to motivate it and explain it in detail. Additional
information can be found in the paper below, although some of the technical ideas in this chapter are new and have not
been described elsewhere.
`Analytically-invertible dynamics with contacts and constraints: Theory and implementation in MuJoCo
<https://scholar.google.com/scholar?cluster=9217655838195954277>`__ E. Todorov (2014).
.. _Motivation:
Motivation for MuJoCo's convex soft contact model
-------------------------------------------------
Robots as well as humans interact with their environment primarily through physical contact. Given the increasing
importance of physics modeling in robotics, machine learning, animation, virtual reality, biomechanics and other fields,
there is need for simulation models of contact dynamics that are both physically accurate and computationally efficient.
One application of simulation models is to assess candidate estimation and control strategies before deploying them on
physical systems. Another application is to automate the design of those strategies - usually through numerical
optimization that uses simulation in an inner loop. The latter application imposes an additional constraint: the
objective function defined with respect to the contact dynamics should be amenable to numerical optimization. The
contact model underlying MuJoCo has benefits along these and other relevant dimensions. In the following sections we
discuss its benefits, while clarifying the differences from the linear complementarity (LCP) family of contact models
which are the *de facto* standard.
.. _moRealism:
Physical realism and soft contacts
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
Many of the advantages of our contact model can be traced to the fact that we drop the strict complementarity constraint
at the heart of the LCP formulation. We will call this family of models convex; see :ref:`References` for related work.
For frictionless contacts dropping the explicit complementarity constraint makes no difference, because the
Karush-Kuhn-Tucker (KKT) optimality conditions for the resulting convex quadratic program are equivalent to an LCP. But
for frictional contacts there are differences.
If one sees convex models as approximations to LCP, the logical question to ask is how good that approximation is.
However we do not see it that way. Instead, we see both LCP models and convex models as different approximations to
physical reality, each with its strengths and weaknesses. The immediate consequence of dropping strict complementarity
and replacing it with a cost is that complementarity can be violated - meaning that force and velocity in the contact
normal direction can be simultaneously positive, and frictional forces may not be maximally dissipative. A related
phenomenon is that the only way to initiate slip is to generate some motion in the normal direction. These effects are
numerically small yet undesirable. This shortcoming however has little practical relevance, because it is premised on
the assumption of hard contact. Yet all physical materials allow some deformation. This is particularly important in
robotics, where the parts of the robot that come in contact with the environment are usually designed to be soft. For
soft contacts complementarity has to be violated: when there is penetration and the material is pushing the contacting
bodies apart, both the normal force and velocity are positive. Furthermore if an object is resting on a soft surface
with some penetration, and we push it sideways, we would expect it to move up a bit as it starts sliding. So the
deviations from LCP actually increase physical realism in the presence of soft contacts.
Of course not every soft model is desirable; for example spring-damper models are soft but are plagued by instabilities.
At the same time different materials have different profiles, and so unlike hard contact models, a soft model must have
sufficiently rich parameterization if it is to be adapted to multiple systems of interest. This in turn facilitates
system identification of contact model parameters.
.. _moEfficiency:
Computational efficiency
~~~~~~~~~~~~~~~~~~~~~~~~
LCP models with frictional contact correspond to NP-hard optimization problems. This has given rise to an industry of
approximate solvers, with the unfortunate side-effect that many popular physics engines use poorly-documented shortcuts
and the resulting equations of motion are difficult to characterize. To be fair, NP-hardness is a statement about
worst-case performance and does not mean that solving the LCP quickly is impossible in practice. Still, convex
optimization has well-established advantages. In MuJoCo we have observed that for typical robotic models, 10 sweeps of a
projected Gauss-Seidel method (PGS) yield solutions which for practical purposes are indistinguishable from the global
minimum. Of course there are problems that are much harder to solve numerically, even though they are convex, and for
such problems we have conjugate gradient solvers with higher-order convergence.
The requirements for computational efficiency are different depending on the use case. If all we need is real-time
simulation, modern computers are fast enough to handle most robotic systems of interest even with inefficient solvers.
In the context of optimization however, there is no such thing as fast-enough simulation. If the objective functions and
their derivatives can be computed faster, this translates into larger search horizons or training sets or sample sizes,
which in turn leads to increased performance. This is why we have invested a lot of effort in developing efficient
solvers.
.. _moContinuous:
Continuous time
~~~~~~~~~~~~~~~
One might have thought that the equations of motion for any physical system would be uniquely defined in continuous
time. However frictional contacts are problematic because the Coulomb friction model is not well-defined in continuous
time (Painleve's paradox). This has made discrete-time approximations and associated velocity-stepping schemes very
popular. The continuous-time limit of these models is rarely investigated. For a single contact and under not
necessarily realistic assumptions on the applied forces, the limit satisfies the differential-inclusion form of the
Coulomb friction model, while for multiple simultaneous contacts there can be multiple solutions depending on how
exactly the continuous-time limit is taken. These difficulties can be traced to the assumption of hard contact.
Convex models of frictional contact have also relied on discrete-time approximations in the past, but this is not
necessary. The present model is defined in continuous-time, in terms of forces and accelerations. This is more natural
given that time in the real world is continuous. It is also the preferred formulation in the controls literature, and
indeed we are hoping that MuJoCo will attract users from that community. Another advantage of continuous-time
formulations is that they are amenable to sophisticated numerical integration, without having to pay the computational
overhead of discrete-time variational integrators (which are necessarily implicit when the inertia is
configuration-dependent). Continuous-time dynamics are also well-defined backward in time, which is needed in some
optimization algorithms.
.. _moInverse:
Inverse dynamics and optimization
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
The objective of inverse dynamics it to recover the applied force and contact force given the position, velocity and
acceleration of the multi-joint system. With hard contacts this computation is impossible. Consider pushing against a
wall without moving. The contact force cannot be recovered from the kinematics, unless of course we consider the
material deformations - in which case we need a soft contact model. Inverse dynamics are trivial to compute with
spring-damper models of contact, because in that case the contact force is only a function of position and velocity and
does not depend on applied force. But this is also the reason why spring-damper models are undesirable: ignoring the
applied force means that an error is introduced at each time step, and so the simulator is perpetually in
error-correction mode, in turn causing instabilities. In contrast, modern contact solvers take the applied force (as
well as all internal forces) into account when computing the contact force/impulse. But this complicates inversion. The
present contact model has a uniquely-defined inverse. The inverse dynamics are in fact easier to compute than the
forward dynamics, because the optimization problem becomes diagonal and decomposes into independent optimization
problems over individual contacts - which can be solved analytically.
Inverse dynamics play a key role in optimization algorithms arising in system identification, estimation and control.
They make it possible to treat the sequence of positions (or a parametric representation thereof) as the object being
optimized. Velocities and acceleration are then computed by differentiating the positions; inverse dynamics are used to
compute the applied and contact forces; and finally an objective function is constructed which can depend on all of the
above. This is interchangeably called space-time optimization, spectral method, direct collocation. MuJoCo is uniquely
suited to facilitate such computations in the presence of contacts and other constraints.
.. _Framework:
General framework
-----------------
Our notation is summarized in the table below. Additional notation specific to constraints will be introduced later.
When available, we also show the fields of main data structures :ref:`mjModel` and :ref:`mjData` corresponding to the
mathematical notation.
+-----------------+----------------+----------------+----------------------+
| Symbol | Size | Description | MuJoCo field |
+=================+================+================+======================+
| :math:`n_Q` | | number of | ``mjModel.nq`` |
| | | position | |
| | | coordinates | |
+-----------------+----------------+----------------+----------------------+
| :math:`n_V` | | number of | ``mjModel.nv`` |
| | | degrees of | |
| | | freedom | |
+-----------------+----------------+----------------+----------------------+
| :math:`n_C` | | number of | ``mjData.nefc`` |
| | | active | |
| | | constraints | |
+-----------------+----------------+----------------+----------------------+
| :math:`q` | :math:`n_Q` | joint position | ``mjData.qpos`` |
+-----------------+----------------+----------------+----------------------+
| :math:`v` | :math:`n_V` | joint velocity | ``mjData.qvel`` |
+-----------------+----------------+----------------+----------------------+
| :math:`\tau` | :math:`n_V` | applied force: | |
| | | passive, | |
| | | actuation, | |
| | | external | |
+-----------------+----------------+----------------+----------------------+
| :math:`c(q, v)` | :math:`n_V` | bias force: | ``mjData.qfrc_bias`` |
| | | Coriolis, | |
| | | centrifugal, | |
| | | gravitational | |
+-----------------+----------------+----------------+----------------------+
| :math:`M(q)` | :math:`n_V | inertia in | ``mjData.qM`` |
| | \times n_V` | joint space | |
+-----------------+----------------+----------------+----------------------+
| :math:`J(q)` | :math:`n_C | constraint | ``mjData.efc_J`` |
| | \times n_V` | Jacobian | |
+-----------------+----------------+----------------+----------------------+
| :math:`r(q)` | :math:`n_C` | constraint | ``mjData.efc_pos`` |
| | | residual | |
+-----------------+----------------+----------------+----------------------+
| :math:`f(q, v, | :math:`n_C` | constraint | ``mjData.efc_force`` |
| \tau)` | | force | |
+-----------------+----------------+----------------+----------------------+
All model elements are enumerated at compile time and assembled into the above system-level vectors and matrices. In our
earlier arm model :ref:`example <Examples>` the model has :math:`n_V = 13` degrees of freedom: 3 for the ball joint, one
for each of the 4 hinge joints, and 6 for the free-floating object. They appear in the same order in all system-level
vectors and matrices whose dimensionality is :math:`n_V`. The data corresponding to a given model element can be
recovered via indexing operations as illustrated in the :ref:`Clarifications` section in the Overview chapter. Vectors
and matrices with dimensionality :math:`n_C` are somewhat different because the active :ref:`constraints <Constraint>`
change at runtime. In that case there is still a fixed enumeration order (corresponding to the order in which the model
elements appear in ``mjModel``) but any inactive constraints are omitted.
The number of position coordinates :math:`n_Q` is larger than the number of degrees of freedom :math:`n_V` whenever
quaternions are used to represent 3D orientations. This occurs when the model contains ball joints or free joints (i.e.,
in most models). In that case :math:`\dot{q}` does not equal :math:`v`, at least not in the usual sense. Instead one has
to consider the group of rigid body orientations :math:`SO(3)` - which has the geometry of a unit sphere in 4D space.
Velocities live in the 3D tangent space to this sphere. This is taken into account by all internal computations. For
custom computations, MuJoCo provides the function :ref:`mj_differentiatePos` which "subtracts" two position vectors with
dimensionality :math:`n_Q` and returns a velocity vector with dimensionality :math:`n_V`. A number of quaternion-related
utility functions are also provided.
MuJoCo computes both forward and inverse dynamics in continuous time. Forward dynamics are then integrated over the
specified ``mjModel.opt.timestep`` with the chosen :ref:`numerical
integrator <geIntegration>`. The general equations of motion in continuous time are
.. math::
M \dot{v} + c = \tau + J^T f
:label: eq:motion
The Jacobian establishes the relationship between quantities in joint and constraint coordinates. It maps motion vectors
(velocities and accelerations) from joint to constraint coordinates: the joint velocity :math:`v` maps to velocity
:math:`J v` in constraint coordinates. The transpose of the Jacobian maps force vectors from constraint to joint
coordinates: the constraint force :math:`f` maps to force :math:`J^T f` in joint coordinates.
The joint-space inertia matrix :math:`M` is always invertible. Therefore once the constraint force :math:`f` is known,
we can finalize the forward and inverse dynamics computations as
.. math::
\begin{aligned}
\text{forward:} & & \dot{v} &= M^{-1} (\tau + J^T f - c) \\
\text{inverse:} & & \tau &= M \dot{v} + c - J^T f \\
\end{aligned}
The computation of the constraint force is the hard part and will be described later. But first, we complete the
description of the general framework by summarizing how the above quantities up to the constraint Jacobian are computed.
- The applied force :math:`\tau` includes :ref:`passive <gePassive>` forces from spring-dampers and fluid dynamics,
:ref:`actuation <geActuation>` forces, and additonal forces specified by the user.
- The bias force :math:`c` includes Coriolis, centrifugal and gravitational forces. Their sum is computed using the
Recursive Newton-Euler (RNE) algorithm with acceleration set to 0.
- The joint-space inertia matrix :math:`M` is computed using the Composite Rigid-Body (CRB) algorithm. This matrix is
usually quite sparse, and we represent it as such, in a custom format tailored to kinematic trees.
- Since we often need to multiply vectors by the inverse of :math:`M`, we compute its :math:`L^T D L` factorization in
a way that preserves sparsity. When a quantity of the form :math:`M^{-1} x` is needed later, it is computed via
sparse back-substitution.
Before any of these computations we apply forward kinematics, which computes the global position and orientation of all
spatial objects as well as the joint axes. While it is often recommended to apply RNE and CRB in local coordinates, here
we are setting the stage for collision detection which is done in global coordinates, thus RNE and CRB are also
implemented in global coordinates. Nevertheless, to improve floating point accuracy, we represent the data for each
kinematic subtree in a global frame centered at the subtree center of mass (fields starting with c in ``mjData``). A
detailed summary of the :ref:`simulation pipeline <Pipeline>` is given at the end of the chapter.
.. _geActuation:
Actuation model
~~~~~~~~~~~~~~~
MuJoCo provides a flexible actuator model. All actuators are single-input-single-output (SISO). The input to actuator
:math:`i` is a scalar control :math:`u_i` specified by the user. The output is a scalar force :math:`p_i` which is
mapped to joint coordinates by a vector of moment arms determined by the transmission. An actuator can also have
activation state :math:`w_i` with its own dynamics. The control inputs for all actuators are stored in ``mjData.ctrl``,
the force outputs are stored in ``mjData.actuator_force``, and the activation states (if any) are stored in
``mjData.act``.
These three components of an actuator - transmission, activation dynamics, and force generation - determine how the
actuator works. The user can set them independently for maximum flexibility, or use :ref:`Actuator shortcuts
<CActuator>` which instantiate common actuator types.
.. _geTransmission:
Transmission
~~~~~~~~~~~~
Each actuator has a scalar length :math:`l_i(q)` defined by the type of transmission and its parameters. The gradient
:math:`\nabla l_i` is an :math:`n_V`-dimensional vector of moment arms. It determines the mapping from scalar
actuator force to joint force. The transmission properties are determined by the MuJoCo object to which the actuator
is attached; the possible attachment object types are :at:`joint`, :at:`tendon`, :at:`jointinparent`,
:at:`slider-crank`, :at:`site`, and :at:`body`.
The :at:`joint` and :at:`tendon` transmission types act as expected and correspond to the actuator applying forces or
torques to the target object. Ball joints are special, see the :at:`joint` documentation in
:ref:`actuator<actuator-general>` reference for more details.
The :at:`jointinparent` transmission is unique to ball and free joint and asserts that rotation should be measured
in the parent rather than child frame.
:at:`slider-crank` `transmissions <https://en.wikipedia.org/wiki/Slider-crank_linkage>`_ transform a linear force to
a torque, as in a piston-driven combustion engine. `This model
<https://github.com/deepmind/mujoco/tree/main/model/slider_crank>`_ contains pedagogical examples. Slider-cranks can
also be modeled explicitly by creating MuJoCo bodies and coupling them with equality constraints to the rest of the
system, but that would be less efficient.
:at:`site` transmission (without a :at:`refsite`, see below) and :at:`body` transmission targets have a fixed zero
length :math:`l_i(q) = 0`. They can therefore not be used to maintain a desired length, but can be used to apply
forces. Site transmissions correspond to applying a Cartsian force/torque at the site, and are useful for modeling
jets and propellors. :el:`body` transmissions correspond to applying forces at contact points belonging to a body, in
order to model vacuum grippers and biomechanical adhesive appendages. For more information about adhesion, see the
:ref:`adhesion<actuator-adhesion>` actuator documentation.
If a :at:`site` transmission target is defined with the optional :at:`refsite` attribute, forces and torques are
applied in the frame of the reference site rather than the the site's own frame. If a reference site is defined then
the length of the actuator is nonzero and corresponds to the pose difference of the two sites. This length can then
be controlled with a :el:`position` actuator, enabling Cartesian end-effector control. See the :at:`refsite`
documentation in :ref:`actuator<actuator-general>` reference for more details.
Activation dynamics
Some actuators such as pneumatic and hydraulic cylinders as well as biological muscles have an internal state called
"activation". This is a true dynamic state, beyond the joint positions :math:`q` and velocities :math:`v`. Including
such actuators in the model results in 3rd-order dynamics. We denote the vector of actuator activations :math:`w`.
They have some first-order dynamics
.. math::
\dot{w}_i \left( u_i, w_i, l_i, \dot{l}_i \right)
determined by the activation type and corresponding model parameters. Note that each actuator has scalar dynamics
independent of the other actuators. The activation types currently implemented are
.. math::
\begin{aligned}
\text{integrator}: & & \dot{w}_i &= u_i \\
\text{filter}: & & \dot{w}_i &= (u_i - w_i) / t \\
\end{aligned}
where :math:`t` is an actuator-specific time constant stored in ``mjModel.actuator_dynprm``. In addition the type can
be "user", in which case :math:`w_i` is computed by the user-defined callback :ref:`mjcb_act_dyn`. The type can also
be "none" which corresponds to a regular actuator with no activation state. The dimensionality of :math:`w` equals
the number of actuators whose activation type is different from "none".
Force generation
Each actuator generates a scalar force :math:`p_i` which is some function
.. math::
p_i \left( u_i, w_i, l_i, \dot{l}_i \right)
Similarly to activation dynamics, the force generation mechanism is actuator-specific and cannot interact with the
other actuators in the model. Currently the force is affine in the activation state when present, and in the control
otherwise:
.. math::
p_i = (a w_i \; \text{or} \; a u_i) + b_0 + b_1 l_i + b_2 \dot{l}_i
Here :math:`a` is an actuator-specific gain parameter and :math:`b_0, b_1, b_2` are actuator-specific bias
parameters, stored in ``mjModel.actuator_gainprm`` and ``mjModel.actuator_biasprm`` respectively. Different settings
of the gain and bias parameters can be used to model direct force control as well as position and velocity servos -in
which case the control/activation has the meaning of reference position or velocity. One can also compute custom gain
and bias terms by installing the callbacks :ref:`mjcb_act_gain` and :ref:`mjcb_act_bias` and setting the gain and
bias type to "user". Note that affine force generation makes it possible to infer the controls/activations from the
applied force computed in inverse dynamics, using the pseudo-inverse of the matrix of moment arms. However some of
the actuators used in the real world are not affine (especially those that have embedded low-level controllers), so
we are considering extensions to the above model.
Putting all this together, the net force in generalized coordinates contributed by all actuators is
.. math::
\sum_i \nabla l_i(q) \; p_i \left(u_i, w_i, l_i(q), \dot{l}_i(q, v) \right)
This quantity is stored in ``mjData.qfrc_actuator``. It is added to the applied force vector :math:`\tau`, together
with any user-defined forces in joint or Cartesian coordinates (which are stored in ``mjData.qfrc_applied`` and
``mjData.xfrc_applied`` respectively).
.. _gePassive:
Passive forces
~~~~~~~~~~~~~~
Passive forces are defined as forces that depend only on position and velocity, and not on control in forward dynamics
or acceleration in inverse dynamics. As a result, such forces are inputs to both the forward and inverse dynamics
computations, and are identical in both cases. They are stored in ``mjData.qfrc_passive``. The passive forces computed
by MuJoCo are also passive in the sense of physics, i.e., they do not increase energy, however the user can install the
callback :ref:`mjcb_passive` and add forces to ``mjData.qfrc_passive`` that may increase energy. This will not interfere
with MuJoCo's operation as long as such user forces depend only on position and velocity.
MuJoCo can compute three types of passive forces: spring-dampers in joints and tendons, gravity compensation forces, and
fluid dynamics.
When Euler or the implicit integator are used, joint damping is integrated implicitly which significantly increases
stability. Thus, even though damping can be modeled as an actuator property, it is better to model it as a joint
property. Note also the XML :ref:`joint <body-joint>` attribute springdamper which automates the creation of mass-
spring-dampers with desired time constants and damping ratios; in that case the compiler computes the stiffness and
damping coefficients of the joint by taking the joint inertia into account.
Gravity compensation is a force applied to a body's center of mass opposing gravity, see :ref:`body gravcomp<body>` for
details.
Proper simulation of fluid dynamics is beyond the scope of MuJoCo, and would be too slow for the applications we aim to
facilitate. Nevertheless we provide a phenomenological model which is sufficient for simulating behaviors such as flying
and swimming. It is enabled by setting ``mjModel.opt.viscosity`` and ``mjModel.opt.density`` to positive values (they
are zero by default). These parameters specify the viscosity :math:`\beta` and density :math:`\rho` of the medium and
apply to all bodies. The shape of each body for fluid dynamics purposes is assumed to be the equivalent inertia box,
which can also be visualized. Each forward-facing (relative to the linear velocity) face of the box experiences force
along its normal direction. All faces also experience torque due to the angular velocity; this torque is obtained by
integrating the force resulting from the rotation over the surface area. In this sub-section only, let :math:`v` and
:math:`\omega` denote the linear and angular body velocity in its local frame (which is aligned with the equivalent
inertia box), and :math:`s` the 3D vector of box sizes. When the contributions from all faces are added, the resulting
force and torque in local body coordinates have :math:`i`-th component
.. math::
\begin{aligned}
\text{density force} : \quad &- {1 \over 2} \rho s_j s_k |v_i| v_i \\
\text{density torque} : \quad &- {1 \over 64} \rho s_i \left(s_j^4 + s_k^4 \right) |\omega_i| \omega_i \\
\end{aligned}
This model implicitly assumes high Reynolds numbers, with lift-to-drag ratio equal to the tangent of the angle of
attack. One can also specify a non-zero ``mjModel.opt.wind``, which is a 3D vector subtracted from the body linear
velocity in the fluid dynamics computation.
Each body also experiences a force and a torque proportional to viscosity and opposite to its linear and angular
velocity. Note that viscosity can be used independent of density, to make the simulation more damped. We use the
formulas for a sphere at low Reynolds numbers, with diameter :math:`d` equal to the average of the equivalent inertia
box sizes. The resulting 3D force and torque in local body coordinates are
.. math::
\begin{aligned}
\text{viscosity force} : \quad &- 3 \beta \pi d v \\
\text{viscosity torque} : \quad &- \beta \pi d^3 \omega \\
\end{aligned}
Existing phenomenological models of fluid dynamics tend to be valid for one regime (e.g. flat vs. spherical objects) and
it is difficult to construct a model which can be simulated efficiently and is broadly valid. For example, drag forces
are known to transition from being linear in velocity at low Reynolds numbers, to being quadratic in velocity at high
Reynolds numbers. However it is not clear how this transition should occur for lift forces. This motivated the above
separation, using density to compute all quadratic forces and viscosity to compute all linear forces. Users who need a
more detailed simulation of fluid dynamics should leave the density and viscosity parameters set to zero so as to
disable the built-in mechanism. A custom model of fluid dynamics (or any other force field that depends only on position
and velocity) can be implemented in the callback :ref:`mjcb_passive`.
.. _geIntegration:
Numerical integration
~~~~~~~~~~~~~~~~~~~~~
MuJoCo computes forward and inverse dynamics in continuous time. The end result of forward dynamics is the joint
acceleration :math:`a=\dot{v}` as well as the actuator activations :math:`\dot{w}` when present in the model. These are
used to advance the simulation time from :math:`t` to :math:`t+h`, and to update the state variables :math:`q, v, w`.
Four numerical integrators are available, three single-step integrators and the multi-step 4th order Runge-Kutta
integrator. Before describing the integrators, we begin with a general description of single-step Euler integrators:
*explicit*, *semi-implicit* and *implicit-in-velocity*. The *explicit* Euler method is not supported by MuJoCo but has
pedagogical value. It can be written as:
.. math::
:label: eq_explicit
\begin{aligned}
\textrm{activation:}\quad w_{t+h} &= w_t + h \dot{w}_t \\
\textrm{velocity:}\quad v_{t+h} &= v_t + h a_t \\
\textrm{position:}\quad q_{t+h} &= q_t + h v_t
\end{aligned}
Note that in the presence of quaternions, the operation :math:`q_t + h v_t` is more involved than a simple summation, as
the dimensionalities of :math:`q` and :math:`v` are different. The reason explicit Euler is not implemented is that the
following formulation, known as *semi-implicit* Euler is `strictly better <https://en.wikipedia.org/wiki/Semi-
implicit_Euler_method>`_, and standard in physics simulation:
.. math::
:label: eq_semimplicit
\begin{aligned}
v_{t+h} &= v_t + h a_t \\
q_{t+h} &= q_t + h v_{\color{red}t+h}
\end{aligned}
Comparing :eq:`eq_explicit` and :eq:`eq_semimplicit`, we see that in semi-implicit Euler, the position is updated using
the *new* velocity. *Implicit* Euler means:
.. math::
:label: eq_implicit
\begin{aligned}
v_{t+h} &= v_t + h a_{\color{red}t+h} \\
q_{t+h} &= q_t + h v_{t+h}
\end{aligned}
Comparing :eq:`eq_semimplicit` and :eq:`eq_implicit`, we see that the acceleration :math:`a_{t+h}=\dot{v}_{t+h}` on the
right hand side of the velocity update is evaluated at the *next time step*. While evaluating the next acceleration
is not possible without stepping, we can use a first-order Taylor expansion to approximate this quantity, and
take a single step of Newton's method. When the expansion is only with respect to velocity (and not position), the
integrator is known as *implicit-in-velocity* Euler. This approach is particularly effective in systems where
instabilities are caused by velocity-dependent forces: multi-joint pendulums, bodies tumbling through space, systems
with lift and drag forces, and systems with substantial damping in tendons and actuators. Writing the
acceleration as a function of velocity: :math:`a_t = a(v_t)`, the velocity update we aim to approximate is
.. math:: v_{t+h} = v_t + h a(v_{t+h})
This is a non-linear equation in the unknown vector :math:`v_{t+h}` and can be solved numerically at each time step
using a first-order expansion of :math:`a(v_{t+h})` around :math:`v_t`. Recall that the forward dynamics are
.. math:: a(v) = M^{-1} \big(\tau(v) - c(v) + J^T f(v)\big)
Thus we define the derivative
.. math::
\begin{aligned}
{\partial a(v) \over \partial v} &= M^{-1} D \\
D &\equiv {\partial \over \partial v} \Big(\tau(v) - c (v) + J^T f(v)\Big)
\end{aligned}
The velocity update corresponding to Newton's method is as follows. First, we expand the right hand side to first order
.. math::
\begin{aligned}
v_{t+h} &= v_t + h a(v_{t+h}) \\
&\approx v_t + h \big( a(v_t) + {\partial a(v) \over \partial v} \cdot (v_{t+h}-v_t) \big) \\
&= v_t + h a(v_t) + h M^{-1} D \cdot (v_{t+h}-v_t)
\end{aligned}
Premultiplying by :math:`M` and rearranging yields
.. math:: (M-h D) v_{t+h} = (M-h D) v_t + h M a(v_t)
Solving for :math:`v_{t+h}`, we obtain the implicit-in-velocity update
.. math::
:label: eq_implicit_update
v_{t+h} = v_t + h (M-h D)^{-1} M a(v_t)
All three single-step integrators in MuJoCo use the update :eq:`eq_implicit_update`, with different definitions of the
:math:`D` matrix, which is computed analytically.
Semi-implicit Euler with implicit joint damping (``Euler``)
For this method :math:`D` only includes derivatives of joint damping. Note that in this case :math:`D` is diagonal
and :math:`M-h D` is symmetric, so Cholesky decomposition can be used.
Implicit-in-velocity Euler (``implicit``)
For this method :math:`D` includes derivatives of all forces except the constraint forces :math:`J^T f(v)`. These are
currently ignored since even though computing them is possible, it is complicated, and numerical tests show that
including them does not confer much benefit. That said, analytical derivatives of constraint forces are planned for a
future version. Additionally, we restrict :math:`D` to have the same sparsity pattern as :math:`M`, for computational
efficiency. This restriction will exclude damping in tendons which connect bodies that are on different branches of
the kinematic tree. Since :math:`D` is not symmetric, we cannot use Cholesky factorization, but because :math:`D` and
:math:`M` have the same sparsity pattern corresponding to the topology of the kinematic tree, reverse-order LU
factorization of :math:`M-h D` is `guaranteed to have no fill-in
<https://link.springer.com/book/10.1007/978-1-4899-7560-7>`_. This factorization is stored ``mjData.qLU``.
Fast implicit-in-velocity (``implicitfast``)
For this method :math:`D` includes derivatives of all forces used in the implicit method, with the exception of the
centripetal and Coriolis forces :math:`c (v)` computed by the RNE algorithm. Additionally, it is symmetrized :math:`D
\leftarrow (D + D^T)/2`. One reason for dropping the RNE derivatives is that they are the most expensive to compute.
Second, these forces change rapidly only at high rotational velocities of complex pendula and spinning bodies,
scenarios which are not common and already well-handled by the Runge-Kutta integrator (see below). Because the RNE
derivatives are also the main source of asymmetry of :math:`D`, by dropping them and symmetrizing, we can use the
faster Cholesky rather than LU decomposition.
.. tip::
The implicitfast integrator has similar computational cost to Euler, yet provides increased stability, and is
therefore a strict improvement. It is the recommended integrator and will become the default in a future version.
4th-order Runge-Kutta (``RK4``)
One advantage of our continuous-time formulation is that we can use higher order integrators such as Runge-Kutta or
multistep methods. The only such integrator currently implemented is the fixed-step `4th-order Runge-Kutta method
<https://en.wikipedia.org/wiki/Runge–Kutta_methods#Derivation_of_the_Runge–Kutta_fourth-order_method>`_, though users
can easily implement other integrators by calling :ref:`mj_forward` and integrating accelerations themselves. We have
observed that for energy-conserving systems (`example
<https://github.com/deepmind/mujoco/blob/main/test/engine/testdata/derivative/energy_conserving_pendulum.xml>`_) RK4
is qualitatively better than the single-step methods, both in terms of stability and accuracy, even when the timestep
is decreased by a factor of 4 (so the computational effort is identical). In the presence of large velocity-
dependent forces, if the chosen single-step method integrates those forces implicitly, single-step methods can be
significantly more stable than RK4.
.. note::
The accuracy and stability of all integrators can be improved by reducing the time step :math:`h` which is stored in
``mjModel.opt.timestep``. Of course this also slows down the simulation. The time step is perhaps the most important
parameter that the user can adjust. If it is too large, the simulation will become unstable. If it is too small, CPU
time will be wasted without meaningful improvement in accuracy. There is always a comfortable range where the time
step is "just right", but that range is model-dependent.
.. _geState:
The **state**
~~~~~~~~~~~~~
To complete our description of the general framework we will now discuss the notion of *state*. MuJoCo has a compact,
well-defined internal state which, together with the deterministic computational pipeline, means that operations like
resetting the state and computing dynamics derivatives are also well-defined. The state is entirely encapsulated in the
``mjData`` struct and consists of several components:
.. _gePhysicsState:
Physics state
^^^^^^^^^^^^^
| The *physics state* contains all quantities which are time-integrated during stepping.
| They are ``mjData.{qpos, qvel, act, time}``:
Mechanical state: ``qpos`` and ``qvel``
The *mechanical state* of a simulation is given by the generalized position (``mjData.qpos``) and velocity
(``mjData.qvel``) vectors, denoted above as :math:`q` and :math:`v`, respectively.
Actuator activations: ``act``
``mjData.act`` contains the internal states of stateful actuators, denoted above as :math:`w`.
Time: ``time``
The time of the simulation is given by the scalar ``mjData.time``. Since physics is time-invariant, it is
often excluded from the *physics state*; an exception could be a time-dependent user callback (e.g., an open-loop
controller), in which case time should be included.
.. _geInput:
User inputs
^^^^^^^^^^^
These input fields are set by the user and affect the physics simulation, but are untouched by the simulator. All input
fields except for MoCap poses default to 0.
Controls: ``ctrl``
Controls are defined by the :ref:`actuator<actuator>` section of the XML. ``mjData.ctrl`` values either produce
generalized forces directly (stateless actuators), or affect the actuator activations in ``mjData.act``, which then
produce forces.
Auxillary Controls: ``qfrc_applied`` and ``xfrc_applied``
| ``mjData.qfrc_applied`` are directly applied generalized forces.
| ``mjData.xfrc_applied`` are Cartesian wrenches applied to the CoM of individual bodies. This field is used for
example, by the :ref:`native viewer<saSimulate>` to apply mouse perturbations.
| Note that the effects of ``qfrc_applied`` and ``xfrc_applied`` can usually be recreated by appropriate actuator
definitions.
MoCap poses: ``mocap_pos`` and ``mocap_quat``
``mjData.mocap_pos`` and ``mjData.mocap_quat`` are special optional kinematic states :ref:`described here<CMocap>`,
which allow the user to set the positions and orientations of static bodies in real-time, for example when streaming
6D poses from a motion-capture device. The default values set by :ref:`mj_resetData` are the poses of the bodies at
the default configuration.
User data: ``userdata``
``mjData.userdata`` acts as a user-defined memory space untouched by the engine. For example it can be used by
callbacks. This is described in more detail in the :ref:`Programming chapter<siSimulation>`.
.. _geWarmstart:
Warmstart accelerations
^^^^^^^^^^^^^^^^^^^^^^^
``qacc_warmstart``
``mjData.qacc_warmstart`` are accelerations used to warmstart the constraint solver, saved from the previous step.
When using a slowly-converging :ref:`constraint solver<Solver>` like PGS, these can speed up simulation by reducing
the number of iterations required for convergence. Note however that the default Newton solver converges so quickly
(usually 2-3 iterations), that warmstarts often have no effect on speed and can be disabled.
Different warmstarts have no perceptible effect on the dynamics but should be saved if perfect numerical
reproducibility is required when loading a non-initial state. Note that even though their effect on physics is
negligible, many physical systems will accumulate small differences `exponentially
<https://en.wikipedia.org/wiki/Lyapunov_exponent>`__ when time-stepping, quickly leading to divergent trajectories
for different warmstarts.
.. _geIntegrationState:
Integration state
^^^^^^^^^^^^^^^^^
The *integration state* is the union of all the above ``mjData`` fields and constitutes the entire set of inputs to
the *forward dynamics*. In the case of *inverse dynamics*, ``mjData.qacc`` is also treated as an input variable. All
other ``mjData`` fields are functions of the integration state.
|br| When saving the integration state in order to reload it elsewhere, it is sensible to avoid saving unused fields
that always remain in their default values. Specifically, ``xfrc_applied`` can be quite large (``6 x nbody``) yet is
often unused.
.. _geSimulationState:
Simulation state: ``mjData``
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
The *simulation state* is the entirety of the ``mjData`` struct and associated memory buffer. This state includes
all derived quantities computed during dynamics computation. Because the ``mjData`` buffers are preallocated for the
worst case, it is often significantly faster to recompute derived quantities from the *integration state* rather than
using ``mj_copyData``.
.. _Constraint:
Constraint model
----------------
MuJoCo has a very flexible constraint model, which is nevertheless handled in a uniform way by the
:ref:`solver <Solver>` described later. Here we explain what the individual constraints are conceptually, and how they
are laid out in the system-level vector and matrices with dimensionality :math:`n_C`. Each conceptual constraint can
contribute one or more scalar constraints towards the total count :math:`n_C`, and each scalar constraint has a
corresponding row in the constraint Jacobian :math:`J`. Active constraints are ordered by type in the order in which the
types are described below, and then by model element within each type. The types are: equality, friction loss, limit,
contact. Limits are handled as frictionless contacts by the solver and are not treated as a separate type internally. We
use the prefix ``efc`` in ``mjData`` to denote system-level vectors and matrices with constraint-related data.
.. _coEquality:
Equality
~~~~~~~~
MuJoCo can model equality constraints in the general form :math:`r(q) = 0` where :math:`r` can be any differentiable
scalar or vector function of the position vector :math:`q`. It has the semantics of a residual. The solver can actually
work with non-holonomic constraints as well, but we do not yet have such constraint types defined. Each equality
constraint contributes :math:`\dim(r)` elements to the total constraint count :math:`n_C`. The corresponding block in
:math:`J` is simply the Jacobian of the residual, namely :math:`\partial r / \partial q`. Note that due to the
properties of quaternions, differentiation with respect to :math:`q` produces vectors of size :math:`n_V` rather than
:math:`n_Q`.
Among other applications, equality constraints can be used to create "loop joints", i.e., joints that cannot be modeled
via the kinematic tree. Gaming engines represent all joints in this way. The same can be done in MuJoCo but is not
recommended - because it leads to both slower and less accurate simulation, effectively turning MuJoCo into a gaming
engine. The only reason to represent joints with equality constraints would be to model soft joints - which can be done
via the constraint solver but not via the kinematic tree.
There are five types of equality constraints described next. The numbers in the headings correspond to the
dimensionality of the constraint residual in each case.
``connect`` : 3
This constraint connects two bodies at a point, effectively creating a ball joint outside the kinematic tree. The
model specifies the two bodies to be connected, and a point (or "anchor") in the local frame of each body. The
constraint residual is then defined as the difference between the global 3D positions of these points. Note that
specifying two connect constraints for the same pair of bodies can be used to model a hinge joint outside the
kinematic tree. Specifying three or more connect constraints (whose anchors are not co-linear) is mathematically
equivalent to a weld constraint but is less efficient computationally.
``weld`` : 6
This constraint welds two bodies together, suppressing all relative degrees of freedom between them. The relative
body positions and orientations that are being enforced by the constraint solver are parameters in ``mjModel``. The
compiler computes them from the initial configuration in which the model is defined, namely ``mjModel.qpos0``, but
the user can change them later. The 6D residual has a 3D position component identical to the connect constraint,
followed by a 3D orientation component. The latter is defined as :math:`\sin(\theta/2)
(x, y, z)` where :math:`\theta` is the rotation angle in radians and :math:`(x, y, z)` is the unit vector
corresponding to the rotation axis. For small angles this approaches the exponential map representation of the
orientation difference (modulo a factor of 2). For large angles it avoids the wrap-around discontinuity that would
result if we used :math:`\theta` instead of :math:`\sin(\theta/2)`. It does have a drawback though: when the angle
approaches 180 deg the constraint becomes weak. Note also that if one body is a child of the other body, a faster and
more accurate way to implement the weld constraint is to simply remove all joints defined in the child body.
``joint`` : 1
This constraint applies only to scalar joints: hinge and slide. It can be used to lock one joint into a constant
position, or to couple two joints via a quartic polynomial. Locking a joint is better achieved by removing the joint,
however it can be useful in special cases such as modeling backlash (via a soft equality constraint). Coupling of two
joints is useful for modeling helical joints, or other forms of mechanical coupling. The quartic polynomial model is
defined as follows. Suppose :math:`y` is the position of the first joint and :math:`x` is the position of the second
joint, and the subscript 0 denotes the corresponding joint positions when the model is in the initial configuration
``mjModel.qpos0``. Then the equality constraint is
.. math::
y-y_0 = a_0 + a_1 \left( x-x_0 \right) + a_2 \left( x-x_0 \right)^2 +
a_3 \left( x-x_0 \right)^3 + a_4 \left( x-x_0 \right)^4
where :math:`a_0, \ldots, a_4` are coefficients defined in the model. If the constraint involves only one joint, it
reduces to :math:`y-y_0 = a_0`.
``tendon`` : 1
This constraint is very similar to the joint constraint above, but applies to the length of tendons instead of the
position of joints. Tendons are length quantities that depend on the vector of positions. This dependence can be a
linear combination of scalar joint positions, or a minimal-length string wrapping around spatial obstacles. Unlike
joints whose positions in model configuration ``mjModel.qpos0`` can be read directly from the position vector, the
computation of tendon lengths is less trivial. This is why the "resting lengths" of all tendons are computed by the
compiler and stored in ``mjModel``. In general, all fields of ``mjModel`` whose names end with 0 are quantities
computed by the compiler in the initial model configuration ``mjModel.qpos0``.
``distance`` : 1
.. attention::
Distance equality constraints were removed in MuJoCo version 2.2.2. If you are using an earlier version, please
switch to the corresponding version of the documentation.
.. _coFriction:
Friction loss
~~~~~~~~~~~~~
Friction loss is also known as dry friction, or static friction, or load-independent friction (in contrast with Coulomb
friction which scales with normal force). Similar to damping or viscosity, it has the effect of opposing motion. However
it acts preemptively before the onset of motion, and so it cannot be modeled as a velocity-dependent force. Instead it
is modeled as a constraint, namely an upper limit on the absolute value of the force that friction can generate. This
limit is specified via the attribute frictionloss of the corresponding model element, and can be applied to joints and
tendons.
Friction loss is different from all other constraint types in that there is no position residual that can be associated
with it; so we formally set the corresponding components of :math:`r(q)` to zero. Indeed we will see later that our
constraint solver formulation needs to be extended in an unusual way to incorporate this constraint. Nevertheless the
velocity of the affected joint or tendon acts as a velocity "residual" - because the effect of the constraint is to
reduce this velocity and ideally keep it at zero. Thus the corresponding block in the constraint Jacobian is simply the
Jacobian of the joint position (or tendon length) with respect to :math:`q`. For scalar joints this is a vector of 0s
with a 1 at the joint address. For tendons this is known as the moment arm vector.
``joint`` : 1, 3 or 6
Friction loss can be defined not only for scalar joints (slide and hinge), but also for ball joints which have 3
degrees of freedom, and free joints which have 6 degrees of freedom. When defined, it is applied independently to all
degrees of freedom of the affected joint. The frictionloss parameter has implicit units compatible with the joint
(linear or angular). Free joints are an exception because they have both linear and angular components, and the MJCF
model format allows a single frictionloss parameter per joint. In that case the same parameter is used for both the
linear and angular components. It could be argued that friction loss in free joints should not be allowed. However we
allow it because it can model useful non-physical effects, such as keeping an object in place until something pushes
it with sufficient force.
``tendon`` : 1
Tendons are scalar quantities, thus defining friction loss for a tendon always adds one scalar constraint. For
spatial tendons this could be used to model friction between the tendon and the surfaces it wraps around. Such
friction will be load-independent though. To construct a more detailed model of this phenomenon, create several small
floating spheres and connect them with tendons in series. Then the contacts between the spheres and the surrounding
surfaces will have load-dependent (i.e., Coulomb) friction, but this is less efficient to simulate.
.. _coLimit:
Limit
~~~~~
Limits as well as contacts have a well-defined spatial residual, but unlike equality constraints they are uni-lateral,
i.e. they introduce inequality rather than equality constraints. Limits can be defined for joints and tendons. This is
done by tagging the corresponding model element as "limited" and defining its "range" parameter. The residual
:math:`r(q)` is the distance between the current position/length and the closer of the two limiting values specified in
range. The sign of this distance is automatically adjusted so that it is positive if the limit is not yet reached, zero
at the limit, and negative if the limit is violated. The constraint becomes active when this distance falls below the
"margin" parameter. However this is not the same as offsetting limit by margin and setting margin to 0. Instead the
constraint force depends on distance through the solver :ref:`parameters <soParameters>` described later.
It is possible that both the lower and the upper limits for a given joint or tendon become active. In that case they are
both included in the list of scalar constraints, however this situation should be avoided - by increasing the range or
decreasing the margin. In particular, avoid using narrow ranges to approximate an equality constraint. Instead use an
explicit equality constraint, and if some slack is desired make the constraint soft by adjusting the solver parameters.
This is more efficient computationally, not only because it involves one scalar constraint instead of two, but also
because solving for equality constraint forces is generally faster.
``joint`` : 1 or 2
Limits can be defined for scalar joints (hinge and slide) as well as for ball joints. Scalar joints are treated as
described above. Ball joint limits are applied to the exponential-map or angle-axis representation of the joint
quaternion, i.e., the vector :math:`(\theta x, \theta y, \theta z)` where :math:`\theta` is the rotation angle and
:math:`(x, y, z)` is the unit vector corresponding to the rotation axis. The limit is applied to the absolute value
of the rotation angle :math:`\theta`. At runtime the limit is determined by the larger of the two range parameters.
For semantic clarity however, one should use the second range parameter to specify the limit and set the first range
parameter to 0. This rule is enforced by the compiler.
``tendon`` : 1 or 2
Tendon are scalar quantities and their limits are treated as described above. Note that fixed tendons (which are
linear combinations of scalar joint positions) can have both positive and negative "lengths", because joint positions
are defined relative to the joint reference and can be both positive and negative. Spatial tendons however have true
lengths which cannot be negative. Keep this in mind when setting ranges and margins for tendon limits.
.. _coContact:
Contact
~~~~~~~
Contacts are the most elaborate constraint type, both in terms of specifying them in the model and in terms of the
computations that need to be performed. This is because contact modeling is challenging to begin with, and furthermore
we support a general contact model allowing tangential, torsional and rolling friction, as well as elliptic and
pyramidal friction cones.
MuJoCo works with point contacts, defined geometrically by a point between two geoms and a spatial frame centered at
that point, both expressed in global coordinates. The first (:math:`x`) axis of this frame is the contact normal
direction, while the remaining (:math:`y` and :math:`z`) axes define the tangent plane. One might have expected the
normal to correspond to the :math:`z` axis, as in MuJoCo's visualization convention, but we support frictionless
contacts where only the normal axis is used, which is why we want to have the normal in first position. Similar to
limits, the contact distance is positive when the two geoms are separated, zero when they touch, and negative when they
penetrate. The contact point is in the middle between the two surfaces along the normal axis (for mesh collisions this
may be approximate). :ref:`Collision
detection <Collision>` is a separate topic discussed in detail below. All we need for now is that the contact point,
spatial frame and normal distance are given by the collision detector.
In addition to the above quantities which are computed online, each contact has several parameters obtained from the
model definition.
+---------------------------+-----------------------------------+
| Parameter | Description |
+===========================+===================================+
| ``condim`` | Dimensionality of the contact |
| | force/torque in the contact |
| | frame. It can be 1, 3, 4 or 6. |
+---------------------------+-----------------------------------+
| ``friction`` | Vector of friction coefficients, |
| | with dimensionality ``condim-1``. |
+---------------------------+-----------------------------------+
| ``margin`` | The distance margin used to |
| | determine if the contact should |
| | be included in the global contact |
| | array ``mjData.contact``. |
+---------------------------+-----------------------------------+
| ``gap`` | For custom computations it is |
| | sometimes convenient to include |
| | contacts in ``mjData.contact`` |
| | but not generate contact forces. |
| | This is what ``gap`` does: |
| | contact forces are generated only |
| | when the normal distance is below |
| | margin-gap. |
+---------------------------+-----------------------------------+
| ``solref`` and ``solimp`` | :ref:`Solver <Solver>` |
| | parameters explained later. |
+---------------------------+-----------------------------------+
The contact friction cone can be either elliptic or pyramidal. This is a global setting determined by the choice of
constraint solver: the elliptic solvers work with elliptic cones, while the pyramidal solvers work with pyramidal cones,
as defined later. The ``condim`` parameter determines the contact type, and has the following meaning:
``condim = 1`` : 1 for elliptic, 1 for pyramidal
This corresponds to a frictionless contact and adds only one scalar constraint. Recall that the first axis of the
contact frame is the contact normal. Frictionless contacts can only generate force along the normal. This is very
similar to a joint or tendon limit, but is applied to the distance between two geoms.
``condim = 3`` : 3 for elliptic, 4 for pyramidal
This is a regular frictional contact, which can generate normal force as well as tangential friction force opposing
slip.
``condim = 4`` : 4 for elliptic, 6 for pyramidal
In addition to normal and tangential force, this contact can generate torsional friction torque opposing rotation
around the contact normal. This is useful for modeling soft fingers, and can substantially improve the stability of
simulated grasping. Keep in mind that the torsional (as well as rolling) friction coefficients have different units
from the tangential friction coefficients.
``condim = 6`` : 6 for elliptic, 10 for pyramidal
This contact can oppose motion in all relative degrees of freedom between the two geoms. In particular it adds
rolling friction, which can be used for example to stop a ball from rolling indefinitely on a plane. It can also be
used to model rolling friction between tires and a road, and in general to stabilize contacts.
Note that condim cannot be 2 or 5. This is because the two tangential directions and the two rolling directions are
treated as pairs. The friction coefficients within a pair can be different though, which can be used to model skating
for example.
Now we describe the friction cones and the corresponding Jacobians more formally. In this section only, let :math:`f`
denote the vector of constraint forces for a single contact (as opposed to the system-level vector of constraint
forces), :math:`\mu` the vector of friction coefficients, and :math:`n` the contact dimensionality condim. For
:math:`n > 1` the elliptic and pyramidal friction cones are defined as
.. math::
\begin{aligned}
\text{elliptic cone}: & & \mathcal{K} &=
\left\{ f \in \mathbb{R}^n : f_1 \geq 0,
f_1^2 \geq \sum_{i=2}^n {f_i^2 / \mu_{i-1}^2} \right\} \\
\text{pyramidal cone}: & & \mathcal{K} &=
\left\{ f \in \mathbb{R}^{2(n-1)} : f \geq 0 \right\} \\
\end{aligned}
The vector inequality in the pyramidal cone definition is meant element-wise. For :math:`n=1` both cones are defined as
the non-negative ray (which is a special case of a cone). Note that the system-level friction cone discussed in the
solver section below will also be denoted :math:`\mathcal{K}`. It is the product of the friction cones for the
individual contacts as defined here.
We also need to specify how the constraint force acts on the system. This is done by associating a 6D basis vector with
each component of :math:`f`. The basis vectors are spatial vectors: 3D force followed by 3D torque. Arranging the basis
vectors into the columns of a matrix :math:`E`, the force/torque generated by the constraint force in the contact frame
is :math:`E f`. The matrix of basis vectors is constructed as follows.
.. image:: images/computation/contact_frame.svg
:width: 700px
:align: center
The figure illustrates the full basis set corresponding to the case :math:`n = 6`. Otherwise we use only the first
:math:`n` or :math:`2(n-1)` columns depending on the cone type. Elliptic cones are easier to understand. Since the
matrix :math:`E` is the identity matrix, the first three components of :math:`f` are forces acting along the axes of the
contact frame, while the next three components are torques acting around the axes. For pyramidal cones, the basis
vectors correspond to the edges of a pyramid. Each vector combines a normal force component and either a frictional
force or a frictional torque component. The scaling by the friction coefficients ensures that all basis vectors lie
within the elliptic friction cone we are approximating. The same holds for any convex combination of these vectors.
Finally we specify how the contact Jacobian is computed. First we construct the :math:`6`-by-:math:`n_V` matrix
:math:`S` which maps joint velocities :math:`v` to spatial velocities :math:`S v` expressed in the contact frame. This
is done by considering the contact point as belonging to one or the other geom, computing its spatial Jacobian, and
subtracting these two Jacobians to obtain :math:`S`. The convention we use is that the contact force acts from the first
towards the second geom, so the spatial Jacobian for the first geom has negative sign. The contact Jacobian is then
:math:`E^T S`. As with all other constraints, this matrix is inserted into the system-level Jacobian :math:`J`.
.. _Solver:
Constraint solver
-----------------
This section explains how the constraint forces are computed. This is done in two stages. First, the constraint forces
are defined as the unique global solution to a convex optimization problem. It is a quadratic program for pyramidal
cones and a conic program for elliptic cones. Second, the optimization problem is solved with the algorithms described
below. We also describe the parameters of the constraint model and how they affect the resulting dynamics.
The definition of the optimization problem itself has two steps. We start with a primal problem defined over
accelerations :math:`\dot{v}` where the constraint forces are implicit. We then transform the primal problem over
accelerations into its Lagrange dual. The dual is a convex optimization problem over constraint forces, which also play
the role of Lagrange multipliers for the primal problem. In forward dynamics, either the primal or the dual problem has
to be solved numerically. In inverse dynamics, the problem becomes diagonal and can be solved analytically.
The primal formulation is based on a generalization of the Gauss principle of least constraint. In its basic form, the
Gauss principle states that if we have unconstrained dynamics :math:`M \dot{v} = \tau` and impose acceleration
constraint :math:`J \dot{v} = a^*`, the resulting acceleration will be
.. math::
\dot{v} = \arg \min_x \left\| x-M^{-1} \tau \right\|^2_M \\
\textrm{subject to} \; J x = a^*
where the weighted :math:`L_2` norm is the usual :math:`\|x\|^2_M = x^T M x`. Thus the constraint causes the smallest
possible deviation from the unconstrained acceleration :math:`M^{-1}\tau`, where the metric for measuring deviations in
joint coordinates is given by the inertia matrix. This principle is known to be equivalent to the Lagrange-d'Alembert
principle of constrained motion. Here we will use it to obtain a rich yet principled model of soft constraints. This
will be done by generalizing both the cost function and the constraints in the Gauss principle.
We will use the following notation beyond the notation introduced earlier:
+----------------------+----------------------+----------------------+
| Symbol | Size | Description |
+======================+======================+======================+
| :math:`z` | :math:`n_C` | constraint |
| | | deformations |
+----------------------+----------------------+----------------------+
| :math:`\omega` | :math:`n_C` | velocity of |
| | | constraint |
| | | deformations |
+----------------------+----------------------+----------------------+
| :math:`d` | :math:`n_C` | constraint impedance |
+----------------------+----------------------+----------------------+
| :math:`b` | :math:`n_C` | virtual constraint |
| | | damping |
+----------------------+----------------------+----------------------+
| :math:`k` | :math:`n_C` | virtual constraint |
| | | stiffness |
+----------------------+----------------------+----------------------+
| :math:`A(q)` | :math:`n_C \times | inverse inertia in |
| | n_C` | constraint space |
+----------------------+----------------------+----------------------+
| :math:`R(q)` | :math:`n_C \times | diagonal regularizer |
| | n_C` | in constraint space |
+----------------------+----------------------+----------------------+
| :math:`a^*(q,v)` | :math:`n_C` | reference |
| | | acceleration in |
| | | constraint space |
+----------------------+----------------------+----------------------+
| :math:`a^0(q, v, | :math:`n_C` | unconstrained |
| \tau)` | | acceleration in |
| | | constraint space |
+----------------------+----------------------+----------------------+