Types#

MuJoCo defines a large number of types:

Primitive types#

The two types below are defined in mjtnum.h.

mjtNum#

This is the floating-point type used throughout the simulator. If the symbol mjUSEDOUBLE is defined in mjmodel.h, this type is defined as double, otherwise it is defined as float. Currently only the double-precision version of MuJoCo is distributed, although the entire code base works with single-precision as well. We may release the single-precision version in the future for efficiency reasons, but the double-precision version will always be available. Thus it is safe to write user code assuming double precision. However, our preference is to write code that works with either single or double precision. To this end we provide math utility functions that are always defined with the correct floating-point type.

Note that changing mjUSEDOUBLE in mjtnum.h will not change how the library was compiled, and instead will result in numerous link errors. In general, the header files distributed with precompiled MuJoCo should never be changed by the user.

#ifdef mjUSEDOUBLE
    typedef double mjtNum;
#else
    typedef float mjtNum;
#endif

mjtByte#

Byte type used to represent boolean variables.

typedef unsigned char mjtByte;

Enum types#

Model#

The enums below are defined in mjmodel.h.

mjtDisableBit#

Constants which are powers of 2. They are used as bitmasks for the field disableflags of mjOption. At runtime this field is m->opt.disableflags. The number of these constants is given by mjNDISABLE which is also the length of the global string array mjDISABLESTRING with text descriptions of these flags.

typedef enum mjtDisableBit_ {     // disable default feature bitflags
  mjDSBL_CONSTRAINT   = 1<<0,     // entire constraint solver
  mjDSBL_EQUALITY     = 1<<1,     // equality constraints
  mjDSBL_FRICTIONLOSS = 1<<2,     // joint and tendon frictionloss constraints
  mjDSBL_LIMIT        = 1<<3,     // joint and tendon limit constraints
  mjDSBL_CONTACT      = 1<<4,     // contact constraints
  mjDSBL_PASSIVE      = 1<<5,     // passive forces
  mjDSBL_GRAVITY      = 1<<6,     // gravitational forces
  mjDSBL_CLAMPCTRL    = 1<<7,     // clamp control to specified range
  mjDSBL_WARMSTART    = 1<<8,     // warmstart constraint solver
  mjDSBL_FILTERPARENT = 1<<9,     // remove collisions with parent body
  mjDSBL_ACTUATION    = 1<<10,    // apply actuation forces
  mjDSBL_REFSAFE      = 1<<11,    // integrator safety: make ref[0]>=2*timestep
  mjDSBL_SENSOR       = 1<<12,    // sensors
  mjDSBL_MIDPHASE     = 1<<13,    // mid-phase collision filtering

  mjNDISABLE          = 14        // number of disable flags
} mjtDisableBit;

mjtEnableBit#

Constants which are powers of 2. They are used as bitmasks for the field enableflags of mjOption. At runtime this field is m->opt.enableflags. The number of these constants is given by mjNENABLE which is also the length of the global string array mjENABLESTRING with text descriptions of these flags.

typedef enum mjtEnableBit_ {      // enable optional feature bitflags
  mjENBL_OVERRIDE     = 1<<0,     // override contact parameters
  mjENBL_ENERGY       = 1<<1,     // energy computation
  mjENBL_FWDINV       = 1<<2,     // record solver statistics
  mjENBL_SENSORNOISE  = 1<<3,     // add noise to sensor data
                                  // experimental features:
  mjENBL_MULTICCD     = 1<<4,     // multi-point convex collision detection

  mjNENABLE           = 5         // number of enable flags
} mjtEnableBit;

mjtJoint#

Primitive joint types. These values are used in m->jnt_type. The numbers in the comments indicate how many positional coordinates each joint type has. Note that ball joints and rotational components of free joints are represented as unit quaternions - which have 4 positional coordinates but 3 degrees of freedom each.

typedef enum mjtJoint_ {          // type of degree of freedom
  mjJNT_FREE          = 0,        // global position and orientation (quat)       (7)
  mjJNT_BALL,                     // orientation (quat) relative to parent        (4)
  mjJNT_SLIDE,                    // sliding distance along body-fixed axis       (1)
  mjJNT_HINGE                     // rotation angle (rad) around body-fixed axis  (1)
} mjtJoint;

mjtGeom#

Geometric types supported by MuJoCo. The first group are “official” geom types that can be used in the model. The second group are geom types that cannot be used in the model but are used by the visualizer to add decorative elements. These values are used in m->geom_type and m->site_type.

typedef enum mjtGeom_ {           // type of geometric shape
  // regular geom types
  mjGEOM_PLANE        = 0,        // plane
  mjGEOM_HFIELD,                  // height field
  mjGEOM_SPHERE,                  // sphere
  mjGEOM_CAPSULE,                 // capsule
  mjGEOM_ELLIPSOID,               // ellipsoid
  mjGEOM_CYLINDER,                // cylinder
  mjGEOM_BOX,                     // box
  mjGEOM_MESH,                    // mesh

  mjNGEOMTYPES,                   // number of regular geom types

  // rendering-only geom types: not used in mjModel, not counted in mjNGEOMTYPES
  mjGEOM_ARROW        = 100,      // arrow
  mjGEOM_ARROW1,                  // arrow without wedges
  mjGEOM_ARROW2,                  // arrow in both directions
  mjGEOM_LINE,                    // line
  mjGEOM_SKIN,                    // skin
  mjGEOM_LABEL,                   // text label

  mjGEOM_NONE         = 1001      // missing geom type
} mjtGeom;

mjtCamLight#

Dynamic modes for cameras and lights, specifying how the camera/light position and orientation are computed. These values are used in m->cam_mode and m->light_mode.

typedef enum mjtCamLight_ {       // tracking mode for camera and light
  mjCAMLIGHT_FIXED    = 0,        // pos and rot fixed in body
  mjCAMLIGHT_TRACK,               // pos tracks body, rot fixed in global
  mjCAMLIGHT_TRACKCOM,            // pos tracks subtree com, rot fixed in body
  mjCAMLIGHT_TARGETBODY,          // pos fixed in body, rot tracks target body
  mjCAMLIGHT_TARGETBODYCOM        // pos fixed in body, rot tracks target subtree com
} mjtCamLight;

mjtTexture#

Texture types, specifying how the texture will be mapped. These values are used in m->tex_type.

typedef enum mjtTexture_ {        // type of texture
  mjTEXTURE_2D        = 0,        // 2d texture, suitable for planes and hfields
  mjTEXTURE_CUBE,                 // cube texture, suitable for all other geom types
  mjTEXTURE_SKYBOX                // cube texture used as skybox
} mjtTexture;

mjtIntegrator#

Numerical integrator types. These values are used in m->opt.integrator.

typedef enum mjtIntegrator_ {     // integrator mode
  mjINT_EULER         = 0,        // semi-implicit Euler
  mjINT_RK4,                      // 4th-order Runge Kutta
  mjINT_IMPLICIT,                 // implicit in velocity
  mjINT_IMPLICITFAST              // implicit in velocity, no rne derivative
} mjtIntegrator;

mjtCollision#

Collision modes specifying how candidate geom pairs are generated for near-phase collision checking. These values are used in m->opt.collision.

typedef enum mjtCollision_ {      // collision mode for selecting geom pairs
  mjCOL_ALL           = 0,        // test precomputed and dynamic pairs
  mjCOL_PAIR,                     // test predefined pairs only
  mjCOL_DYNAMIC                   // test dynamic pairs only
} mjtCollision;

mjtCone#

Available friction cone types. These values are used in m->opt.cone.

typedef enum mjtCone_ {           // type of friction cone
  mjCONE_PYRAMIDAL     = 0,       // pyramidal
  mjCONE_ELLIPTIC                 // elliptic
} mjtCone;

mjtJacobian#

Available Jacobian types. These values are used in m->opt.jacobian.

typedef enum mjtJacobian_ {       // type of constraint Jacobian
  mjJAC_DENSE          = 0,       // dense
  mjJAC_SPARSE,                   // sparse
  mjJAC_AUTO                      // dense if nv<60, sparse otherwise
} mjtJacobian;

mjtSolver#

Available constraint solver algorithms. These values are used in m->opt.solver.

typedef enum mjtSolver_ {         // constraint solver algorithm
  mjSOL_PGS            = 0,       // PGS    (dual)
  mjSOL_CG,                       // CG     (primal)
  mjSOL_NEWTON                    // Newton (primal)
} mjtSolver;

mjtEq#

Equality constraint types. These values are used in m->eq_type.

typedef enum mjtEq_ {             // type of equality constraint
  mjEQ_CONNECT        = 0,        // connect two bodies at a point (ball joint)
  mjEQ_WELD,                      // fix relative position and orientation of two bodies
  mjEQ_JOINT,                     // couple the values of two scalar joints with cubic
  mjEQ_TENDON,                    // couple the lengths of two tendons with cubic
  mjEQ_DISTANCE                   // unsupported, will cause an error if used
} mjtEq;

mjtWrap#

Tendon wrapping object types. These values are used in m->wrap_type.

typedef enum mjtWrap_ {           // type of tendon wrap object
  mjWRAP_NONE         = 0,        // null object
  mjWRAP_JOINT,                   // constant moment arm
  mjWRAP_PULLEY,                  // pulley used to split tendon
  mjWRAP_SITE,                    // pass through site
  mjWRAP_SPHERE,                  // wrap around sphere
  mjWRAP_CYLINDER                 // wrap around (infinite) cylinder
} mjtWrap;

mjtTrn#

Actuator transmission types. These values are used in m->actuator_trntype.

typedef enum mjtTrn_ {            // type of actuator transmission
  mjTRN_JOINT         = 0,        // force on joint
  mjTRN_JOINTINPARENT,            // force on joint, expressed in parent frame
  mjTRN_SLIDERCRANK,              // force via slider-crank linkage
  mjTRN_TENDON,                   // force on tendon
  mjTRN_SITE,                     // force on site
  mjTRN_BODY,                     // adhesion force on a body's geoms

  mjTRN_UNDEFINED     = 1000      // undefined transmission type
} mjtTrn;

mjtDyn#

Actuator dynamics types. These values are used in m->actuator_dyntype.

typedef enum mjtDyn_ {            // type of actuator dynamics
  mjDYN_NONE          = 0,        // no internal dynamics; ctrl specifies force
  mjDYN_INTEGRATOR,               // integrator: da/dt = u
  mjDYN_FILTER,                   // linear filter: da/dt = (u-a) / tau
  mjDYN_MUSCLE,                   // piece-wise linear filter with two time constants
  mjDYN_USER                      // user-defined dynamics type
} mjtDyn;

mjtGain#

Actuator gain types. These values are used in m->actuator_gaintype.

typedef enum mjtGain_ {           // type of actuator gain
  mjGAIN_FIXED        = 0,        // fixed gain
  mjGAIN_AFFINE,                  // const + kp*length + kv*velocity
  mjGAIN_MUSCLE,                  // muscle FLV curve computed by mju_muscleGain()
  mjGAIN_USER                     // user-defined gain type
} mjtGain;

mjtBias#

Actuator bias types. These values are used in m->actuator_biastype.

typedef enum mjtBias_ {           // type of actuator bias
  mjBIAS_NONE         = 0,        // no bias
  mjBIAS_AFFINE,                  // const + kp*length + kv*velocity
  mjBIAS_MUSCLE,                  // muscle passive force computed by mju_muscleBias()
  mjBIAS_USER                     // user-defined bias type
} mjtBias;

mjtObj#

MuJoCo object types. These are used, for example, in the support functions mj_name2id and mj_id2name to convert between object names and integer ids.

typedef enum mjtObj_ {            // type of MujoCo object
  mjOBJ_UNKNOWN       = 0,        // unknown object type
  mjOBJ_BODY,                     // body
  mjOBJ_XBODY,                    // body, used to access regular frame instead of i-frame
  mjOBJ_JOINT,                    // joint
  mjOBJ_DOF,                      // dof
  mjOBJ_GEOM,                     // geom
  mjOBJ_SITE,                     // site
  mjOBJ_CAMERA,                   // camera
  mjOBJ_LIGHT,                    // light
  mjOBJ_MESH,                     // mesh
  mjOBJ_SKIN,                     // skin
  mjOBJ_HFIELD,                   // heightfield
  mjOBJ_TEXTURE,                  // texture
  mjOBJ_MATERIAL,                 // material for rendering
  mjOBJ_PAIR,                     // geom pair to include
  mjOBJ_EXCLUDE,                  // body pair to exclude
  mjOBJ_EQUALITY,                 // equality constraint
  mjOBJ_TENDON,                   // tendon
  mjOBJ_ACTUATOR,                 // actuator
  mjOBJ_SENSOR,                   // sensor
  mjOBJ_NUMERIC,                  // numeric
  mjOBJ_TEXT,                     // text
  mjOBJ_TUPLE,                    // tuple
  mjOBJ_KEY,                      // keyframe
  mjOBJ_PLUGIN                    // plugin instance
} mjtObj;

mjtConstraint#

Constraint types. These values are not used in mjModel, but are used in the mjData field d->efc_type when the list of active constraints is constructed at each simulation time step.

typedef enum mjtConstraint_ {     // type of constraint
  mjCNSTR_EQUALITY    = 0,        // equality constraint
  mjCNSTR_FRICTION_DOF,           // dof friction
  mjCNSTR_FRICTION_TENDON,        // tendon friction
  mjCNSTR_LIMIT_JOINT,            // joint limit
  mjCNSTR_LIMIT_TENDON,           // tendon limit
  mjCNSTR_CONTACT_FRICTIONLESS,   // frictionless contact
  mjCNSTR_CONTACT_PYRAMIDAL,      // frictional contact, pyramidal friction cone
  mjCNSTR_CONTACT_ELLIPTIC        // frictional contact, elliptic friction cone
} mjtConstraint;

mjtConstraintState#

These values are used by the solver internally to keep track of the constraint states.

