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 maps to velocity in constraint coordinates. The transpose of the
Jacobian maps force vectors from constraint to joint coordinates: the constraint force maps to force in joint coordinates.
The joint-space inertia matrix is always invertible. Therefore once the constraint force is known, we can finalize the forward and
inverse dynamics computations as
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 includes passive forces from spring-dampers and fluid dynamics, actuation forces, and additonal forces
specified by the user.
The bias force 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 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 , we compute its factorization in a way that preserves sparsity.
When a quantity of the form 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 simulation pipeline is given at the end of the chapter.
Actuation model
MuJoCo provides a flexible actuator model. All actuators are single-input-single-output (SISO). The input to actuator is a scalar control
specified by the user. The output is a scalar force which is mapped to joint coordinates by a vector of moment arms determined by
the transmission. An actuator can also have activation state 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 Actuator shortcuts which instantiate common actuator types.
Transmission
Each actuator has a scalar length defined by the type of transmission and its parameters. The gradient is an -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 joint, tendon, jointinparent, slider-
crank, site, and body.
The joint and 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 joint documentation in actuator reference for more details.
The jointinparent transmission is unique to ball and free joint and asserts that rotation should be measured in the parent rather than
child frame.
slider-crank transmissions transform a linear force to a torque, as in a piston-driven combustion engine. This model 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.
site transmission (without a refsite, see below) and body transmission targets have a fixed zero length . 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. body transmissions correspond to applying
forces at contact points belonging to a body, in order to model vacuum grippers and biomechanical adhesive appendages. For
v Jv
f J f
T
M f