typedef enum mjtConstraintState_ {  // constraint state
  mjCNSTRSTATE_SATISFIED = 0,       // constraint satisfied, zero cost (limit, contact)
  mjCNSTRSTATE_QUADRATIC,           // quadratic cost (equality, friction, limit, contact)
  mjCNSTRSTATE_LINEARNEG,           // linear cost, negative side (friction)
  mjCNSTRSTATE_LINEARPOS,           // linear cost, positive side (friction)
  mjCNSTRSTATE_CONE                 // squared distance to cone cost (elliptic contact)
} mjtConstraintState;

mjtSensor#

Sensor types. These values are used in m->sensor_type.

typedef enum mjtSensor_ {         // type of sensor
  // common robotic sensors, attached to a site
  mjSENS_TOUCH        = 0,        // scalar contact normal forces summed over sensor zone
  mjSENS_ACCELEROMETER,           // 3D linear acceleration, in local frame
  mjSENS_VELOCIMETER,             // 3D linear velocity, in local frame
  mjSENS_GYRO,                    // 3D angular velocity, in local frame
  mjSENS_FORCE,                   // 3D force between site's body and its parent body
  mjSENS_TORQUE,                  // 3D torque between site's body and its parent body
  mjSENS_MAGNETOMETER,            // 3D magnetometer
  mjSENS_RANGEFINDER,             // scalar distance to nearest geom or site along z-axis

  // sensors related to scalar joints, tendons, actuators
  mjSENS_JOINTPOS,                // scalar joint position (hinge and slide only)
  mjSENS_JOINTVEL,                // scalar joint velocity (hinge and slide only)
  mjSENS_TENDONPOS,               // scalar tendon position
  mjSENS_TENDONVEL,               // scalar tendon velocity
  mjSENS_ACTUATORPOS,             // scalar actuator position
  mjSENS_ACTUATORVEL,             // scalar actuator velocity
  mjSENS_ACTUATORFRC,             // scalar actuator force

  // sensors related to ball joints
  mjSENS_BALLQUAT,                // 4D ball joint quaternion
  mjSENS_BALLANGVEL,              // 3D ball joint angular velocity

  // joint and tendon limit sensors, in constraint space
  mjSENS_JOINTLIMITPOS,           // joint limit distance-margin
  mjSENS_JOINTLIMITVEL,           // joint limit velocity
  mjSENS_JOINTLIMITFRC,           // joint limit force
  mjSENS_TENDONLIMITPOS,          // tendon limit distance-margin
  mjSENS_TENDONLIMITVEL,          // tendon limit velocity
  mjSENS_TENDONLIMITFRC,          // tendon limit force

  // sensors attached to an object with spatial frame: (x)body, geom, site, camera
  mjSENS_FRAMEPOS,                // 3D position
  mjSENS_FRAMEQUAT,               // 4D unit quaternion orientation
  mjSENS_FRAMEXAXIS,              // 3D unit vector: x-axis of object's frame
  mjSENS_FRAMEYAXIS,              // 3D unit vector: y-axis of object's frame
  mjSENS_FRAMEZAXIS,              // 3D unit vector: z-axis of object's frame
  mjSENS_FRAMELINVEL,             // 3D linear velocity
  mjSENS_FRAMEANGVEL,             // 3D angular velocity
  mjSENS_FRAMELINACC,             // 3D linear acceleration
  mjSENS_FRAMEANGACC,             // 3D angular acceleration

  // sensors related to kinematic subtrees; attached to a body (which is the subtree root)
  mjSENS_SUBTREECOM,              // 3D center of mass of subtree
  mjSENS_SUBTREELINVEL,           // 3D linear velocity of subtree
  mjSENS_SUBTREEANGMOM,           // 3D angular momentum of subtree

  // global sensors
  mjSENS_CLOCK,                   // simulation time

  // plugin-controlled sensors
  mjSENS_PLUGIN,                  // plugin-controlled

  // user-defined sensor
  mjSENS_USER                     // sensor data provided by mjcb_sensor callback
} mjtSensor;

mjtStage#

These are the compute stages for the skipstage parameters of mj_forwardSkip and mj_inverseSkip.

typedef enum mjtStage_ {          // computation stage
  mjSTAGE_NONE        = 0,        // no computations
  mjSTAGE_POS,                    // position-dependent computations
  mjSTAGE_VEL,                    // velocity-dependent computations
  mjSTAGE_ACC                     // acceleration/force-dependent computations
} mjtStage;

mjtDataType#

These are the possible sensor data types, used in mjData.sensor_datatype.

typedef enum mjtDataType_ {       // data type for sensors
  mjDATATYPE_REAL     = 0,        // real values, no constraints
  mjDATATYPE_POSITIVE,            // positive values; 0 or negative: inactive
  mjDATATYPE_AXIS,                // 3D unit vector
  mjDATATYPE_QUATERNION           // unit quaternion
} mjtDataType;

Data#

The enums below are defined in mjdata.h.

mjtWarning#

Warning types. The number of warning types is given by mjNWARNING which is also the length of the array mjData.warning.

typedef enum mjtWarning_ {   // warning types
  mjWARN_INERTIA      = 0,   // (near) singular inertia matrix
  mjWARN_CONTACTFULL,        // too many contacts in contact list
  mjWARN_CNSTRFULL,          // too many constraints
  mjWARN_VGEOMFULL,          // too many visual geoms
  mjWARN_BADQPOS,            // bad number in qpos
  mjWARN_BADQVEL,            // bad number in qvel
  mjWARN_BADQACC,            // bad number in qacc
  mjWARN_BADCTRL,            // bad number in ctrl

  mjNWARNING                 // number of warnings
} mjtWarning;

mjtTimer#

Timer types. The number of timer types is given by mjNTIMER which is also the length of the array mjData.timer, as well as the length of the string array mjTIMERSTRING with timer names.

typedef enum mjtTimer_ {     // internal timers
  // main api
  mjTIMER_STEP        = 0,   // step
  mjTIMER_FORWARD,           // forward
  mjTIMER_INVERSE,           // inverse

  // breakdown of step/forward
  mjTIMER_POSITION,          // fwdPosition
  mjTIMER_VELOCITY,          // fwdVelocity
  mjTIMER_ACTUATION,         // fwdActuation
  mjTIMER_ACCELERATION,      // fwdAcceleration
  mjTIMER_CONSTRAINT,        // fwdConstraint

  // breakdown of fwdPosition
  mjTIMER_POS_KINEMATICS,    // kinematics, com, tendon, transmission
  mjTIMER_POS_INERTIA,       // inertia computations
  mjTIMER_POS_COLLISION,     // collision detection
  mjTIMER_POS_MAKE,          // make constraints
  mjTIMER_POS_PROJECT,       // project constraints

  mjNTIMER                   // number of timers
} mjtTimer;

Visualization#

The enums below are defined in mjvisualize.h.

mjtCatBit#

These are the available categories of geoms in the abstract visualizer. The bitmask can be used in the function mjr_render to specify which categories should be rendered.

typedef enum mjtCatBit_ {         // bitflags for mjvGeom category
  mjCAT_STATIC        = 1,        // model elements in body 0
  mjCAT_DYNAMIC       = 2,        // model elements in all other bodies
  mjCAT_DECOR         = 4,        // decorative geoms
  mjCAT_ALL           = 7         // select all categories
} mjtCatBit;

mjtMouse#

These are the mouse actions that the abstract visualizer recognizes. It is up to the user to intercept mouse events and translate them into these actions, as illustrated in simulate.cc.

typedef enum mjtMouse_ {          // mouse interaction mode
  mjMOUSE_NONE        = 0,        // no action
  mjMOUSE_ROTATE_V,               // rotate, vertical plane
  mjMOUSE_ROTATE_H,               // rotate, horizontal plane
  mjMOUSE_MOVE_V,                 // move, vertical plane
  mjMOUSE_MOVE_H,                 // move, horizontal plane
  mjMOUSE_ZOOM,                   // zoom
  mjMOUSE_SELECT                  // selection
} mjtMouse;

mjtPertBit#

These bitmasks enable the translational and rotational components of the mouse perturbation. For the regular mouse, only one can be enabled at a time. For the 3D mouse (SpaceNavigator) both can be enabled simultaneously. They are used in mjvPerturb.active.

typedef enum mjtPertBit_ {        // mouse perturbations
  mjPERT_TRANSLATE    = 1,        // translation
  mjPERT_ROTATE       = 2         // rotation
} mjtPertBit;

mjtCamera#

These are the possible camera types, used in mjvCamera.type.

typedef enum mjtCamera_ {         // abstract camera type
  mjCAMERA_FREE       = 0,        // free camera
  mjCAMERA_TRACKING,              // tracking camera; uses trackbodyid
  mjCAMERA_FIXED,                 // fixed camera; uses fixedcamid
  mjCAMERA_USER                   // user is responsible for setting OpenGL camera
} mjtCamera;

mjtLabel#

These are the abstract visualization elements that can have text labels. Used in mjvOption.label.

typedef enum mjtLabel_ {          // object labeling
  mjLABEL_NONE        = 0,        // nothing
  mjLABEL_BODY,                   // body labels
  mjLABEL_JOINT,                  // joint labels
  mjLABEL_GEOM,                   // geom labels
  mjLABEL_SITE,                   // site labels
  mjLABEL_CAMERA,                 // camera labels
  mjLABEL_LIGHT,                  // light labels
  mjLABEL_TENDON,                 // tendon labels
  mjLABEL_ACTUATOR,               // actuator labels
  mjLABEL_CONSTRAINT,             // constraint labels
  mjLABEL_SKIN,                   // skin labels
  mjLABEL_SELECTION,              // selected object
  mjLABEL_SELPNT,                 // coordinates of selection point
  mjLABEL_CONTACTPOINT,           // contact information
  mjLABEL_CONTACTFORCE,           // magnitude of contact force

  mjNLABEL                        // number of label types
} mjtLabel;

mjtFrame#

These are the MuJoCo objects whose spatial frames can be rendered. Used in mjvOption.frame.

typedef enum mjtFrame_ {          // frame visualization
  mjFRAME_NONE        = 0,        // no frames
  mjFRAME_BODY,                   // body frames
  mjFRAME_GEOM,                   // geom frames
  mjFRAME_SITE,                   // site frames
  mjFRAME_CAMERA,                 // camera frames
  mjFRAME_LIGHT,                  // light frames
  mjFRAME_CONTACT,                // contact frames
  mjFRAME_WORLD,                  // world frame

  mjNFRAME                        // number of visualization frames
} mjtFrame;

mjtVisFlag#

These are indices in the array mjvOption.flags, whose elements enable/disable the visualization of the corresponding model or decoration element.

typedef enum mjtVisFlag_ {        // flags enabling model element visualization
  mjVIS_CONVEXHULL    = 0,        // mesh convex hull
  mjVIS_TEXTURE,                  // textures
  mjVIS_JOINT,                    // joints
  mjVIS_CAMERA,                   // cameras
  mjVIS_ACTUATOR,                 // actuators
  mjVIS_ACTIVATION,               // activations
  mjVIS_LIGHT,                    // lights
  mjVIS_TENDON,                   // tendons
  mjVIS_RANGEFINDER,              // rangefinder sensors
  mjVIS_CONSTRAINT,               // point constraints
  mjVIS_INERTIA,                  // equivalent inertia boxes
  mjVIS_SCLINERTIA,               // scale equivalent inertia boxes with mass
  mjVIS_PERTFORCE,                // perturbation force
  mjVIS_PERTOBJ,                  // perturbation object
  mjVIS_CONTACTPOINT,             // contact points
  mjVIS_CONTACTFORCE,             // contact force
  mjVIS_CONTACTSPLIT,             // split contact force into normal and tangent
  mjVIS_TRANSPARENT,              // make dynamic geoms more transparent
  mjVIS_AUTOCONNECT,              // auto connect joints and body coms
  mjVIS_COM,                      // center of mass
  mjVIS_SELECT,                   // selection point
  mjVIS_STATIC,                   // static bodies
  mjVIS_SKIN,                     // skin
  mjVIS_MIDPHASE,                 // mid-phase bounding volume hierarchy

  mjNVISFLAG                      // number of visualization flags
} mjtVisFlag;

mjtRndFlag#

These are indices in the array mjvScene.flags, whose elements enable/disable OpenGL rendering effects.

typedef enum mjtRndFlag_ {        // flags enabling rendering effects
  mjRND_SHADOW        = 0,        // shadows
  mjRND_WIREFRAME,                // wireframe
  mjRND_REFLECTION,               // reflections
  mjRND_ADDITIVE,                 // additive transparency
  mjRND_SKYBOX,                   // skybox
  mjRND_FOG,                      // fog
  mjRND_HAZE,                     // haze
  mjRND_SEGMENT,                  // segmentation with random color
  mjRND_IDCOLOR,                  // segmentation with segid+1 color
  mjRND_CULL_FACE,                // cull backward faces

  mjNRNDFLAG                      // number of rendering flags
} mjtRndFlag;

mjtStereo#

These are the possible stereo rendering types. They are used in mjvScene.stereo.

typedef enum mjtStereo_ {         // type of stereo rendering
  mjSTEREO_NONE       = 0,        // no stereo; use left eye only
  mjSTEREO_QUADBUFFERED,          // quad buffered; revert to side-by-side if no hardware support
  mjSTEREO_SIDEBYSIDE             // side-by-side
} mjtStereo;

Rendering#

The enums below are defined in mjrender.h.

mjtGridPos#

These are the possible grid positions for text overlays. They are used as an argument to the function mjr_overlay.

typedef enum mjtGridPos_ {        // grid position for overlay
  mjGRID_TOPLEFT      = 0,        // top left
  mjGRID_TOPRIGHT,                // top right
  mjGRID_BOTTOMLEFT,              // bottom left
  mjGRID_BOTTOMRIGHT              // bottom right
} mjtGridPos;

mjtFramebuffer#

These are the possible framebuffers. They are used as an argument to the function mjr_setBuffer.

typedef enum mjtFramebuffer_ {    // OpenGL framebuffer option
  mjFB_WINDOW         = 0,        // default/window buffer
  mjFB_OFFSCREEN                  // offscreen buffer
} mjtFramebuffer;

mjtFontScale#

These are the possible font sizes. The fonts are predefined bitmaps stored in the dynamic library at three different sizes.

typedef enum mjtFontScale_ {      // font scale, used at context creation
  mjFONTSCALE_50      = 50,       // 50% scale, suitable for low-res rendering
  mjFONTSCALE_100     = 100,      // normal scale, suitable in the absence of DPI scaling
  mjFONTSCALE_150     = 150,      // 150% scale
  mjFONTSCALE_200     = 200,      // 200% scale
  mjFONTSCALE_250     = 250,      // 250% scale
  mjFONTSCALE_300     = 300       // 300% scale
} mjtFontScale;

mjtFont#

These are the possible font types.

typedef enum mjtFont_ {           // font type, used at each text operation
  mjFONT_NORMAL       = 0,        // normal font
  mjFONT_SHADOW,                  // normal font with shadow (for higher contrast)
  mjFONT_BIG                      // big font (for user alerts)
} mjtFont;

User Interface#

The enums below are defined in mjui.h.

mjtButton#

Mouse button IDs used in the UI framework.

typedef enum mjtButton_ {         // mouse button
  mjBUTTON_NONE = 0,              // no button
  mjBUTTON_LEFT,                  // left button
  mjBUTTON_RIGHT,                 // right button
  mjBUTTON_MIDDLE                 // middle button
} mjtButton;

mjtEvent#

Event types used in the UI framework.

typedef enum mjtEvent_ {          // mouse and keyboard event type
  mjEVENT_NONE = 0,               // no event
  mjEVENT_MOVE,                   // mouse move
  mjEVENT_PRESS,                  // mouse button press
  mjEVENT_RELEASE,                // mouse button release
  mjEVENT_SCROLL,                 // scroll
  mjEVENT_KEY,                    // key press
  mjEVENT_RESIZE,                 // resize
  mjEVENT_REDRAW,                 // redraw
  mjEVENT_FILESDROP               // files drop
} mjtEvent;

mjtItem#

Item types used in the UI framework.

typedef enum mjtItem_ {           // UI item type
  mjITEM_END = -2,                // end of definition list (not an item)
  mjITEM_SECTION = -1,            // section (not an item)
  mjITEM_SEPARATOR = 0,           // separator
  mjITEM_STATIC,                  // static text
  mjITEM_BUTTON,                  // button

  // the rest have data pointer
  mjITEM_CHECKINT,                // check box, int value
  mjITEM_CHECKBYTE,               // check box, mjtByte value
  mjITEM_RADIO,                   // radio group
  mjITEM_RADIOLINE,               // radio group, single line
  mjITEM_SELECT,                  // selection box
  mjITEM_SLIDERINT,               // slider, int value
  mjITEM_SLIDERNUM,               // slider, mjtNum value
  mjITEM_EDITINT,                 // editable array, int values
  mjITEM_EDITNUM,                 // editable array, mjtNum values
  mjITEM_EDITTXT,                 // editable text

  mjNITEM                         // number of item types
} mjtItem;

Plugins#

The enums below are defined in mjplugin.h. See Engine plugins for details.

mjtPluginCapabilityBit#

Capabilities declared by an engine plugin.

typedef enum mjtPluginCapabilityBit_ {
  mjPLUGIN_ACTUATOR = 1<<0,
  mjPLUGIN_SENSOR   = 1<<1,
  mjPLUGIN_PASSIVE  = 1<<2,
} mjtPluginCapabilityBit;

Struct types#

Main#

The three central struct types for physics simulation are mjModel, mjOption (embedded in mjModel) and mjData. An introductory discussion of these strucures can be found in the Overview under Separation of model and data.

mjModel#

This is the main data structure holding the MuJoCo model. It is treated as constant by the simulator. Some specific details regarding datastructures in mjModel can be found below in Notes.

struct mjModel_ {
  // ------------------------------- sizes

  // sizes needed at mjModel construction
  int nq;                         // number of generalized coordinates = dim(qpos)
  int nv;                         // number of degrees of freedom = dim(qvel)
  int nu;                         // number of actuators/controls = dim(ctrl)
  int na;                         // number of activation states = dim(act)
  int nbody;                      // number of bodies
  int nbvh;                       // number of total bounding volumes in all bodies
  int njnt;                       // number of joints
  int ngeom;                      // number of geoms
  int nsite;                      // number of sites
  int ncam;                       // number of cameras
  int nlight;                     // number of lights
  int nmesh;                      // number of meshes
  int nmeshvert;                  // number of vertices in all meshes
  int nmeshnormal;                // number of normals in all meshes
  int nmeshtexcoord;              // number of texcoords in all meshes
  int nmeshface;                  // number of triangular faces in all meshes
  int nmeshgraph;                 // number of ints in mesh auxiliary data
  int nskin;                      // number of skins
  int nskinvert;                  // number of vertices in all skins
  int nskintexvert;               // number of vertiex with texcoords in all skins
  int nskinface;                  // number of triangular faces in all skins
  int nskinbone;                  // number of bones in all skins
  int nskinbonevert;              // number of vertices in all skin bones
  int nhfield;                    // number of heightfields
  int nhfielddata;                // number of data points in all heightfields
  int ntex;                       // number of textures
  int ntexdata;                   // number of bytes in texture rgb data
  int nmat;                       // number of materials
  int npair;                      // number of predefined geom pairs
  int nexclude;                   // number of excluded geom pairs
  int neq;                        // number of equality constraints
  int ntendon;                    // number of tendons
  int nwrap;                      // number of wrap objects in all tendon paths
  int nsensor;                    // number of sensors
  int nnumeric;                   // number of numeric custom fields
  int nnumericdata;               // number of mjtNums in all numeric fields
  int ntext;                      // number of text custom fields
  int ntextdata;                  // number of mjtBytes in all text fields
  int ntuple;                     // number of tuple custom fields
  int ntupledata;                 // number of objects in all tuple fields
  int nkey;                       // number of keyframes
  int nmocap;                     // number of mocap bodies
  int nplugin;                    // number of plugin instances
  int npluginattr;                // number of chars in all plugin config attributes
  int nuser_body;                 // number of mjtNums in body_user
  int nuser_jnt;                  // number of mjtNums in jnt_user
  int nuser_geom;                 // number of mjtNums in geom_user
  int nuser_site;                 // number of mjtNums in site_user
  int nuser_cam;                  // number of mjtNums in cam_user
  int nuser_tendon;               // number of mjtNums in tendon_user
  int nuser_actuator;             // number of mjtNums in actuator_user
  int nuser_sensor;               // number of mjtNums in sensor_user
  int nnames;                     // number of chars in all names
  int nnames_map;                 // number of slots in the names hash map

  // sizes set after mjModel construction (only affect mjData)
  int nM;                         // number of non-zeros in sparse inertia matrix
  int nD;                         // number of non-zeros in sparse dof-dof matrix
  int nB;                         // number of non-zeros in sparse body-dof matrix
  int nemax;                      // number of potential equality-constraint rows
  int njmax;                      // number of available rows in constraint Jacobian
  int nconmax;                    // number of potential contacts in contact list
  int nstack;                     // number of fields in mjData stack
  int nuserdata;                  // number of extra fields in mjData
  int nsensordata;                // number of fields in sensor data vector
  int npluginstate;               // number of fields in the plugin state vector

  int nbuffer;                    // number of bytes in buffer

  // ------------------------------- options and statistics

  mjOption opt;                   // physics options
  mjVisual vis;                   // visualization options
  mjStatistic stat;               // model statistics

  // ------------------------------- buffers

  // main buffer
  void*     buffer;               // main buffer; all pointers point in it    (nbuffer)

  // default generalized coordinates
  mjtNum*   qpos0;                // qpos values at default pose              (nq x 1)
  mjtNum*   qpos_spring;          // reference pose for springs               (nq x 1)

  // bodies
  int*      body_parentid;        // id of body's parent                      (nbody x 1)
  int*      body_rootid;          // id of root above body                    (nbody x 1)
  int*      body_weldid;          // id of body that this body is welded to   (nbody x 1)
  int*      body_mocapid;         // id of mocap data; -1: none               (nbody x 1)
  int*      body_jntnum;          // number of joints for this body           (nbody x 1)
  int*      body_jntadr;          // start addr of joints; -1: no joints      (nbody x 1)
  int*      body_dofnum;          // number of motion degrees of freedom      (nbody x 1)
  int*      body_dofadr;          // start addr of dofs; -1: no dofs          (nbody x 1)
  int*      body_geomnum;         // number of geoms                          (nbody x 1)
  int*      body_geomadr;         // start addr of geoms; -1: no geoms        (nbody x 1)
  mjtByte*  body_simple;          // body is simple (has diagonal M)          (nbody x 1)
  mjtByte*  body_sameframe;       // inertial frame is same as body frame     (nbody x 1)
  mjtNum*   body_pos;             // position offset rel. to parent body      (nbody x 3)
  mjtNum*   body_quat;            // orientation offset rel. to parent body   (nbody x 4)
  mjtNum*   body_ipos;            // local position of center of mass         (nbody x 3)
  mjtNum*   body_iquat;           // local orientation of inertia ellipsoid   (nbody x 4)
  mjtNum*   body_mass;            // mass                                     (nbody x 1)
  mjtNum*   body_subtreemass;     // mass of subtree starting at this body    (nbody x 1)
  mjtNum*   body_inertia;         // diagonal inertia in ipos/iquat frame     (nbody x 3)
  mjtNum*   body_invweight0;      // mean inv inert in qpos0 (trn, rot)       (nbody x 2)
  mjtNum*   body_gravcomp;        // antigravity force, units of body weight  (nbody x 1)
  mjtNum*   body_user;            // user data                                (nbody x nuser_body)
  int*      body_plugin;          // plugin instance id; -1: not in use       (nbody x 1)
  int*      body_bvhadr;          // address of bvh root                      (nbody x 1)
  int*      body_bvhnum;          // number of bounding volumes               (nbody x 1)

  // bounding volume hierarchy
  int*      bvh_depth;            // depth in the bounding volume hierarchy   (nbvh x 1)
  int*      bvh_child;            // left and right children in tree          (nbvh x 2)
  int*      bvh_geomid;           // geom id of the node; -1: non-leaf        (nbvh x 1)
  mjtNum*   bvh_aabb;             // bounding box of node (center, size)      (nbvh x 6)

  // joints
  int*      jnt_type;             // type of joint (mjtJoint)                 (njnt x 1)
  int*      jnt_qposadr;          // start addr in 'qpos' for joint's data    (njnt x 1)
  int*      jnt_dofadr;           // start addr in 'qvel' for joint's data    (njnt x 1)
  int*      jnt_bodyid;           // id of joint's body                       (njnt x 1)
  int*      jnt_group;            // group for visibility                     (njnt x 1)
  mjtByte*  jnt_limited;          // does joint have limits                   (njnt x 1)
  mjtNum*   jnt_solref;           // constraint solver reference: limit       (njnt x mjNREF)
  mjtNum*   jnt_solimp;           // constraint solver impedance: limit       (njnt x mjNIMP)
  mjtNum*   jnt_pos;              // local anchor position                    (njnt x 3)
  mjtNum*   jnt_axis;             // local joint axis                         (njnt x 3)
  mjtNum*   jnt_stiffness;        // stiffness coefficient                    (njnt x 1)
  mjtNum*   jnt_range;            // joint limits                             (njnt x 2)
  mjtNum*   jnt_margin;           // min distance for limit detection         (njnt x 1)
  mjtNum*   jnt_user;             // user data                                (njnt x nuser_jnt)

  // dofs
  int*      dof_bodyid;           // id of dof's body                         (nv x 1)
  int*      dof_jntid;            // id of dof's joint                        (nv x 1)
  int*      dof_parentid;         // id of dof's parent; -1: none             (nv x 1)
  int*      dof_Madr;             // dof address in M-diagonal                (nv x 1)
  int*      dof_simplenum;        // number of consecutive simple dofs        (nv x 1)
  mjtNum*   dof_solref;           // constraint solver reference:frictionloss (nv x mjNREF)
  mjtNum*   dof_solimp;           // constraint solver impedance:frictionloss (nv x mjNIMP)
  mjtNum*   dof_frictionloss;     // dof friction loss                        (nv x 1)
  mjtNum*   dof_armature;         // dof armature inertia/mass                (nv x 1)
  mjtNum*   dof_damping;          // damping coefficient                      (nv x 1)
  mjtNum*   dof_invweight0;       // diag. inverse inertia in qpos0           (nv x 1)
  mjtNum*   dof_M0;               // diag. inertia in qpos0                   (nv x 1)

  // geoms
  int*      geom_type;            // geometric type (mjtGeom)                 (ngeom x 1)
  int*      geom_contype;         // geom contact type                        (ngeom x 1)
  int*      geom_conaffinity;     // geom contact affinity                    (ngeom x 1)
  int*      geom_condim;          // contact dimensionality (1, 3, 4, 6)      (ngeom x 1)
  int*      geom_bodyid;          // id of geom's body                        (ngeom x 1)
  int*      geom_dataid;          // id of geom's mesh/hfield; -1: none       (ngeom x 1)
  int*      geom_matid;           // material id for rendering; -1: none      (ngeom x 1)
  int*      geom_group;           // group for visibility                     (ngeom x 1)
  int*      geom_priority;        // geom contact priority                    (ngeom x 1)
  mjtByte*  geom_sameframe;       // same as body frame (1) or iframe (2)     (ngeom x 1)
  mjtNum*   geom_solmix;          // mixing coef for solref/imp in geom pair  (ngeom x 1)
  mjtNum*   geom_solref;          // constraint solver reference: contact     (ngeom x mjNREF)
  mjtNum*   geom_solimp;          // constraint solver impedance: contact     (ngeom x mjNIMP)
  mjtNum*   geom_size;            // geom-specific size parameters            (ngeom x 3)
  mjtNum*   geom_aabb;            // bounding box, (center, size)             (ngeom x 6)
  mjtNum*   geom_rbound;          // radius of bounding sphere                (ngeom x 1)
  mjtNum*   geom_pos;             // local position offset rel. to body       (ngeom x 3)
  mjtNum*   geom_quat;            // local orientation offset rel. to body    (ngeom x 4)
  mjtNum*   geom_friction;        // friction for (slide, spin, roll)         (ngeom x 3)
  mjtNum*   geom_margin;          // detect contact if dist<margin            (ngeom x 1)
  mjtNum*   geom_gap;             // include in solver if dist<margin-gap     (ngeom x 1)
  mjtNum*   geom_fluid;           // fluid interaction parameters             (ngeom x mjNFLUID)
  mjtNum*   geom_user;            // user data                                (ngeom x nuser_geom)
  float*    geom_rgba;            // rgba when material is omitted            (ngeom x 4)

  // sites
  int*      site_type;            // geom type for rendering (mjtGeom)        (nsite x 1)
  int*      site_bodyid;          // id of site's body                        (nsite x 1)
  int*      site_matid;           // material id for rendering; -1: none      (nsite x 1)
  int*      site_group;           // group for visibility                     (nsite x 1)
  mjtByte*  site_sameframe;       // same as body frame (1) or iframe (2)     (nsite x 1)
  mjtNum*   site_size;            // geom size for rendering                  (nsite x 3)
  mjtNum*   site_pos;             // local position offset rel. to body       (nsite x 3)
  mjtNum*   site_quat;            // local orientation offset rel. to body    (nsite x 4)
  mjtNum*   site_user;            // user data                                (nsite x nuser_site)
  float*    site_rgba;            // rgba when material is omitted            (nsite x 4)

  // cameras
  int*      cam_mode;             // camera tracking mode (mjtCamLight)       (ncam x 1)
  int*      cam_bodyid;           // id of camera's body                      (ncam x 1)
  int*      cam_targetbodyid;     // id of targeted body; -1: none            (ncam x 1)
  mjtNum*   cam_pos;              // position rel. to body frame              (ncam x 3)
  mjtNum*   cam_quat;             // orientation rel. to body frame           (ncam x 4)
  mjtNum*   cam_poscom0;          // global position rel. to sub-com in qpos0 (ncam x 3)
  mjtNum*   cam_pos0;             // global position rel. to body in qpos0    (ncam x 3)
  mjtNum*   cam_mat0;             // global orientation in qpos0              (ncam x 9)
  mjtNum*   cam_fovy;             // y-field of view (deg)                    (ncam x 1)
  mjtNum*   cam_ipd;              // inter-pupilary distance                  (ncam x 1)
  mjtNum*   cam_user;             // user data                                (ncam x nuser_cam)

  // lights
  int*      light_mode;           // light tracking mode (mjtCamLight)        (nlight x 1)
  int*      light_bodyid;         // id of light's body                       (nlight x 1)
  int*      light_targetbodyid;   // id of targeted body; -1: none            (nlight x 1)
  mjtByte*  light_directional;    // directional light                        (nlight x 1)
  mjtByte*  light_castshadow;     // does light cast shadows                  (nlight x 1)
  mjtByte*  light_active;         // is light on                              (nlight x 1)
  mjtNum*   light_pos;            // position rel. to body frame              (nlight x 3)
  mjtNum*   light_dir;            // direction rel. to body frame             (nlight x 3)
  mjtNum*   light_poscom0;        // global position rel. to sub-com in qpos0 (nlight x 3)
  mjtNum*   light_pos0;           // global position rel. to body in qpos0    (nlight x 3)
  mjtNum*   light_dir0;           // global direction in qpos0                (nlight x 3)
  float*    light_attenuation;    // OpenGL attenuation (quadratic model)     (nlight x 3)
  float*    light_cutoff;         // OpenGL cutoff                            (nlight x 1)
  float*    light_exponent;       // OpenGL exponent                          (nlight x 1)
  float*    light_ambient;        // ambient rgb (alpha=1)                    (nlight x 3)
  float*    light_diffuse;        // diffuse rgb (alpha=1)                    (nlight x 3)
  float*    light_specular;       // specular rgb (alpha=1)                   (nlight x 3)

  // meshes
  int*      mesh_vertadr;         // first vertex address                     (nmesh x 1)
  int*      mesh_vertnum;         // number of vertices                       (nmesh x 1)
  int*      mesh_faceadr;         // first face address                       (nmesh x 1)
  int*      mesh_facenum;         // number of faces                          (nmesh x 1)
  int*      mesh_normaladr;       // first normal address                     (nmesh x 1)
  int*      mesh_normalnum;       // number of normals                        (nmesh x 1)
  int*      mesh_texcoordadr;     // texcoord data address; -1: no texcoord   (nmesh x 1)
  int*      mesh_texcoordnum;     // number of texcoord                       (nmesh x 1)
  int*      mesh_graphadr;        // graph data address; -1: no graph         (nmesh x 1)
  float*    mesh_vert;            // vertex positions for all meshes          (nmeshvert x 3)
  float*    mesh_normal;          // normals for all meshes                   (nmeshnormal x 3)
  float*    mesh_texcoord;        // vertex texcoords for all meshes          (nmeshtexcoord x 2)
  int*      mesh_face;            // vertex face data                         (nmeshface x 3)
  int*      mesh_facenormal;      // normal face data                         (nmeshface x 3)
  int*      mesh_facetexcoord;    // texture face data                        (nmeshface x 3)
  int*      mesh_graph;           // convex graph data                        (nmeshgraph x 1)

  // skins
  int*      skin_matid;           // skin material id; -1: none               (nskin x 1)
  int*      skin_group;           // group for visibility                     (nskin x 1)
  float*    skin_rgba;            // skin rgba                                (nskin x 4)
  float*    skin_inflate;         // inflate skin in normal direction         (nskin x 1)
  int*      skin_vertadr;         // first vertex address                     (nskin x 1)
  int*      skin_vertnum;         // number of vertices                       (nskin x 1)
  int*      skin_texcoordadr;     // texcoord data address; -1: no texcoord   (nskin x 1)
  int*      skin_faceadr;         // first face address                       (nskin x 1)
  int*      skin_facenum;         // number of faces                          (nskin x 1)
  int*      skin_boneadr;         // first bone in skin                       (nskin x 1)
  int*      skin_bonenum;         // number of bones in skin                  (nskin x 1)
  float*    skin_vert;            // vertex positions for all skin meshes     (nskinvert x 3)
  float*    skin_texcoord;        // vertex texcoords for all skin meshes     (nskintexvert x 2)
  int*      skin_face;            // triangle faces for all skin meshes       (nskinface x 3)
  int*      skin_bonevertadr;     // first vertex in each bone                (nskinbone x 1)
  int*      skin_bonevertnum;     // number of vertices in each bone          (nskinbone x 1)
  float*    skin_bonebindpos;     // bind pos of each bone                    (nskinbone x 3)
  float*    skin_bonebindquat;    // bind quat of each bone                   (nskinbone x 4)
  int*      skin_bonebodyid;      // body id of each bone                     (nskinbone x 1)
  int*      skin_bonevertid;      // mesh ids of vertices in each bone        (nskinbonevert x 1)
  float*    skin_bonevertweight;  // weights of vertices in each bone         (nskinbonevert x 1)

  // height fields
  mjtNum*   hfield_size;          // (x, y, z_top, z_bottom)                  (nhfield x 4)
  int*      hfield_nrow;          // number of rows in grid                   (nhfield x 1)
  int*      hfield_ncol;          // number of columns in grid                (nhfield x 1)
  int*      hfield_adr;           // address in hfield_data                   (nhfield x 1)
  float*    hfield_data;          // elevation data                           (nhfielddata x 1)

  // textures
  int*      tex_type;             // texture type (mjtTexture)                (ntex x 1)
  int*      tex_height;           // number of rows in texture image          (ntex x 1)
  int*      tex_width;            // number of columns in texture image       (ntex x 1)
  int*      tex_adr;              // address in rgb                           (ntex x 1)
  mjtByte*  tex_rgb;              // rgb (alpha = 1)                          (ntexdata x 1)

  // materials
  int*      mat_texid;            // texture id; -1: none                     (nmat x 1)
  mjtByte*  mat_texuniform;       // make texture cube uniform                (nmat x 1)
  float*    mat_texrepeat;        // texture repetition for 2d mapping        (nmat x 2)
  float*    mat_emission;         // emission (x rgb)                         (nmat x 1)
  float*    mat_specular;         // specular (x white)                       (nmat x 1)
  float*    mat_shininess;        // shininess coef                           (nmat x 1)
  float*    mat_reflectance;      // reflectance (0: disable)                 (nmat x 1)
  float*    mat_rgba;             // rgba                                     (nmat x 4)

  // predefined geom pairs for collision detection; has precedence over exclude
  int*      pair_dim;             // contact dimensionality                   (npair x 1)
  int*      pair_geom1;           // id of geom1                              (npair x 1)
  int*      pair_geom2;           // id of geom2                              (npair x 1)
  int*      pair_signature;       // (body1+1) << 16 + body2+1                (npair x 1)
  mjtNum*   pair_solref;          // constraint solver reference: contact     (npair x mjNREF)
  mjtNum*   pair_solimp;          // constraint solver impedance: contact     (npair x mjNIMP)
  mjtNum*   pair_margin;          // detect contact if dist<margin            (npair x 1)
  mjtNum*   pair_gap;             // include in solver if dist<margin-gap     (npair x 1)
  mjtNum*   pair_friction;        // tangent1, 2, spin, roll1, 2              (npair x 5)

  // excluded body pairs for collision detection
  int*      exclude_signature;    // (body1+1) << 16 + body2+1                (nexclude x 1)

  // equality constraints
  int*      eq_type;              // constraint type (mjtEq)                  (neq x 1)
  int*      eq_obj1id;            // id of object 1                           (neq x 1)
  int*      eq_obj2id;            // id of object 2                           (neq x 1)
  mjtByte*  eq_active;            // enable/disable constraint                (neq x 1)
  mjtNum*   eq_solref;            // constraint solver reference              (neq x mjNREF)
  mjtNum*   eq_solimp;            // constraint solver impedance              (neq x mjNIMP)
  mjtNum*   eq_data;              // numeric data for constraint              (neq x mjNEQDATA)

  // tendons
  int*      tendon_adr;           // address of first object in tendon's path (ntendon x 1)
  int*      tendon_num;           // number of objects in tendon's path       (ntendon x 1)
  int*      tendon_matid;         // material id for rendering                (ntendon x 1)
  int*      tendon_group;         // group for visibility                     (ntendon x 1)
  mjtByte*  tendon_limited;       // does tendon have length limits           (ntendon x 1)
  mjtNum*   tendon_width;         // width for rendering                      (ntendon x 1)
  mjtNum*   tendon_solref_lim;    // constraint solver reference: limit       (ntendon x mjNREF)
  mjtNum*   tendon_solimp_lim;    // constraint solver impedance: limit       (ntendon x mjNIMP)
  mjtNum*   tendon_solref_fri;    // constraint solver reference: friction    (ntendon x mjNREF)
  mjtNum*   tendon_solimp_fri;    // constraint solver impedance: friction    (ntendon x mjNIMP)
  mjtNum*   tendon_range;         // tendon length limits                     (ntendon x 2)
  mjtNum*   tendon_margin;        // min distance for limit detection         (ntendon x 1)
  mjtNum*   tendon_stiffness;     // stiffness coefficient                    (ntendon x 1)
  mjtNum*   tendon_damping;       // damping coefficient                      (ntendon x 1)
  mjtNum*   tendon_frictionloss;  // loss due to friction                     (ntendon x 1)
  mjtNum*   tendon_lengthspring;  // spring resting length range              (ntendon x 2)
  mjtNum*   tendon_length0;       // tendon length in qpos0                   (ntendon x 1)
  mjtNum*   tendon_invweight0;    // inv. weight in qpos0                     (ntendon x 1)
  mjtNum*   tendon_user;          // user data                                (ntendon x nuser_tendon)
  float*    tendon_rgba;          // rgba when material is omitted            (ntendon x 4)

  // list of all wrap objects in tendon paths
  int*      wrap_type;            // wrap object type (mjtWrap)               (nwrap x 1)
  int*      wrap_objid;           // object id: geom, site, joint             (nwrap x 1)
  mjtNum*   wrap_prm;             // divisor, joint coef, or site id          (nwrap x 1)

  // actuators
  int*      actuator_trntype;     // transmission type (mjtTrn)               (nu x 1)
  int*      actuator_dyntype;     // dynamics type (mjtDyn)                   (nu x 1)
  int*      actuator_gaintype;    // gain type (mjtGain)                      (nu x 1)
  int*      actuator_biastype;    // bias type (mjtBias)                      (nu x 1)
  int*      actuator_trnid;       // transmission id: joint, tendon, site     (nu x 2)
  int*      actuator_actadr;      // first activation address; -1: stateless  (nu x 1)
  int*      actuator_actnum;      // number of activation variables           (nu x 1)
  int*      actuator_group;       // group for visibility                     (nu x 1)
  mjtByte*  actuator_ctrllimited; // is control limited                       (nu x 1)
  mjtByte*  actuator_forcelimited;// is force limited                         (nu x 1)
  mjtByte*  actuator_actlimited;  // is activation limited                    (nu x 1)
  mjtNum*   actuator_dynprm;      // dynamics parameters                      (nu x mjNDYN)
  mjtNum*   actuator_gainprm;     // gain parameters                          (nu x mjNGAIN)
  mjtNum*   actuator_biasprm;     // bias parameters                          (nu x mjNBIAS)
  mjtNum*   actuator_ctrlrange;   // range of controls                        (nu x 2)
  mjtNum*   actuator_forcerange;  // range of forces                          (nu x 2)
  mjtNum*   actuator_actrange;    // range of activations                     (nu x 2)
  mjtNum*   actuator_gear;        // scale length and transmitted force       (nu x 6)
  mjtNum*   actuator_cranklength; // crank length for slider-crank            (nu x 1)
  mjtNum*   actuator_acc0;        // acceleration from unit force in qpos0    (nu x 1)
  mjtNum*   actuator_length0;     // actuator length in qpos0                 (nu x 1)
  mjtNum*   actuator_lengthrange; // feasible actuator length range           (nu x 2)
  mjtNum*   actuator_user;        // user data                                (nu x nuser_actuator)
  int*      actuator_plugin;      // plugin instance id; -1: not a plugin     (nu x 1)

  // sensors
  int*      sensor_type;          // sensor type (mjtSensor)                  (nsensor x 1)
  int*      sensor_datatype;      // numeric data type (mjtDataType)          (nsensor x 1)
  int*      sensor_needstage;     // required compute stage (mjtStage)        (nsensor x 1)
  int*      sensor_objtype;       // type of sensorized object (mjtObj)       (nsensor x 1)
  int*      sensor_objid;         // id of sensorized object                  (nsensor x 1)
  int*      sensor_reftype;       // type of reference frame (mjtObj)         (nsensor x 1)
  int*      sensor_refid;         // id of reference frame; -1: global frame  (nsensor x 1)
  int*      sensor_dim;           // number of scalar outputs                 (nsensor x 1)
  int*      sensor_adr;           // address in sensor array                  (nsensor x 1)
  mjtNum*   sensor_cutoff;        // cutoff for real and positive; 0: ignore  (nsensor x 1)
  mjtNum*   sensor_noise;         // noise standard deviation                 (nsensor x 1)
  mjtNum*   sensor_user;          // user data                                (nsensor x nuser_sensor)
  int*      sensor_plugin;        // plugin instance id; -1: not a plugin     (nsensor x 1)

  // plugin instances
  int*      plugin;               // globally registered plugin slot number   (nplugin x 1)
  int*      plugin_stateadr;      // address in the plugin state array        (nplugin x 1)
  int*      plugin_statenum;      // number of states in the plugin instance  (nplugin x 1)
  char*     plugin_attr;          // config attributes of plugin instances    (npluginattr x 1)
  int*      plugin_attradr;       // address to each instance's config attrib (nplugin x 1)

  // custom numeric fields
  int*      numeric_adr;          // address of field in numeric_data         (nnumeric x 1)
  int*      numeric_size;         // size of numeric field                    (nnumeric x 1)
  mjtNum*   numeric_data;         // array of all numeric fields              (nnumericdata x 1)

  // custom text fields
  int*      text_adr;             // address of text in text_data             (ntext x 1)
  int*      text_size;            // size of text field (strlen+1)            (ntext x 1)
  char*     text_data;            // array of all text fields (0-terminated)  (ntextdata x 1)

  // custom tuple fields
  int*      tuple_adr;            // address of text in text_data             (ntuple x 1)
  int*      tuple_size;           // number of objects in tuple               (ntuple x 1)
  int*      tuple_objtype;        // array of object types in all tuples      (ntupledata x 1)
  int*      tuple_objid;          // array of object ids in all tuples        (ntupledata x 1)
  mjtNum*   tuple_objprm;         // array of object params in all tuples     (ntupledata x 1)

  // keyframes
  mjtNum*   key_time;             // key time                                 (nkey x 1)
  mjtNum*   key_qpos;             // key position                             (nkey x nq)
  mjtNum*   key_qvel;             // key velocity                             (nkey x nv)
  mjtNum*   key_act;              // key activation                           (nkey x na)
  mjtNum*   key_mpos;             // key mocap position                       (nkey x 3*nmocap)
  mjtNum*   key_mquat;            // key mocap quaternion                     (nkey x 4*nmocap)
  mjtNum*   key_ctrl;             // key control                              (nkey x nu)

  // names
  int*      name_bodyadr;         // body name pointers                       (nbody x 1)
  int*      name_jntadr;          // joint name pointers                      (njnt x 1)
  int*      name_geomadr;         // geom name pointers                       (ngeom x 1)
  int*      name_siteadr;         // site name pointers                       (nsite x 1)
  int*      name_camadr;          // camera name pointers                     (ncam x 1)
  int*      name_lightadr;        // light name pointers                      (nlight x 1)
  int*      name_meshadr;         // mesh name pointers                       (nmesh x 1)
  int*      name_skinadr;         // skin name pointers                       (nskin x 1)
  int*      name_hfieldadr;       // hfield name pointers                     (nhfield x 1)
  int*      name_texadr;          // texture name pointers                    (ntex x 1)
  int*      name_matadr;          // material name pointers                   (nmat x 1)
  int*      name_pairadr;         // geom pair name pointers                  (npair x 1)
  int*      name_excludeadr;      // exclude name pointers                    (nexclude x 1)
  int*      name_eqadr;           // equality constraint name pointers        (neq x 1)
  int*      name_tendonadr;       // tendon name pointers                     (ntendon x 1)
  int*      name_actuatoradr;     // actuator name pointers                   (nu x 1)
  int*      name_sensoradr;       // sensor name pointers                     (nsensor x 1)
  int*      name_numericadr;      // numeric name pointers                    (nnumeric x 1)
  int*      name_textadr;         // text name pointers                       (ntext x 1)
  int*      name_tupleadr;        // tuple name pointers                      (ntuple x 1)
  int*      name_keyadr;          // keyframe name pointers                   (nkey x 1)
  int*      name_pluginadr;       // plugin instance name pointers            (nplugin x 1)
  char*     names;                // names of all objects, 0-terminated       (nnames x 1)
  int*      names_map;            // internal hash map of names               (nnames_map x 1)
};
typedef struct mjModel_ mjModel;

mjOption#

This is the data structure with simulation options. It corresponds to the MJCF element option. One instance of it is embedded in mjModel.

struct mjOption_ {                // physics options
  // timing parameters
  mjtNum timestep;                // timestep
  mjtNum apirate;                 // update rate for remote API (Hz)

  // solver parameters
  mjtNum impratio;                // ratio of friction-to-normal contact impedance
  mjtNum tolerance;               // main solver tolerance
  mjtNum noslip_tolerance;        // noslip solver tolerance
  mjtNum mpr_tolerance;           // MPR solver tolerance

  // physical constants
  mjtNum gravity[3];              // gravitational acceleration
  mjtNum wind[3];                 // wind (for lift, drag and viscosity)
  mjtNum magnetic[3];             // global magnetic flux
  mjtNum density;                 // density of medium
  mjtNum viscosity;               // viscosity of medium

  // override contact solver parameters (if enabled)
  mjtNum o_margin;                // margin
  mjtNum o_solref[mjNREF];        // solref
  mjtNum o_solimp[mjNIMP];        // solimp

  // discrete settings
  int integrator;                 // integration mode (mjtIntegrator)
  int collision;                  // collision mode (mjtCollision)
  int cone;                       // type of friction cone (mjtCone)
  int jacobian;                   // type of Jacobian (mjtJacobian)
  int solver;                     // solver algorithm (mjtSolver)
  int iterations;                 // maximum number of main solver iterations
  int noslip_iterations;          // maximum number of noslip solver iterations
  int mpr_iterations;             // maximum number of MPR solver iterations
  int disableflags;               // bit flags for disabling standard features
  int enableflags;                // bit flags for enabling optional features
};
typedef struct mjOption_ mjOption;

mjData#

This is the main data structure holding the simulation state. It is the workspace where all functions read their modifiable inputs and write their outputs.

struct mjData_ {
  // constant sizes
  int     nstack;            // number of mjtNums that can fit in the arena+stack space
  int     nbuffer;           // size of main buffer in bytes
  int     nplugin;           // number of plugin instances

  // stack pointer
  size_t  pstack;            // first available mjtNum address in stack

  // arena pointer
  size_t  parena;            // first available byte in arena

  // memory utilization stats
  int     maxuse_stack;      // maximum stack allocation
  size_t  maxuse_arena;      // maximum arena allocation
  int     maxuse_con;        // maximum number of contacts
  int     maxuse_efc;        // maximum number of scalar constraints

  // diagnostics
  mjWarningStat warning[mjNWARNING];  // warning statistics
  mjTimerStat   timer[mjNTIMER];      // timer statistics

  // solver statistics
  mjSolverStat  solver[mjNSOLVER];  // solver statistics per iteration
  int     solver_iter;              // number of solver iterations
  int     solver_nnz;               // number of non-zeros in Hessian or efc_AR
  mjtNum  solver_fwdinv[2];         // forward-inverse comparison: qfrc, efc

  // collision statistics
  int     nbodypair_broad;   // number of body pairs in collision according to the broad-phase
  int     nbodypair_narrow;  // number of body pairs actually in collision in the narrow-phase
  int     ngeompair_mid;     // number of geom pairs in collision according to the mid-phase
  int     ngeompair_narrow;  // number of geom pairs actually in collision in the narrow-phase

  // variable sizes
  int     ne;                // number of equality constraints
  int     nf;                // number of friction constraints
  int     nefc;              // number of constraints
  int     nnzJ;              // number of non-zeros in constraint Jacobian
  int     ncon;              // number of detected contacts

  // global properties
  mjtNum  time;              // simulation time
  mjtNum  energy[2];         // potential, kinetic energy

  //-------------------------------- end of info header

  // buffers
  void*   buffer;            // main buffer; all pointers point in it                (nbuffer bytes)
  void*   arena;             // arena+stack buffer                     (nstack*sizeof(mjtNum) bytes)

  //-------------------------------- main inputs and outputs of the computation

  // state
  mjtNum* qpos;              // position                                         (nq x 1)
  mjtNum* qvel;              // velocity                                         (nv x 1)
  mjtNum* act;               // actuator activation                              (na x 1)
  mjtNum* qacc_warmstart;    // acceleration used for warmstart                  (nv x 1)
  mjtNum* plugin_state;      // plugin state                                     (npluginstate x 1)

  // control
  mjtNum* ctrl;              // control                                          (nu x 1)
  mjtNum* qfrc_applied;      // applied generalized force                        (nv x 1)
  mjtNum* xfrc_applied;      // applied Cartesian force/torque                   (nbody x 6)

  // mocap data
  mjtNum* mocap_pos;         // positions of mocap bodies                        (nmocap x 3)
  mjtNum* mocap_quat;        // orientations of mocap bodies                     (nmocap x 4)

  // dynamics
  mjtNum* qacc;              // acceleration                                     (nv x 1)
  mjtNum* act_dot;           // time-derivative of actuator activation           (na x 1)

  // user data
  mjtNum* userdata;          // user data, not touched by engine                 (nuserdata x 1)

  // sensors
  mjtNum* sensordata;        // sensor data array                                (nsensordata x 1)

  // plugins
  int*        plugin;        // copy of m->plugin, required for deletion         (nplugin x 1)
  uintptr_t*  plugin_data;   // pointer to plugin-managed data structure         (nplugin x 1)

  //-------------------------------- POSITION dependent

  // computed by mj_fwdPosition/mj_kinematics
  mjtNum* xpos;              // Cartesian position of body frame                 (nbody x 3)
  mjtNum* xquat;             // Cartesian orientation of body frame              (nbody x 4)
  mjtNum* xmat;              // Cartesian orientation of body frame              (nbody x 9)
  mjtNum* xipos;             // Cartesian position of body com                   (nbody x 3)
  mjtNum* ximat;             // Cartesian orientation of body inertia            (nbody x 9)
  mjtNum* xanchor;           // Cartesian position of joint anchor               (njnt x 3)
  mjtNum* xaxis;             // Cartesian joint axis                             (njnt x 3)
  mjtNum* geom_xpos;         // Cartesian geom position                          (ngeom x 3)
  mjtNum* geom_xmat;         // Cartesian geom orientation                       (ngeom x 9)
  mjtNum* site_xpos;         // Cartesian site position                          (nsite x 3)
  mjtNum* site_xmat;         // Cartesian site orientation                       (nsite x 9)
  mjtNum* cam_xpos;          // Cartesian camera position                        (ncam x 3)
  mjtNum* cam_xmat;          // Cartesian camera orientation                     (ncam x 9)
  mjtNum* light_xpos;        // Cartesian light position                         (nlight x 3)
  mjtNum* light_xdir;        // Cartesian light direction                        (nlight x 3)

  // computed by mj_fwdPosition/mj_comPos
  mjtNum* subtree_com;       // center of mass of each subtree                   (nbody x 3)
  mjtNum* cdof;              // com-based motion axis of each dof                (nv x 6)
  mjtNum* cinert;            // com-based body inertia and mass                  (nbody x 10)

  // computed by mj_fwdPosition/mj_tendon
  int*    ten_wrapadr;       // start address of tendon's path                   (ntendon x 1)
  int*    ten_wrapnum;       // number of wrap points in path                    (ntendon x 1)
  int*    ten_J_rownnz;      // number of non-zeros in Jacobian row              (ntendon x 1)
  int*    ten_J_rowadr;      // row start address in colind array                (ntendon x 1)
  int*    ten_J_colind;      // column indices in sparse Jacobian                (ntendon x nv)
  mjtNum* ten_length;        // tendon lengths                                   (ntendon x 1)
  mjtNum* ten_J;             // tendon Jacobian                                  (ntendon x nv)
  int*    wrap_obj;          // geom id; -1: site; -2: pulley                    (nwrap*2 x 1)
  mjtNum* wrap_xpos;         // Cartesian 3D points in all path                  (nwrap*2 x 3)

  // computed by mj_fwdPosition/mj_transmission
  mjtNum* actuator_length;   // actuator lengths                                 (nu x 1)
  mjtNum* actuator_moment;   // actuator moments                                 (nu x nv)

  // computed by mj_fwdPosition/mj_crb
  mjtNum* crb;               // com-based composite inertia and mass             (nbody x 10)
  mjtNum* qM;                // total inertia (sparse)                           (nM x 1)

  // computed by mj_fwdPosition/mj_factorM
  mjtNum* qLD;               // L'*D*L factorization of M (sparse)               (nM x 1)
  mjtNum* qLDiagInv;         // 1/diag(D)                                        (nv x 1)
  mjtNum* qLDiagSqrtInv;     // 1/sqrt(diag(D))                                  (nv x 1)

  // computed by mj_collisionTree
  mjtByte* bvh_active;       // volume has been added to collisions              (nbvh x 1)

  //-------------------------------- POSITION, VELOCITY dependent

  // computed by mj_fwdVelocity
  mjtNum* ten_velocity;      // tendon velocities                                (ntendon x 1)
  mjtNum* actuator_velocity; // actuator velocities                              (nu x 1)

  // computed by mj_fwdVelocity/mj_comVel
  mjtNum* cvel;              // com-based velocity [3D rot; 3D tran]             (nbody x 6)
  mjtNum* cdof_dot;          // time-derivative of cdof                          (nv x 6)

  // computed by mj_fwdVelocity/mj_rne (without acceleration)
  mjtNum* qfrc_bias;         // C(qpos,qvel)                                     (nv x 1)

  // computed by mj_fwdVelocity/mj_passive
  mjtNum* qfrc_passive;      // passive force                                    (nv x 1)

  // computed by mj_fwdVelocity/mj_referenceConstraint
  mjtNum* efc_vel;           // velocity in constraint space: J*qvel             (nefc x 1)
  mjtNum* efc_aref;          // reference pseudo-acceleration                    (nefc x 1)

  // computed by mj_sensorVel/mj_subtreeVel if needed
  mjtNum* subtree_linvel;    // linear velocity of subtree com                   (nbody x 3)
  mjtNum* subtree_angmom;    // angular momentum about subtree com               (nbody x 3)

  // computed by mj_Euler or mj_implicit
  mjtNum*   qH;              // L'*D*L factorization of modified M               (nM x 1)
  mjtNum*   qHDiagInv;       // 1/diag(D) of modified M                          (nv x 1)

  // computed by mj_resetData
  int*    D_rownnz;          // non-zeros in each row                            (nv x 1)
  int*    D_rowadr;          // address of each row in D_colind                  (nv x 1)
  int*    D_colind;          // column indices of non-zeros                      (nD x 1)
  int*    B_rownnz;          // non-zeros in each row                            (nbody x 1)
  int*    B_rowadr;          // address of each row in B_colind                  (nbody x 1)
  int*    B_colind;          // column indices of non-zeros                      (nB x 1)

  // computed by mj_implicit/mj_derivative
  mjtNum* qDeriv;            // d (passive + actuator - bias) / d qvel           (nD x 1)

  // computed by mj_implicit/mju_factorLUSparse
  mjtNum* qLU;               // sparse LU of (qM - dt*qDeriv)                    (nD x 1)

  //-------------------------------- POSITION, VELOCITY, CONTROL/ACCELERATION dependent

  // computed by mj_fwdActuation
  mjtNum* actuator_force;    // actuator force in actuation space                (nu x 1)
  mjtNum* qfrc_actuator;     // actuator force                                   (nv x 1)

  // computed by mj_fwdAcceleration
  mjtNum* qfrc_smooth;       // net unconstrained force                          (nv x 1)
  mjtNum* qacc_smooth;       // unconstrained acceleration                       (nv x 1)

  // computed by mj_fwdConstraint/mj_inverse
  mjtNum* qfrc_constraint;   // constraint force                                 (nv x 1)

  // computed by mj_inverse
  mjtNum* qfrc_inverse;      // net external force; should equal:                (nv x 1)
                             // qfrc_applied + J'*xfrc_applied + qfrc_actuator

  // computed by mj_sensorAcc/mj_rnePostConstraint if needed; rotation:translation format
  mjtNum* cacc;              // com-based acceleration                           (nbody x 6)
  mjtNum* cfrc_int;          // com-based interaction force with parent          (nbody x 6)
  mjtNum* cfrc_ext;          // com-based external force on body                 (nbody x 6)

  //-------------------------------- ARENA-ALLOCATED ARRAYS

  // computed by mj_collision
  mjContact* contact;        // list of all detected contacts                    (ncon x 1)

  // computed by mj_makeConstraint
  int*    efc_type;          // constraint type (mjtConstraint)                  (nefc x 1)
  int*    efc_id;            // id of object of specified type                   (nefc x 1)
  int*    efc_J_rownnz;      // number of non-zeros in constraint Jacobian row   (nefc x 1)
  int*    efc_J_rowadr;      // row start address in colind array                (nefc x 1)
  int*    efc_J_rowsuper;    // number of subsequent rows in supernode           (nefc x 1)
  int*    efc_J_colind;      // column indices in constraint Jacobian            (nnzJ x 1)
  int*    efc_JT_rownnz;     // number of non-zeros in constraint Jacobian row T (nv x 1)
  int*    efc_JT_rowadr;     // row start address in colind array              T (nv x 1)
  int*    efc_JT_rowsuper;   // number of subsequent rows in supernode         T (nv x 1)
  int*    efc_JT_colind;     // column indices in constraint Jacobian          T (nnzJ x 1)
  mjtNum* efc_J;             // constraint Jacobian                              (nnzJ x 1)
  mjtNum* efc_JT;            // constraint Jacobian transposed                   (nnzJ x 1)
  mjtNum* efc_pos;           // constraint position (equality, contact)          (nefc x 1)
  mjtNum* efc_margin;        // inclusion margin (contact)                       (nefc x 1)
  mjtNum* efc_frictionloss;  // frictionloss (friction)                          (nefc x 1)
  mjtNum* efc_diagApprox;    // approximation to diagonal of A                   (nefc x 1)
  mjtNum* efc_KBIP;          // stiffness, damping, impedance, imp'              (nefc x 4)
  mjtNum* efc_D;             // constraint mass                                  (nefc x 1)
  mjtNum* efc_R;             // inverse constraint mass                          (nefc x 1)

  // computed by mj_fwdConstraint/mj_inverse
  mjtNum* efc_b;            // linear cost term: J*qacc_smooth - aref            (nefc x 1)
  mjtNum* efc_force;        // constraint force in constraint space              (nefc x 1)
  int*    efc_state;        // constraint state (mjtConstraintState)             (nefc x 1)

  // computed by mj_projectConstraint
  int*    efc_AR_rownnz;    // number of non-zeros in AR                         (nefc x 1)
  int*    efc_AR_rowadr;    // row start address in colind array                 (nefc x 1)
  int*    efc_AR_colind;    // column indices in sparse AR                       (nefc x nefc)
  mjtNum* efc_AR;           // J*inv(M)*J' + R                                   (nefc x nefc)
};
typedef struct mjData_ mjData;

Auxillary#

These struct types are used in the engine and their names are prefixed with mj. mjVisual and mjStatistic are embedded in mjModel, mjContact is embedded in mjData, and mjVFS is a library-level struct used for loading assets.

mjVisual#

This is the data structure with abstract visualization options. It corresponds to the MJCF element visual. One instance of it is embedded in mjModel.

struct mjVisual_ {                // visualization options
  struct {                        // global parameters
    float fovy;                   // y-field of view for free camera (degrees)
    float ipd;                    // inter-pupilary distance for free camera
    float azimuth;                // initial azimuth of free camera (degrees)
    float elevation;              // initial elevation of free camera (degrees)
    float linewidth;              // line width for wireframe and ray rendering
    float glow;                   // glow coefficient for selected body
    float realtime;               // initial real-time factor (1: real time)
    int offwidth;                 // width of offscreen buffer
    int offheight;                // height of offscreen buffer
    int ellipsoidinertia;         // geom for inertia visualization (0: box, 1: ellipsoid)
  } global;

  struct {                        // rendering quality
    int   shadowsize;             // size of shadowmap texture
    int   offsamples;             // number of multisamples for offscreen rendering
    int   numslices;              // number of slices for builtin geom drawing
    int   numstacks;              // number of stacks for builtin geom drawing
    int   numquads;               // number of quads for box rendering
  } quality;

  struct {                        // head light
    float ambient[3];             // ambient rgb (alpha=1)
    float diffuse[3];             // diffuse rgb (alpha=1)
    float specular[3];            // specular rgb (alpha=1)
    int   active;                 // is headlight active
  } headlight;

  struct {                        // mapping
    float stiffness;              // mouse perturbation stiffness (space->force)
    float stiffnessrot;           // mouse perturbation stiffness (space->torque)
    float force;                  // from force units to space units
    float torque;                 // from torque units to space units
    float alpha;                  // scale geom alphas when transparency is enabled
    float fogstart;               // OpenGL fog starts at fogstart * mjModel.stat.extent
    float fogend;                 // OpenGL fog ends at fogend * mjModel.stat.extent
    float znear;                  // near clipping plane = znear * mjModel.stat.extent
    float zfar;                   // far clipping plane = zfar * mjModel.stat.extent
    float haze;                   // haze ratio
    float shadowclip;             // directional light: shadowclip * mjModel.stat.extent
    float shadowscale;            // spot light: shadowscale * light.cutoff
    float actuatortendon;         // scale tendon width
  } map;

  struct {                        // scale of decor elements relative to mean body size
    float forcewidth;             // width of force arrow
    float contactwidth;           // contact width
    float contactheight;          // contact height
    float connect;                // autoconnect capsule width
    float com;                    // com radius
    float camera;                 // camera object
    float light;                  // light object
    float selectpoint;            // selection point
    float jointlength;            // joint length
    float jointwidth;             // joint width
    float actuatorlength;         // actuator length
    float actuatorwidth;          // actuator width
    float framelength;            // bodyframe axis length
    float framewidth;             // bodyframe axis width
    float constraint;             // constraint width
    float slidercrank;            // slidercrank width
  } scale;

  struct {                        // color of decor elements
    float fog[4];                 // fog
    float haze[4];                // haze
    float force[4];               // external force
    float inertia[4];             // inertia box
    float joint[4];               // joint
    float actuator[4];            // actuator, neutral
    float actuatornegative[4];    // actuator, negative limit
    float actuatorpositive[4];    // actuator, positive limit
    float com[4];                 // center of mass
    float camera[4];              // camera object
    float light[4];               // light object
    float selectpoint[4];         // selection point
    float connect[4];             // auto connect
    float contactpoint[4];        // contact point
    float contactforce[4];        // contact force
    float contactfriction[4];     // contact friction force
    float contacttorque[4];       // contact torque
    float contactgap[4];          // contact point in gap
    float rangefinder[4];         // rangefinder ray
    float constraint[4];          // constraint
    float slidercrank[4];         // slidercrank
    float crankbroken[4];         // used when crank must be stretched/broken
  } rgba;
};
typedef struct mjVisual_ mjVisual;

mjStatistic#

This is the data structure with model statistics precomputed by the compiler or set by the user. It corresponds to the MJCF element statistic. One instance of it is embedded in mjModel.

struct mjStatistic_ {             // model statistics (in qpos0)
  mjtNum meaninertia;             // mean diagonal inertia
  mjtNum meanmass;                // mean body mass
  mjtNum meansize;                // mean body size
  mjtNum extent;                  // spatial extent
  mjtNum center[3];               // center of model
};
typedef struct mjStatistic_ mjStatistic;

mjContact#

This is the data structure holding information about one contact. mjData.contact is a preallocated array of mjContact data structures, populated at runtime with the contacts found by the collision detector. Additional contact information is then filled-in by the simulator.

struct mjContact_ {          // result of collision detection functions
  // contact parameters set by geom-specific collision detector
  mjtNum  dist;              // distance between nearest points; neg: penetration
  mjtNum  pos[3];            // position of contact point: midpoint between geoms
  mjtNum  frame[9];          // normal is in [0-2]

  // contact parameters set by mj_collideGeoms
  mjtNum  includemargin;     // include if dist<includemargin=margin-gap
  mjtNum  friction[5];       // tangent1, 2, spin, roll1, 2
  mjtNum  solref[mjNREF];    // constraint solver reference
  mjtNum  solimp[mjNIMP];    // constraint solver impedance

  // internal storage used by solver
  mjtNum  mu;                // friction of regularized cone, set by mj_makeConstraint
  mjtNum  H[36];             // cone Hessian, set by mj_updateConstraint

  // contact descriptors set by mj_collideGeoms
  int     dim;               // contact space dimensionality: 1, 3, 4 or 6
  int     geom1;             // id of geom 1
  int     geom2;             // id of geom 2

  // flag set by mj_instantianteEquality
  int     exclude;           // 0: include, 1: in gap, 2: fused, 3: no dofs

  // address computed by mj_instantiateContact
  int     efc_address;       // address in efc; -1: not included
};
typedef struct mjContact_ mjContact;

mjVFS#

This is the data structure of the virtual file system. It can only be constructed programmatically, and does not have an analog in MJCF.

struct mjVFS_ {                            // virtual file system for loading from memory
  int   nfile;                             // number of files present
  char  filename[mjMAXVFS][mjMAXVFSNAME];  // file name without path
  int   filesize[mjMAXVFS];                // file size in bytes
  void* filedata[mjMAXVFS];                // buffer with file data
};
typedef struct mjVFS_ mjVFS;

mjLROpt#

Options for configuring the automatic actuator length-range computation.

struct mjLROpt_ {                 // options for mj_setLengthRange()
  // flags
  int mode;                       // which actuators to process (mjtLRMode)
  int useexisting;                // use existing length range if available
  int uselimit;                   // use joint and tendon limits if available

  // algorithm parameters
  mjtNum accel;                   // target acceleration used to compute force
  mjtNum maxforce;                // maximum force; 0: no limit
  mjtNum timeconst;               // time constant for velocity reduction; min 0.01
  mjtNum timestep;                // simulation timestep; 0: use mjOption.timestep
  mjtNum inttotal;                // total simulation time interval
  mjtNum interval;                // evaluation time interval (at the end)
  mjtNum tolrange;                // convergence tolerance (relative to range)
};
typedef struct mjLROpt_ mjLROpt;

Sim statistics#

These structs are all embedded in mjData, and collect simulation-related statistics.

mjWarningStat#

This is the data structure holding information about one warning type. mjData.warning is a preallocated array of mjWarningStat data structures, one for each warning type.

struct mjWarningStat_ {      // warning statistics
  int     lastinfo;          // info from last warning
  int     number;            // how many times was warning raised
};
typedef struct mjWarningStat_ mjWarningStat;

mjTimerStat#

This is the data structure holding information about one timer. mjData.timer is a preallocated array of mjTimerStat data structures, one for each timer type.

struct mjTimerStat_ {        // timer statistics
  mjtNum  duration;          // cumulative duration
  int     number;            // how many times was timer called
};
typedef struct mjTimerStat_ mjTimerStat;

mjSolverStat#

This is the data structure holding information about one solver iteration. mjData.solver is a preallocated array of mjSolverStat data structures, one for each iteration of the solver, up to a maximum of mjNSOLVER. The actual number of solver iterations is given by mjData.solver_iter.

struct mjSolverStat_ {       // per-iteration solver statistics
  mjtNum  improvement;       // cost reduction, scaled by 1/trace(M(qpos0))
  mjtNum  gradient;          // gradient norm (primal only, scaled)
  mjtNum  lineslope;         // slope in linesearch
  int     nactive;           // number of active constraints
  int     nchange;           // number of constraint state changes
  int     neval;             // number of cost evaluations in line search
  int     nupdate;           // number of Cholesky updates in line search
};
typedef struct mjSolverStat_ mjSolverStat;

Visualisation#

The names of these struct types are prefixed with mjv.

mjvPerturb#

This is the data structure holding information about mouse perturbations.

struct mjvPerturb_ {              // object selection and perturbation
  int      select;                // selected body id; non-positive: none
  int      skinselect;            // selected skin id; negative: none
  int      active;                // perturbation bitmask (mjtPertBit)
  int      active2;               // secondary perturbation bitmask (mjtPertBit)
  mjtNum   refpos[3];             // reference position for selected object
  mjtNum   refquat[4];            // reference orientation for selected object
  mjtNum   refselpos[3];          // reference position for selection point
  mjtNum   localpos[3];           // selection point in object coordinates
  mjtNum   localmass;             // spatial inertia at selection point
  mjtNum   scale;                 // relative mouse motion-to-space scaling (set by initPerturb)
};
typedef struct mjvPerturb_ mjvPerturb;

mjvCamera#

This is the data structure describing one abstract camera.

struct mjvCamera_ {               // abstract camera
  // type and ids
  int      type;                  // camera type (mjtCamera)
  int      fixedcamid;            // fixed camera id
  int      trackbodyid;           // body id to track

  // abstract camera pose specification
  mjtNum   lookat[3];             // lookat point
  mjtNum   distance;              // distance to lookat point or tracked body
  mjtNum   azimuth;               // camera azimuth (deg)
  mjtNum   elevation;             // camera elevation (deg)
};
typedef struct mjvCamera_ mjvCamera;

mjvGLCamera#

This is the data structure describing one OpenGL camera.

struct mjvGLCamera_ {             // OpenGL camera
  // camera frame
  float    pos[3];                // position
  float    forward[3];            // forward direction
  float    up[3];                 // up direction

  // camera projection
  float    frustum_center;        // hor. center (left,right set to match aspect)
  float    frustum_bottom;        // bottom
  float    frustum_top;           // top
  float    frustum_near;          // near
  float    frustum_far;           // far
};
typedef struct mjvGLCamera_ mjvGLCamera;

mjvGeom#

This is the data structure describing one abstract visualization geom - which could correspond to a model geom or to a decoration element constructed by the visualizer.

struct mjvGeom_ {                 // abstract geom
  // type info
  int      type;                  // geom type (mjtGeom)
  int      dataid;                // mesh, hfield or plane id; -1: none
  int      objtype;               // mujoco object type; mjOBJ_UNKNOWN for decor
  int      objid;                 // mujoco object id; -1 for decor
  int      category;              // visual category
  int      texid;                 // texture id; -1: no texture
  int      texuniform;            // uniform cube mapping
  int      texcoord;              // mesh geom has texture coordinates
  int      segid;                 // segmentation id; -1: not shown

  // OpenGL info
  float    texrepeat[2];          // texture repetition for 2D mapping
  float    size[3];               // size parameters
  float    pos[3];                // Cartesian position
  float    mat[9];                // Cartesian orientation
  float    rgba[4];               // color and transparency
  float    emission;              // emission coef
  float    specular;              // specular coef
  float    shininess;             // shininess coef
  float    reflectance;           // reflectance coef
  char     label[100];            // text label

  // transparency rendering (set internally)
  float    camdist;               // distance to camera (used by sorter)
  float    modelrbound;           // geom rbound from model, 0 if not model geom
  mjtByte  transparent;           // treat geom as transparent
};
typedef struct mjvGeom_ mjvGeom;

mjvLight#

This is the data structure describing one OpenGL light.

struct mjvLight_ {                // OpenGL light
  float    pos[3];                // position rel. to body frame
  float    dir[3];                // direction rel. to body frame
  float    attenuation[3];        // OpenGL attenuation (quadratic model)
  float    cutoff;                // OpenGL cutoff
  float    exponent;              // OpenGL exponent
  float    ambient[3];            // ambient rgb (alpha=1)
  float    diffuse[3];            // diffuse rgb (alpha=1)
  float    specular[3];           // specular rgb (alpha=1)
  mjtByte  headlight;             // headlight
  mjtByte  directional;           // directional light
  mjtByte  castshadow;            // does light cast shadows
};
typedef struct mjvLight_ mjvLight;

mjvOption#

This structure contains options that enable and disable the visualization of various elements.

struct mjvOption_ {                  // abstract visualization options
  int      label;                    // what objects to label (mjtLabel)
  int      frame;                    // which frame to show (mjtFrame)
  mjtByte  geomgroup[mjNGROUP];      // geom visualization by group
  mjtByte  sitegroup[mjNGROUP];      // site visualization by group
  mjtByte  jointgroup[mjNGROUP];     // joint visualization by group
  mjtByte  tendongroup[mjNGROUP];    // tendon visualization by group
  mjtByte  actuatorgroup[mjNGROUP];  // actuator visualization by group
  mjtByte  skingroup[mjNGROUP];      // skin visualization by group
  mjtByte  flags[mjNVISFLAG];        // visualization flags (indexed by mjtVisFlag)
  int bvh_depth;                     // depth of the bounding volume hierarchy to be visualized
};
typedef struct mjvOption_ mjvOption;

mjvScene#

This structure contains everything needed to render the 3D scene in OpenGL.

struct mjvScene_ {                // abstract scene passed to OpenGL renderer
  // abstract geoms
  int      maxgeom;               // size of allocated geom buffer
  int      ngeom;                 // number of geoms currently in buffer
  mjvGeom* geoms;                 // buffer for geoms (ngeom)
  int*     geomorder;             // buffer for ordering geoms by distance to camera (ngeom)

  // skin data
  int      nskin;                 // number of skins
  int*     skinfacenum;           // number of faces in skin (nskin)
  int*     skinvertadr;           // address of skin vertices (nskin)
  int*     skinvertnum;           // number of vertices in skin (nskin)
  float*   skinvert;              // skin vertex data (nskin)
  float*   skinnormal;            // skin normal data (nskin)

  // OpenGL lights
  int      nlight;                // number of lights currently in buffer
  mjvLight lights[mjMAXLIGHT];    // buffer for lights (nlight)

  // OpenGL cameras
  mjvGLCamera camera[2];          // left and right camera

  // OpenGL model transformation
  mjtByte  enabletransform;       // enable model transformation
  float    translate[3];          // model translation
  float    rotate[4];             // model quaternion rotation
  float    scale;                 // model scaling

  // OpenGL rendering effects
  int      stereo;                // stereoscopic rendering (mjtStereo)
  mjtByte  flags[mjNRNDFLAG];     // rendering flags (indexed by mjtRndFlag)

  // framing
  int      framewidth;            // frame pixel width; 0: disable framing
  float    framergb[3];           // frame color
};
typedef struct mjvScene_ mjvScene;

mjvSceneState#

This structure contains the portions of mjModel and mjData that are required for various mjv_* functions.

struct mjvScene_ {                // abstract scene passed to OpenGL renderer
  // abstract geoms
  int      maxgeom;               // size of allocated geom buffer
  int      ngeom;                 // number of geoms currently in buffer
  mjvGeom* geoms;                 // buffer for geoms (ngeom)
  int*     geomorder;             // buffer for ordering geoms by distance to camera (ngeom)

  // skin data
  int      nskin;                 // number of skins
  int*     skinfacenum;           // number of faces in skin (nskin)
  int*     skinvertadr;           // address of skin vertices (nskin)
  int*     skinvertnum;           // number of vertices in skin (nskin)
  float*   skinvert;              // skin vertex data (nskin)
  float*   skinnormal;            // skin normal data (nskin)

  // OpenGL lights
  int      nlight;                // number of lights currently in buffer
  mjvLight lights[mjMAXLIGHT];    // buffer for lights (nlight)

  // OpenGL cameras
  mjvGLCamera camera[2];          // left and right camera

  // OpenGL model transformation
  mjtByte  enabletransform;       // enable model transformation
  float    translate[3];          // model translation
  float    rotate[4];             // model quaternion rotation
  float    scale;                 // model scaling

  // OpenGL rendering effects
  int      stereo;                // stereoscopic rendering (mjtStereo)
  mjtByte  flags[mjNRNDFLAG];     // rendering flags (indexed by mjtRndFlag)

  // framing
  int      framewidth;            // frame pixel width; 0: disable framing
  float    framergb[3];           // frame color
};
typedef struct mjvScene_ mjvScene;

mjvFigure#

This structure contains everything needed to render a 2D plot in OpenGL. The buffers for line points etc. are preallocated, and the user has to populate them before calling the function mjr_figure with this data structure as an argument.

struct mjvFigure_ {               // abstract 2D figure passed to OpenGL renderer
  // enable flags
  int     flg_legend;             // show legend
  int     flg_ticklabel[2];       // show grid tick labels (x,y)
  int     flg_extend;             // automatically extend axis ranges to fit data
  int     flg_barplot;            // isolated line segments (i.e. GL_LINES)
  int     flg_selection;          // vertical selection line
  int     flg_symmetric;          // symmetric y-axis

  // style settings
  float   linewidth;              // line width
  float   gridwidth;              // grid line width
  int     gridsize[2];            // number of grid points in (x,y)
  float   gridrgb[3];             // grid line rgb
  float   figurergba[4];          // figure color and alpha
  float   panergba[4];            // pane color and alpha
  float   legendrgba[4];          // legend color and alpha
  float   textrgb[3];             // text color
  float   linergb[mjMAXLINE][3];  // line colors
  float   range[2][2];            // axis ranges; (min>=max) automatic
  char    xformat[20];            // x-tick label format for sprintf
  char    yformat[20];            // y-tick label format for sprintf
  char    minwidth[20];           // string used to determine min y-tick width

  // text labels
  char    title[1000];            // figure title; subplots separated with 2+ spaces
  char    xlabel[100];            // x-axis label
  char    linename[mjMAXLINE][100];  // line names for legend

  // dynamic settings
  int     legendoffset;           // number of lines to offset legend
  int     subplot;                // selected subplot (for title rendering)
  int     highlight[2];           // if point is in legend rect, highlight line
  int     highlightid;            // if id>=0 and no point, highlight id
  float   selection;              // selection line x-value

  // line data
  int     linepnt[mjMAXLINE];     // number of points in line; (0) disable
  float   linedata[mjMAXLINE][2*mjMAXLINEPNT]; // line data (x,y)

  // output from renderer
  int     xaxispixel[2];          // range of x-axis in pixels
  int     yaxispixel[2];          // range of y-axis in pixels
  float   xaxisdata[2];           // range of x-axis in data units
  float   yaxisdata[2];           // range of y-axis in data units
};
typedef struct mjvFigure_ mjvFigure;

Rendering#

The names of these struct types are prefixed with mjr.

mjrRect#

This structure specifies a rectangle.

struct mjrRect_ {                 // OpenGL rectangle
  int left;                       // left (usually 0)
  int bottom;                     // bottom (usually 0)
  int width;                      // width (usually buffer width)
  int height;                     // height (usually buffer height)
};
typedef struct mjrRect_ mjrRect;

mjrContext#

This structure contains the custom OpenGL rendering context, with the ids of all OpenGL resources uploaded to the GPU.

struct mjrContext_ {              // custom OpenGL context
  // parameters copied from mjVisual
  float lineWidth;                // line width for wireframe rendering
  float shadowClip;               // clipping radius for directional lights
  float shadowScale;              // fraction of light cutoff for spot lights
  float fogStart;                 // fog start = stat.extent * vis.map.fogstart
  float fogEnd;                   // fog end = stat.extent * vis.map.fogend
  float fogRGBA[4];               // fog rgba
  int shadowSize;                 // size of shadow map texture
  int offWidth;                   // width of offscreen buffer
  int offHeight;                  // height of offscreen buffer
  int offSamples;                 // number of offscreen buffer multisamples

  // parameters specified at creation
  int fontScale;                  // font scale
  int auxWidth[mjNAUX];           // auxiliary buffer width
  int auxHeight[mjNAUX];          // auxiliary buffer height
  int auxSamples[mjNAUX];         // auxiliary buffer multisamples

  // offscreen rendering objects
  unsigned int offFBO;            // offscreen framebuffer object
  unsigned int offFBO_r;          // offscreen framebuffer for resolving multisamples
  unsigned int offColor;          // offscreen color buffer
  unsigned int offColor_r;        // offscreen color buffer for resolving multisamples
  unsigned int offDepthStencil;   // offscreen depth and stencil buffer
  unsigned int offDepthStencil_r; // offscreen depth and stencil buffer for resolving multisamples

  // shadow rendering objects
  unsigned int shadowFBO;         // shadow map framebuffer object
  unsigned int shadowTex;         // shadow map texture

  // auxiliary buffers
  unsigned int auxFBO[mjNAUX];    // auxiliary framebuffer object
  unsigned int auxFBO_r[mjNAUX];  // auxiliary framebuffer object for resolving
  unsigned int auxColor[mjNAUX];  // auxiliary color buffer
  unsigned int auxColor_r[mjNAUX];// auxiliary color buffer for resolving

  // texture objects and info
  int ntexture;                   // number of allocated textures
  int textureType[100];           // type of texture (mjtTexture) (ntexture)
  unsigned int texture[100];      // texture names

  // displaylist starting positions
  unsigned int basePlane;         // all planes from model
  unsigned int baseMesh;          // all meshes from model
  unsigned int baseHField;        // all hfields from model
  unsigned int baseBuiltin;       // all buildin geoms, with quality from model
  unsigned int baseFontNormal;    // normal font
  unsigned int baseFontShadow;    // shadow font
  unsigned int baseFontBig;       // big font

  // displaylist ranges
  int rangePlane;                 // all planes from model
  int rangeMesh;                  // all meshes from model
  int rangeHField;                // all hfields from model
  int rangeBuiltin;               // all builtin geoms, with quality from model
  int rangeFont;                  // all characters in font

  // skin VBOs
  int nskin;                      // number of skins
  unsigned int* skinvertVBO;      // skin vertex position VBOs (nskin)
  unsigned int* skinnormalVBO;    // skin vertex normal VBOs (nskin)
  unsigned int* skintexcoordVBO;  // skin vertex texture coordinate VBOs (nskin)
  unsigned int* skinfaceVBO;      // skin face index VBOs (nskin)

  // character info
  int charWidth[127];             // character widths: normal and shadow
  int charWidthBig[127];          // chacarter widths: big
  int charHeight;                 // character heights: normal and shadow
  int charHeightBig;              // character heights: big

  // capabilities
  int glInitialized;              // is OpenGL initialized
  int windowAvailable;            // is default/window framebuffer available
  int windowSamples;              // number of samples for default/window framebuffer
  int windowStereo;               // is stereo available for default/window framebuffer
  int windowDoublebuffer;         // is default/window framebuffer double buffered

  // framebuffer
  int     currentBuffer;          // currently active framebuffer: mjFB_WINDOW or mjFB_OFFSCREEN

  // pixel output format
  int     readPixelFormat;        // default color pixel format for mjr_readPixels
};
typedef struct mjrContext_ mjrContext;

User Interface#

The names of these struct types are prefixed with mjui, except for the main mjUI struct itself.

mjuiState#

This structure contains the keyboard and mouse state used by the UI framework.

struct mjuiState_ {               // mouse and keyboard state
  // constants set by user
  int nrect;                      // number of rectangles used
  mjrRect rect[mjMAXUIRECT];      // rectangles (index 0: entire window)
  void* userdata;                 // pointer to user data (for callbacks)

  // event type
  int type;                       // (type mjtEvent)

  // mouse buttons
  int left;                       // is left button down
  int right;                      // is right button down
  int middle;                     // is middle button down
  int doubleclick;                // is last press a double click
  int button;                     // which button was pressed (mjtButton)
  double buttontime;              // time of last button press

  // mouse position
  double x;                       // x position
  double y;                       // y position
  double dx;                      // x displacement
  double dy;                      // y displacement
  double sx;                      // x scroll
  double sy;                      // y scroll

  // keyboard
  int control;                    // is control down
  int shift;                      // is shift down
  int alt;                        // is alt down
  int key;                        // which key was pressed
  double keytime;                 // time of last key press

  // rectangle ownership and dragging
  int mouserect;                  // which rectangle contains mouse
  int dragrect;                   // which rectangle is dragged with mouse
  int dragbutton;                 // which button started drag (mjtButton)

  // files dropping (only valid when type == mjEVENT_FILESDROP)
  int dropcount;                  // number of files dropped
  const char** droppaths;         // paths to files dropped
};
typedef struct mjuiState_ mjuiState;

mjuiThemeSpacing#

This structure defines the spacing of UI items in the theme.

struct mjuiThemeSpacing_ {        // UI visualization theme spacing
  int total;                      // total width
  int scroll;                     // scrollbar width
  int label;                      // label width
  int section;                    // section gap
  int itemside;                   // item side gap
  int itemmid;                    // item middle gap
  int itemver;                    // item vertical gap
  int texthor;                    // text horizontal gap
  int textver;                    // text vertical gap
  int linescroll;                 // number of pixels to scroll
  int samples;                    // number of multisamples
};
typedef struct mjuiThemeSpacing_ mjuiThemeSpacing;

mjuiThemeColor#

This structure defines the colors of UI items in the theme.

struct mjuiThemeColor_ {          // UI visualization theme color
  float master[3];                // master background
  float thumb[3];                 // scrollbar thumb
  float secttitle[3];             // section title
  float sectfont[3];              // section font
  float sectsymbol[3];            // section symbol
  float sectpane[3];              // section pane
  float shortcut[3];              // shortcut background
  float fontactive[3];            // font active
  float fontinactive[3];          // font inactive
  float decorinactive[3];         // decor inactive
  float decorinactive2[3];        // inactive slider color 2
  float button[3];                // button
  float check[3];                 // check
  float radio[3];                 // radio
  float select[3];                // select
  float select2[3];               // select pane
  float slider[3];                // slider
  float slider2[3];               // slider color 2
  float edit[3];                  // edit
  float edit2[3];                 // edit invalid
  float cursor[3];                // edit cursor
};
typedef struct mjuiThemeColor_ mjuiThemeColor;

mjuiItem#

This structure defines one UI item.

struct mjuiItemSingle_ {          // check and button-related
  int modifier;                   // 0: none, 1: control, 2: shift; 4: alt
  int shortcut;                   // shortcut key; 0: undefined
};


struct mjuiItemMulti_ {                  // static, radio and select-related
  int nelem;                             // number of elements in group
  char name[mjMAXUIMULTI][mjMAXUINAME];  // element names
};


struct mjuiItemSlider_ {          // slider-related
  double range[2];                // slider range
  double divisions;               // number of range divisions
};


struct mjuiItemEdit_ {            // edit-related
  int nelem;                      // number of elements in list
  double range[mjMAXUIEDIT][2];   // element range (min>=max: ignore)
};


struct mjuiItem_ {                // UI item
  // common properties
  int type;                       // type (mjtItem)
  char name[mjMAXUINAME];         // name
  int state;                      // 0: disable, 1: enable, 2+: use predicate
  void *pdata;                    // data pointer (type-specific)
  int sectionid;                  // id of section containing item
  int itemid;                     // id of item within section

  // type-specific properties
  union {
    struct mjuiItemSingle_ single;  // check and button
    struct mjuiItemMulti_ multi;    // static, radio and select
    struct mjuiItemSlider_ slider;  // slider
    struct mjuiItemEdit_ edit;      // edit
  };

  // internal
  mjrRect rect;                   // rectangle occupied by item
};
typedef struct mjuiItem_ mjuiItem;

mjuiSection#

This structure defines one section of the UI.

struct mjuiSection_ {             // UI section
  // properties
  char name[mjMAXUINAME];         // name
  int state;                      // 0: closed, 1: open
  int modifier;                   // 0: none, 1: control, 2: shift; 4: alt
  int shortcut;                   // shortcut key; 0: undefined
  int nitem;                      // number of items in use
  mjuiItem item[mjMAXUIITEM];     // preallocated array of items

  // internal
  mjrRect rtitle;                 // rectangle occupied by title
  mjrRect rcontent;               // rectangle occupied by content
};
typedef struct mjuiSection_ mjuiSection;

mjuiDef#

This structure defines one entry in the definition table used for simplified UI construction.

struct mjuiDef_ {                 // table passed to mjui_add()
  int type;                       // type (mjtItem); -1: section
  char name[mjMAXUINAME];         // name
  int state;                      // state
  void* pdata;                    // pointer to data
  char other[mjMAXUITEXT];        // string with type-specific properties
};
typedef struct mjuiDef_ mjuiDef;

mjUI#

This structure defines the entire UI.

struct mjUI_ {                    // entire UI
  // constants set by user
  mjuiThemeSpacing spacing;       // UI theme spacing
  mjuiThemeColor color;           // UI theme color
  mjfItemEnable predicate;        // callback to set item state programmatically
  void* userdata;                 // pointer to user data (passed to predicate)
  int rectid;                     // index of this ui rectangle in mjuiState
  int auxid;                      // aux buffer index of this ui
  int radiocol;                   // number of radio columns (0 defaults to 2)

  // UI sizes (framebuffer units)
  int width;                      // width
  int height;                     // current heigth
  int maxheight;                  // height when all sections open
  int scroll;                     // scroll from top of UI

  // mouse focus
  int mousesect;                  // 0: none, -1: scroll, otherwise 1+section
  int mouseitem;                  // item within section
  int mousehelp;                  // help button down: print shortcuts

  // keyboard focus and edit
  int editsect;                   // 0: none, otherwise 1+section
  int edititem;                   // item within section
  int editcursor;                 // cursor position
  int editscroll;                 // horizontal scroll
  char edittext[mjMAXUITEXT];     // current text
  mjuiItem* editchanged;          // pointer to changed edit in last mjui_event

  // sections
  int nsect;                      // number of sections in use
  mjuiSection sect[mjMAXUISECT];  // preallocated array of sections
};
typedef struct mjUI_ mjUI;

Plugins#

The names of these struct types are prefixed with mjp. See Engine plugins for more details.

mjpPlugin#

This structure contains the definition of a single engine plugin. It mostly contains a set of callbacks, which are triggered by the compiler and the engine during various phases of the computation pipeline.

struct mjpPlugin_ {
  const char* name;     // globally unique name identifying the plugin

  int nattribute;                 // number of configuration attributes
  const char* const* attributes;  // name of configuration attributes

  int capabilityflags;  // bitfield of mjtPluginCapabilityBit specifying plugin capabilities
  int needstage;        // an mjtStage enum value specifying the sensor computation stage

  // number of mjtNums needed to store the state of a plugin instance (required)
  int (*nstate)(const mjModel* m, int instance);

  // dimension of the specified sensor's output (required only for sensor plugins)
  int (*nsensordata)(const mjModel* m, int instance, int sensor_id);

  // called when a new mjData is being created (required), returns 0 on success or -1 on failure
  int (*init)(const mjModel* m, mjData* d, int instance);

  // called when an mjData is being freed (optional)
  void (*destroy)(mjData* d, int instance);

  // called when an mjData is being copied (optional)
  void (*copy)(mjData* dest, const mjModel* m, const mjData* src, int instance);

  // called when an mjData is being reset (required)
  void (*reset)(const mjModel* m, double* plugin_state, void* plugin_data, int instance);

  // called when the plugin needs to update its outputs (required)
  void (*compute)(const mjModel* m, mjData* d, int instance, int capability_bit);

  // called when time integration occurs (optional)
  void (*advance)(const mjModel* m, mjData* d, int instance);

  // called by mjv_updateScene (optional)
  void (*visualize)(const mjModel*m, mjData* d, mjvScene* scn, int instance);
};
typedef struct mjpPlugin_ mjpPlugin;

Function types#

MuJoCo callbacks have corresponding function types. They are defined in mjdata.h and in mjui.h. The actual callback functions are documented in the globals page.

Physics Callbacks#

These function types are used by physics callbacks.

mjfGeneric#

typedef void (*mjfGeneric)(const mjModel* m, mjData* d);

This is the function type of the callbacks mjcb_passive and mjcb_control.

mjfConFilt#

typedef int (*mjfConFilt)(const mjModel* m, mjData* d, int geom1, int geom2);

This is the function type of the callback mjcb_contactfilter. The return value is 1: discard, 0: proceed with collision check.

mjfSensor#

typedef void (*mjfSensor)(const mjModel* m, mjData* d, int stage);

This is the function type of the callback mjcb_sensor.

mjfTime#

typedef mjtNum (*mjfTime)(void);

This is the function type of the callback mjcb_time.

mjfAct#

typedef mjtNum (*mjfAct)(const mjModel* m, const mjData* d, int id);

This is the function type of the callbacks mjcb_act_dyn, mjcb_act_gain and mjcb_act_bias.

mjfCollision#

typedef int (*mjfCollision)(const mjModel* m, const mjData* d,
                            mjContact* con, int g1, int g2, mjtNum margin);

This is the function type of the callbacks in the collision table mjCOLLISIONFUNC.

UI Callbacks#

These function types are used by the UI framework.

mjfItemEnable#

typedef int (*mjfItemEnable)(int category, void* data);

This is the function type of the predicate function used by the UI framework to determine if each item is enabled or disabled.

Notes#

This section contains miscellaneous notes regarding data-structure conventions in MuJoCo struct types.

Convex hulls#

The convex hull descriptors are stored in mjModel:

int*      mesh_graphadr;     // graph data address; -1: no graph      (nmesh x 1)
int*      mesh_graph;        // convex graph data                     (nmeshgraph x 1)

If mesh N has a convex hull stored in mjModel (which is optional), then m->mesh_graphadr[N] is the offset of mesh N’s convex hull data in m->mesh_graph. The convex hull data for each mesh is a record with the following format:

int numvert;
int numface;
int vert_edgeadr[numvert];
int vert_globalid[numvert];
int edge_localid[numvert+3*numface];
int face_globalid[3*numface];

Note that the convex hull contains a subset of the vertices of the full mesh. We use the nomenclature globalid to refer to vertex indices in the full mesh, and localid to refer to vertex indices in the convex hull. The meaning of the fields is as follows:

numvert

Number of vertices in the convex hull.

numface

Number of faces in the convex hull.

vert_edgeadr[numvert]

For each vertex in the convex hull, this is the offset of the edge record for that vertex in edge_localid.

vert_globalid[numvert]

For each vertex in the convex hull, this is the corresponding vertex index in the full mesh

edge_localid[numvert+3*numface]

This contains a sequence of edge records, one for each vertex in the convex hull. Each edge record is an array of vertex indices (in localid format) terminated with -1. For example, say the record for vertex 7 is: 3, 4, 5, 9, -1. This means that vertex 7 belongs to 4 edges, and the other ends of these edges are vertices 3, 4, 5, 9. In this way every edge is represented twice, in the edge records of its two vertices. Note that for a closed triangular mesh (such as the convex hulls used here), the number of edges is 3*numface/2. Thus when each edge is represented twice, we have 3*numface edges. And since we are using the separator -1 at the end of each edge record (one separator per vertex), the length of edge_localid is numvert+3*numface.

face_globalid[3*numface]

For each face of the convex hull, this contains the indices of the three vertices in the full mesh