LibMuJoCo API

Auto-generated bindings for the MuJoCo C library.

MuJoCo.LibMuJoCo.mjContact_Type
mjContact

Fields

  • dist: distance between nearest points; neg: penetration
  • pos: position of contact point: midpoint between geoms
  • frame: normal is in [0-2]
  • includemargin: include if dist<includemargin=margin-gap
  • friction: tangent1, 2, spin, roll1, 2
  • solref: constraint solver reference, normal direction
  • solreffriction: constraint solver reference, friction directions
  • solimp: constraint solver impedance
  • mu: friction of regularized cone, set by mj_makeConstraint
  • H: cone Hessian, set by mj_updateConstraint
  • dim: contact space dimensionality: 1, 3, 4 or 6
  • geom1: id of geom 1
  • geom2: id of geom 2
  • exclude: 0: include, 1: in gap, 2: fused, 3: no dofs
  • efc_address: address in efc; -1: not included
MuJoCo.LibMuJoCo.mjData_Type
mjData

Fields

  • nstack: number of mjtNums that can fit in the arena+stack space
  • nbuffer: size of main buffer in bytes
  • nplugin: number of plugin instances
  • pstack: first available mjtNum address in stack
  • parena: first available byte in arena
  • maxuse_stack: maximum stack allocation
  • maxuse_arena: maximum arena allocation
  • maxuse_con: maximum number of contacts
  • maxuse_efc: maximum number of scalar constraints
  • warning: warning statistics
  • timer: timer statistics
  • solver: solver statistics per iteration
  • solver_iter: number of solver iterations
  • solver_nnz: number of non-zeros in Hessian or efc_AR
  • solver_fwdinv: forward-inverse comparison: qfrc, efc
  • nbodypair_broad: number of body pairs in collision according to the broad-phase
  • nbodypair_narrow: number of body pairs actually in collision in the narrow-phase
  • ngeompair_mid: number of geom pairs in collision according to the mid-phase
  • ngeompair_narrow: number of geom pairs actually in collision in the narrow-phase
  • ne: number of equality constraints
  • nf: number of friction constraints
  • nefc: number of constraints
  • nnzJ: number of non-zeros in constraint Jacobian
  • ncon: number of detected contacts
  • time: simulation time
  • energy: potential, kinetic energy
  • buffer: main buffer; all pointers point in it (nbuffer bytes)
  • arena: arena+stack buffer (nstack*sizeof(mjtNum) bytes)
  • qpos: position (nq x 1)
  • qvel: velocity (nv x 1)
  • act: actuator activation (na x 1)
  • qacc_warmstart: acceleration used for warmstart (nv x 1)
  • plugin_state: plugin state (npluginstate x 1)
  • ctrl: control (nu x 1)
  • qfrc_applied: applied generalized force (nv x 1)
  • xfrc_applied: applied Cartesian force/torque (nbody x 6)
  • mocap_pos: positions of mocap bodies (nmocap x 3)
  • mocap_quat: orientations of mocap bodies (nmocap x 4)
  • qacc: acceleration (nv x 1)
  • act_dot: time-derivative of actuator activation (na x 1)
  • userdata: user data, not touched by engine (nuserdata x 1)
  • sensordata: sensor data array (nsensordata x 1)
  • plugin: copy of m->plugin, required for deletion (nplugin x 1)
  • plugin_data: pointer to plugin-managed data structure (nplugin x 1)
  • xpos: Cartesian position of body frame (nbody x 3)
  • xquat: Cartesian orientation of body frame (nbody x 4)
  • xmat: Cartesian orientation of body frame (nbody x 9)
  • xipos: Cartesian position of body com (nbody x 3)
  • ximat: Cartesian orientation of body inertia (nbody x 9)
  • xanchor: Cartesian position of joint anchor (njnt x 3)
  • xaxis: Cartesian joint axis (njnt x 3)
  • geom_xpos: Cartesian geom position (ngeom x 3)
  • geom_xmat: Cartesian geom orientation (ngeom x 9)
  • site_xpos: Cartesian site position (nsite x 3)
  • site_xmat: Cartesian site orientation (nsite x 9)
  • cam_xpos: Cartesian camera position (ncam x 3)
  • cam_xmat: Cartesian camera orientation (ncam x 9)
  • light_xpos: Cartesian light position (nlight x 3)
  • light_xdir: Cartesian light direction (nlight x 3)
  • subtree_com: center of mass of each subtree (nbody x 3)
  • cdof: com-based motion axis of each dof (nv x 6)
  • cinert: com-based body inertia and mass (nbody x 10)
  • ten_wrapadr: start address of tendon's path (ntendon x 1)
  • ten_wrapnum: number of wrap points in path (ntendon x 1)
  • ten_J_rownnz: number of non-zeros in Jacobian row (ntendon x 1)
  • ten_J_rowadr: row start address in colind array (ntendon x 1)
  • ten_J_colind: column indices in sparse Jacobian (ntendon x nv)
  • ten_length: tendon lengths (ntendon x 1)
  • ten_J: tendon Jacobian (ntendon x nv)
  • wrap_obj: geom id; -1: site; -2: pulley (nwrap*2 x 1)
  • wrap_xpos: Cartesian 3D points in all path (nwrap*2 x 3)
  • actuator_length: actuator lengths (nu x 1)
  • actuator_moment: actuator moments (nu x nv)
  • crb: com-based composite inertia and mass (nbody x 10)
  • qM: total inertia (sparse) (nM x 1)
  • qLD: L'DL factorization of M (sparse) (nM x 1)
  • qLDiagInv: 1/diag(D) (nv x 1)
  • qLDiagSqrtInv: 1/sqrt(diag(D)) (nv x 1)
  • bvh_active: volume has been added to collisions (nbvh x 1)
  • ten_velocity: tendon velocities (ntendon x 1)
  • actuator_velocity: actuator velocities (nu x 1)
  • cvel: com-based velocity 3D rot; 3D tran
  • cdof_dot: time-derivative of cdof (nv x 6)
  • qfrc_bias: C(qpos,qvel) (nv x 1)
  • qfrc_passive: passive force (nv x 1)
  • efc_vel: velocity in constraint space: J*qvel (nefc x 1)
  • efc_aref: reference pseudo-acceleration (nefc x 1)
  • subtree_linvel: linear velocity of subtree com (nbody x 3)
  • subtree_angmom: angular momentum about subtree com (nbody x 3)
  • qH: L'DL factorization of modified M (nM x 1)
  • qHDiagInv: 1/diag(D) of modified M (nv x 1)
  • D_rownnz: non-zeros in each row (nv x 1)
  • D_rowadr: address of each row in D_colind (nv x 1)
  • D_colind: column indices of non-zeros (nD x 1)
  • B_rownnz: non-zeros in each row (nbody x 1)
  • B_rowadr: address of each row in B_colind (nbody x 1)
  • B_colind: column indices of non-zeros (nB x 1)
  • qDeriv: d (passive + actuator - bias) / d qvel (nD x 1)
  • qLU: sparse LU of (qM - dt*qDeriv) (nD x 1)
  • actuator_force: actuator force in actuation space (nu x 1)
  • qfrc_actuator: actuator force (nv x 1)
  • qfrc_smooth: net unconstrained force (nv x 1)
  • qacc_smooth: unconstrained acceleration (nv x 1)
  • qfrc_constraint: constraint force (nv x 1)
  • qfrc_inverse: net external force; should equal: (nv x 1)qfrcapplied + J'*xfrcapplied + qfrc_actuator
  • cacc: com-based acceleration (nbody x 6)
  • cfrc_int: com-based interaction force with parent (nbody x 6)
  • cfrc_ext: com-based external force on body (nbody x 6)
  • contact: list of all detected contacts (ncon x 1)
  • efc_type: constraint type (mjtConstraint) (nefc x 1)
  • efc_id: id of object of specified type (nefc x 1)
  • efc_J_rownnz: number of non-zeros in constraint Jacobian row (nefc x 1)
  • efc_J_rowadr: row start address in colind array (nefc x 1)
  • efc_J_rowsuper: number of subsequent rows in supernode (nefc x 1)
  • efc_J_colind: column indices in constraint Jacobian (nnzJ x 1)
  • efc_JT_rownnz: number of non-zeros in constraint Jacobian row T (nv x 1)
  • efc_JT_rowadr: row start address in colind array T (nv x 1)
  • efc_JT_rowsuper: number of subsequent rows in supernode T (nv x 1)
  • efc_JT_colind: column indices in constraint Jacobian T (nnzJ x 1)
  • efc_J: constraint Jacobian (nnzJ x 1)
  • efc_JT: constraint Jacobian transposed (nnzJ x 1)
  • efc_pos: constraint position (equality, contact) (nefc x 1)
  • efc_margin: inclusion margin (contact) (nefc x 1)
  • efc_frictionloss: frictionloss (friction) (nefc x 1)
  • efc_diagApprox: approximation to diagonal of A (nefc x 1)
  • efc_KBIP: stiffness, damping, impedance, imp' (nefc x 4)
  • efc_D: constraint mass (nefc x 1)
  • efc_R: inverse constraint mass (nefc x 1)
  • efc_b: linear cost term: J*qacc_smooth - aref (nefc x 1)
  • efc_force: constraint force in constraint space (nefc x 1)
  • efc_state: constraint state (mjtConstraintState) (nefc x 1)
  • efc_AR_rownnz: number of non-zeros in AR (nefc x 1)
  • efc_AR_rowadr: row start address in colind array (nefc x 1)
  • efc_AR_colind: column indices in sparse AR (nefc x nefc)
  • efc_AR: Jinv(M)J' + R (nefc x nefc)
MuJoCo.LibMuJoCo.mjLROpt_Type
mjLROpt

Fields

  • mode: which actuators to process (mjtLRMode)
  • useexisting: use existing length range if available
  • uselimit: use joint and tendon limits if available
  • accel: target acceleration used to compute force
  • maxforce: maximum force; 0: no limit
  • timeconst: time constant for velocity reduction; min 0.01
  • timestep: simulation timestep; 0: use mjOption.timestep
  • inttotal: total simulation time interval
  • interval: evaluation time interval (at the end)
  • tolrange: convergence tolerance (relative to range)
MuJoCo.LibMuJoCo.mjModel_Type
mjModel

Fields

  • nq: number of generalized coordinates = dim(qpos)
  • nv: number of degrees of freedom = dim(qvel)
  • nu: number of actuators/controls = dim(ctrl)
  • na: number of activation states = dim(act)
  • nbody: number of bodies
  • nbvh: number of total bounding volumes in all bodies
  • njnt: number of joints
  • ngeom: number of geoms
  • nsite: number of sites
  • ncam: number of cameras
  • nlight: number of lights
  • nmesh: number of meshes
  • nmeshvert: number of vertices in all meshes
  • nmeshnormal: number of normals in all meshes
  • nmeshtexcoord: number of texcoords in all meshes
  • nmeshface: number of triangular faces in all meshes
  • nmeshgraph: number of ints in mesh auxiliary data
  • nskin: number of skins
  • nskinvert: number of vertices in all skins
  • nskintexvert: number of vertiex with texcoords in all skins
  • nskinface: number of triangular faces in all skins
  • nskinbone: number of bones in all skins
  • nskinbonevert: number of vertices in all skin bones
  • nhfield: number of heightfields
  • nhfielddata: number of data points in all heightfields
  • ntex: number of textures
  • ntexdata: number of bytes in texture rgb data
  • nmat: number of materials
  • npair: number of predefined geom pairs
  • nexclude: number of excluded geom pairs
  • neq: number of equality constraints
  • ntendon: number of tendons
  • nwrap: number of wrap objects in all tendon paths
  • nsensor: number of sensors
  • nnumeric: number of numeric custom fields
  • nnumericdata: number of mjtNums in all numeric fields
  • ntext: number of text custom fields
  • ntextdata: number of mjtBytes in all text fields
  • ntuple: number of tuple custom fields
  • ntupledata: number of objects in all tuple fields
  • nkey: number of keyframes
  • nmocap: number of mocap bodies
  • nplugin: number of plugin instances
  • npluginattr: number of chars in all plugin config attributes
  • nuser_body: number of mjtNums in body_user
  • nuser_jnt: number of mjtNums in jnt_user
  • nuser_geom: number of mjtNums in geom_user
  • nuser_site: number of mjtNums in site_user
  • nuser_cam: number of mjtNums in cam_user
  • nuser_tendon: number of mjtNums in tendon_user
  • nuser_actuator: number of mjtNums in actuator_user
  • nuser_sensor: number of mjtNums in sensor_user
  • nnames: number of chars in all names
  • nnames_map: number of slots in the names hash map
  • nM: number of non-zeros in sparse inertia matrix
  • nD: number of non-zeros in sparse dof-dof matrix
  • nB: number of non-zeros in sparse body-dof matrix
  • nemax: number of potential equality-constraint rows
  • njmax: number of available rows in constraint Jacobian
  • nconmax: number of potential contacts in contact list
  • nstack: number of fields in mjData stack
  • nuserdata: number of extra fields in mjData
  • nsensordata: number of fields in sensor data vector
  • npluginstate: number of fields in the plugin state vector
  • nbuffer: number of bytes in buffer
  • opt: physics options
  • vis: visualization options
  • stat: model statistics
  • buffer: main buffer; all pointers point in it (nbuffer)
  • qpos0: qpos values at default pose (nq x 1)
  • qpos_spring: reference pose for springs (nq x 1)
  • body_parentid: id of body's parent (nbody x 1)
  • body_rootid: id of root above body (nbody x 1)
  • body_weldid: id of body that this body is welded to (nbody x 1)
  • body_mocapid: id of mocap data; -1: none (nbody x 1)
  • body_jntnum: number of joints for this body (nbody x 1)
  • body_jntadr: start addr of joints; -1: no joints (nbody x 1)
  • body_dofnum: number of motion degrees of freedom (nbody x 1)
  • body_dofadr: start addr of dofs; -1: no dofs (nbody x 1)
  • body_geomnum: number of geoms (nbody x 1)
  • body_geomadr: start addr of geoms; -1: no geoms (nbody x 1)
  • body_simple: body is simple (has diagonal M) (nbody x 1)
  • body_sameframe: inertial frame is same as body frame (nbody x 1)
  • body_pos: position offset rel. to parent body (nbody x 3)
  • body_quat: orientation offset rel. to parent body (nbody x 4)
  • body_ipos: local position of center of mass (nbody x 3)
  • body_iquat: local orientation of inertia ellipsoid (nbody x 4)
  • body_mass: mass (nbody x 1)
  • body_subtreemass: mass of subtree starting at this body (nbody x 1)
  • body_inertia: diagonal inertia in ipos/iquat frame (nbody x 3)
  • body_invweight0: mean inv inert in qpos0 (trn, rot) (nbody x 2)
  • body_gravcomp: antigravity force, units of body weight (nbody x 1)
  • body_user: user data (nbody x nuser_body)
  • body_plugin: plugin instance id; -1: not in use (nbody x 1)
  • body_bvhadr: address of bvh root (nbody x 1)
  • body_bvhnum: number of bounding volumes (nbody x 1)
  • bvh_depth: depth in the bounding volume hierarchy (nbvh x 1)
  • bvh_child: left and right children in tree (nbvh x 2)
  • bvh_geomid: geom id of the node; -1: non-leaf (nbvh x 1)
  • bvh_aabb: bounding box of node (center, size) (nbvh x 6)
  • jnt_type: type of joint (mjtJoint) (njnt x 1)
  • jnt_qposadr: start addr in 'qpos' for joint's data (njnt x 1)
  • jnt_dofadr: start addr in 'qvel' for joint's data (njnt x 1)
  • jnt_bodyid: id of joint's body (njnt x 1)
  • jnt_group: group for visibility (njnt x 1)
  • jnt_limited: does joint have limits (njnt x 1)
  • jnt_actfrclimited: does joint have actuator force limits (njnt x 1)
  • jnt_solref: constraint solver reference: limit (njnt x mjNREF)
  • jnt_solimp: constraint solver impedance: limit (njnt x mjNIMP)
  • jnt_pos: local anchor position (njnt x 3)
  • jnt_axis: local joint axis (njnt x 3)
  • jnt_stiffness: stiffness coefficient (njnt x 1)
  • jnt_range: joint limits (njnt x 2)
  • jnt_actfrcrange: range of total actuator force (njnt x 2)
  • jnt_margin: min distance for limit detection (njnt x 1)
  • jnt_user: user data (njnt x nuser_jnt)
  • dof_bodyid: id of dof's body (nv x 1)
  • dof_jntid: id of dof's joint (nv x 1)
  • dof_parentid: id of dof's parent; -1: none (nv x 1)
  • dof_Madr: dof address in M-diagonal (nv x 1)
  • dof_simplenum: number of consecutive simple dofs (nv x 1)
  • dof_solref: constraint solver reference:frictionloss (nv x mjNREF)
  • dof_solimp: constraint solver impedance:frictionloss (nv x mjNIMP)
  • dof_frictionloss: dof friction loss (nv x 1)
  • dof_armature: dof armature inertia/mass (nv x 1)
  • dof_damping: damping coefficient (nv x 1)
  • dof_invweight0: diag. inverse inertia in qpos0 (nv x 1)
  • dof_M0: diag. inertia in qpos0 (nv x 1)
  • geom_type: geometric type (mjtGeom) (ngeom x 1)
  • geom_contype: geom contact type (ngeom x 1)
  • geom_conaffinity: geom contact affinity (ngeom x 1)
  • geom_condim: contact dimensionality (1, 3, 4, 6) (ngeom x 1)
  • geom_bodyid: id of geom's body (ngeom x 1)
  • geom_dataid: id of geom's mesh/hfield; -1: none (ngeom x 1)
  • geom_matid: material id for rendering; -1: none (ngeom x 1)
  • geom_group: group for visibility (ngeom x 1)
  • geom_priority: geom contact priority (ngeom x 1)
  • geom_sameframe: same as body frame (1) or iframe (2) (ngeom x 1)
  • geom_solmix: mixing coef for solref/imp in geom pair (ngeom x 1)
  • geom_solref: constraint solver reference: contact (ngeom x mjNREF)
  • geom_solimp: constraint solver impedance: contact (ngeom x mjNIMP)
  • geom_size: geom-specific size parameters (ngeom x 3)
  • geom_aabb: bounding box, (center, size) (ngeom x 6)
  • geom_rbound: radius of bounding sphere (ngeom x 1)
  • geom_pos: local position offset rel. to body (ngeom x 3)
  • geom_quat: local orientation offset rel. to body (ngeom x 4)
  • geom_friction: friction for (slide, spin, roll) (ngeom x 3)
  • geom_margin: detect contact if dist<margin(ngeom x 1)
  • geom_gap: include in solver if dist<margin-gap (ngeom x 1)
  • geom_fluid: fluid interaction parameters (ngeom x mjNFLUID)
  • geom_user: user data (ngeom x nuser_geom)
  • geom_rgba: rgba when material is omitted (ngeom x 4)
  • site_type: geom type for rendering (mjtGeom) (nsite x 1)
  • site_bodyid: id of site's body (nsite x 1)
  • site_matid: material id for rendering; -1: none (nsite x 1)
  • site_group: group for visibility (nsite x 1)
  • site_sameframe: same as body frame (1) or iframe (2) (nsite x 1)
  • site_size: geom size for rendering (nsite x 3)
  • site_pos: local position offset rel. to body (nsite x 3)
  • site_quat: local orientation offset rel. to body (nsite x 4)
  • site_user: user data (nsite x nuser_site)
  • site_rgba: rgba when material is omitted (nsite x 4)
  • cam_mode: camera tracking mode (mjtCamLight) (ncam x 1)
  • cam_bodyid: id of camera's body (ncam x 1)
  • cam_targetbodyid: id of targeted body; -1: none (ncam x 1)
  • cam_pos: position rel. to body frame (ncam x 3)
  • cam_quat: orientation rel. to body frame (ncam x 4)
  • cam_poscom0: global position rel. to sub-com in qpos0 (ncam x 3)
  • cam_pos0: global position rel. to body in qpos0 (ncam x 3)
  • cam_mat0: global orientation in qpos0 (ncam x 9)
  • cam_fovy: y-field of view (deg) (ncam x 1)
  • cam_ipd: inter-pupilary distance (ncam x 1)
  • cam_user: user data (ncam x nuser_cam)
  • light_mode: light tracking mode (mjtCamLight) (nlight x 1)
  • light_bodyid: id of light's body (nlight x 1)
  • light_targetbodyid: id of targeted body; -1: none (nlight x 1)
  • light_directional: directional light (nlight x 1)
  • light_castshadow: does light cast shadows (nlight x 1)
  • light_active: is light on (nlight x 1)
  • light_pos: position rel. to body frame (nlight x 3)
  • light_dir: direction rel. to body frame (nlight x 3)
  • light_poscom0: global position rel. to sub-com in qpos0 (nlight x 3)
  • light_pos0: global position rel. to body in qpos0 (nlight x 3)
  • light_dir0: global direction in qpos0 (nlight x 3)
  • light_attenuation: OpenGL attenuation (quadratic model) (nlight x 3)
  • light_cutoff: OpenGL cutoff (nlight x 1)
  • light_exponent: OpenGL exponent (nlight x 1)
  • light_ambient: ambient rgb (alpha=1) (nlight x 3)
  • light_diffuse: diffuse rgb (alpha=1) (nlight x 3)
  • light_specular: specular rgb (alpha=1) (nlight x 3)
  • mesh_vertadr: first vertex address (nmesh x 1)
  • mesh_vertnum: number of vertices (nmesh x 1)
  • mesh_faceadr: first face address (nmesh x 1)
  • mesh_facenum: number of faces (nmesh x 1)
  • mesh_bvhadr: address of bvh root (nmesh x 1)
  • mesh_bvhnum: number of bvh (nmesh x 1)
  • mesh_normaladr: first normal address (nmesh x 1)
  • mesh_normalnum: number of normals (nmesh x 1)
  • mesh_texcoordadr: texcoord data address; -1: no texcoord (nmesh x 1)
  • mesh_texcoordnum: number of texcoord (nmesh x 1)
  • mesh_graphadr: graph data address; -1: no graph (nmesh x 1)
  • mesh_vert: vertex positions for all meshes (nmeshvert x 3)
  • mesh_normal: normals for all meshes (nmeshnormal x 3)
  • mesh_texcoord: vertex texcoords for all meshes (nmeshtexcoord x 2)
  • mesh_face: vertex face data (nmeshface x 3)
  • mesh_facenormal: normal face data (nmeshface x 3)
  • mesh_facetexcoord: texture face data (nmeshface x 3)
  • mesh_graph: convex graph data (nmeshgraph x 1)
  • skin_matid: skin material id; -1: none (nskin x 1)
  • skin_group: group for visibility (nskin x 1)
  • skin_rgba: skin rgba (nskin x 4)
  • skin_inflate: inflate skin in normal direction (nskin x 1)
  • skin_vertadr: first vertex address (nskin x 1)
  • skin_vertnum: number of vertices (nskin x 1)
  • skin_texcoordadr: texcoord data address; -1: no texcoord (nskin x 1)
  • skin_faceadr: first face address (nskin x 1)
  • skin_facenum: number of faces (nskin x 1)
  • skin_boneadr: first bone in skin (nskin x 1)
  • skin_bonenum: number of bones in skin (nskin x 1)
  • skin_vert: vertex positions for all skin meshes (nskinvert x 3)
  • skin_texcoord: vertex texcoords for all skin meshes (nskintexvert x 2)
  • skin_face: triangle faces for all skin meshes (nskinface x 3)
  • skin_bonevertadr: first vertex in each bone (nskinbone x 1)
  • skin_bonevertnum: number of vertices in each bone (nskinbone x 1)
  • skin_bonebindpos: bind pos of each bone (nskinbone x 3)
  • skin_bonebindquat: bind quat of each bone (nskinbone x 4)
  • skin_bonebodyid: body id of each bone (nskinbone x 1)
  • skin_bonevertid: mesh ids of vertices in each bone (nskinbonevert x 1)
  • skin_bonevertweight: weights of vertices in each bone (nskinbonevert x 1)
  • hfield_size: (x, y, ztop, zbottom) (nhfield x 4)
  • hfield_nrow: number of rows in grid (nhfield x 1)
  • hfield_ncol: number of columns in grid (nhfield x 1)
  • hfield_adr: address in hfield_data (nhfield x 1)
  • hfield_data: elevation data (nhfielddata x 1)
  • tex_type: texture type (mjtTexture) (ntex x 1)
  • tex_height: number of rows in texture image (ntex x 1)
  • tex_width: number of columns in texture image (ntex x 1)
  • tex_adr: address in rgb (ntex x 1)
  • tex_rgb: rgb (alpha = 1) (ntexdata x 1)
  • mat_texid: texture id; -1: none (nmat x 1)
  • mat_texuniform: make texture cube uniform (nmat x 1)
  • mat_texrepeat: texture repetition for 2d mapping (nmat x 2)
  • mat_emission: emission (x rgb) (nmat x 1)
  • mat_specular: specular (x white) (nmat x 1)
  • mat_shininess: shininess coef (nmat x 1)
  • mat_reflectance: reflectance (0: disable) (nmat x 1)
  • mat_rgba: rgba (nmat x 4)
  • pair_dim: contact dimensionality (npair x 1)
  • pair_geom1: id of geom1 (npair x 1)
  • pair_geom2: id of geom2 (npair x 1)
  • pair_signature: (body1+1)<<16 + body2+1 (npair x 1)
  • pair_solref: solver reference: contact normal (npair x mjNREF)
  • pair_solreffriction: solver reference: contact friction (npair x mjNREF)
  • pair_solimp: solver impedance: contact (npair x mjNIMP)
  • pair_margin: detect contact if dist<margin(npair x 1)
  • pair_gap: include in solver if dist<margin-gap (npair x 1)
  • pair_friction: tangent1, 2, spin, roll1, 2 (npair x 5)
  • exclude_signature: (body1+1)<<16 + body2+1 (nexclude x 1)
  • eq_type: constraint type (mjtEq) (neq x 1)
  • eq_obj1id: id of object 1 (neq x 1)
  • eq_obj2id: id of object 2 (neq x 1)
  • eq_active: enable/disable constraint (neq x 1)
  • eq_solref: constraint solver reference (neq x mjNREF)
  • eq_solimp: constraint solver impedance (neq x mjNIMP)
  • eq_data: numeric data for constraint (neq x mjNEQDATA)
  • tendon_adr: address of first object in tendon's path (ntendon x 1)
  • tendon_num: number of objects in tendon's path (ntendon x 1)
  • tendon_matid: material id for rendering (ntendon x 1)
  • tendon_group: group for visibility (ntendon x 1)
  • tendon_limited: does tendon have length limits (ntendon x 1)
  • tendon_width: width for rendering (ntendon x 1)
  • tendon_solref_lim: constraint solver reference: limit (ntendon x mjNREF)
  • tendon_solimp_lim: constraint solver impedance: limit (ntendon x mjNIMP)
  • tendon_solref_fri: constraint solver reference: friction (ntendon x mjNREF)
  • tendon_solimp_fri: constraint solver impedance: friction (ntendon x mjNIMP)
  • tendon_range: tendon length limits (ntendon x 2)
  • tendon_margin: min distance for limit detection (ntendon x 1)
  • tendon_stiffness: stiffness coefficient (ntendon x 1)
  • tendon_damping: damping coefficient (ntendon x 1)
  • tendon_frictionloss: loss due to friction (ntendon x 1)
  • tendon_lengthspring: spring resting length range (ntendon x 2)
  • tendon_length0: tendon length in qpos0 (ntendon x 1)
  • tendon_invweight0: inv. weight in qpos0 (ntendon x 1)
  • tendon_user: user data (ntendon x nuser_tendon)
  • tendon_rgba: rgba when material is omitted (ntendon x 4)
  • wrap_type: wrap object type (mjtWrap) (nwrap x 1)
  • wrap_objid: object id: geom, site, joint (nwrap x 1)
  • wrap_prm: divisor, joint coef, or site id (nwrap x 1)
  • actuator_trntype: transmission type (mjtTrn) (nu x 1)
  • actuator_dyntype: dynamics type (mjtDyn) (nu x 1)
  • actuator_gaintype: gain type (mjtGain) (nu x 1)
  • actuator_biastype: bias type (mjtBias) (nu x 1)
  • actuator_trnid: transmission id: joint, tendon, site (nu x 2)
  • actuator_actadr: first activation address; -1: stateless (nu x 1)
  • actuator_actnum: number of activation variables (nu x 1)
  • actuator_group: group for visibility (nu x 1)
  • actuator_ctrllimited: is control limited (nu x 1)
  • actuator_forcelimited: is force limited (nu x 1)
  • actuator_actlimited: is activation limited (nu x 1)
  • actuator_dynprm: dynamics parameters (nu x mjNDYN)
  • actuator_gainprm: gain parameters (nu x mjNGAIN)
  • actuator_biasprm: bias parameters (nu x mjNBIAS)
  • actuator_ctrlrange: range of controls (nu x 2)
  • actuator_forcerange: range of forces (nu x 2)
  • actuator_actrange: range of activations (nu x 2)
  • actuator_gear: scale length and transmitted force (nu x 6)
  • actuator_cranklength: crank length for slider-crank (nu x 1)
  • actuator_acc0: acceleration from unit force in qpos0 (nu x 1)
  • actuator_length0: actuator length in qpos0 (nu x 1)
  • actuator_lengthrange: feasible actuator length range (nu x 2)
  • actuator_user: user data (nu x nuser_actuator)
  • actuator_plugin: plugin instance id; -1: not a plugin (nu x 1)
  • sensor_type: sensor type (mjtSensor) (nsensor x 1)
  • sensor_datatype: numeric data type (mjtDataType) (nsensor x 1)
  • sensor_needstage: required compute stage (mjtStage) (nsensor x 1)
  • sensor_objtype: type of sensorized object (mjtObj) (nsensor x 1)
  • sensor_objid: id of sensorized object (nsensor x 1)
  • sensor_reftype: type of reference frame (mjtObj) (nsensor x 1)
  • sensor_refid: id of reference frame; -1: global frame (nsensor x 1)
  • sensor_dim: number of scalar outputs (nsensor x 1)
  • sensor_adr: address in sensor array (nsensor x 1)
  • sensor_cutoff: cutoff for real and positive; 0: ignore (nsensor x 1)
  • sensor_noise: noise standard deviation (nsensor x 1)
  • sensor_user: user data (nsensor x nuser_sensor)
  • sensor_plugin: plugin instance id; -1: not a plugin (nsensor x 1)
  • plugin: globally registered plugin slot number (nplugin x 1)
  • plugin_stateadr: address in the plugin state array (nplugin x 1)
  • plugin_statenum: number of states in the plugin instance (nplugin x 1)
  • plugin_attr: config attributes of plugin instances (npluginattr x 1)
  • plugin_attradr: address to each instance's config attrib (nplugin x 1)
  • numeric_adr: address of field in numeric_data (nnumeric x 1)
  • numeric_size: size of numeric field (nnumeric x 1)
  • numeric_data: array of all numeric fields (nnumericdata x 1)
  • text_adr: address of text in text_data (ntext x 1)
  • text_size: size of text field (strlen+1) (ntext x 1)
  • text_data: array of all text fields (0-terminated) (ntextdata x 1)
  • tuple_adr: address of text in text_data (ntuple x 1)
  • tuple_size: number of objects in tuple (ntuple x 1)
  • tuple_objtype: array of object types in all tuples (ntupledata x 1)
  • tuple_objid: array of object ids in all tuples (ntupledata x 1)
  • tuple_objprm: array of object params in all tuples (ntupledata x 1)
  • key_time: key time (nkey x 1)
  • key_qpos: key position (nkey x nq)
  • key_qvel: key velocity (nkey x nv)
  • key_act: key activation (nkey x na)
  • key_mpos: key mocap position (nkey x 3*nmocap)
  • key_mquat: key mocap quaternion (nkey x 4*nmocap)
  • key_ctrl: key control (nkey x nu)
  • name_bodyadr: body name pointers (nbody x 1)
  • name_jntadr: joint name pointers (njnt x 1)
  • name_geomadr: geom name pointers (ngeom x 1)
  • name_siteadr: site name pointers (nsite x 1)
  • name_camadr: camera name pointers (ncam x 1)
  • name_lightadr: light name pointers (nlight x 1)
  • name_meshadr: mesh name pointers (nmesh x 1)
  • name_skinadr: skin name pointers (nskin x 1)
  • name_hfieldadr: hfield name pointers (nhfield x 1)
  • name_texadr: texture name pointers (ntex x 1)
  • name_matadr: material name pointers (nmat x 1)
  • name_pairadr: geom pair name pointers (npair x 1)
  • name_excludeadr: exclude name pointers (nexclude x 1)
  • name_eqadr: equality constraint name pointers (neq x 1)
  • name_tendonadr: tendon name pointers (ntendon x 1)
  • name_actuatoradr: actuator name pointers (nu x 1)
  • name_sensoradr: sensor name pointers (nsensor x 1)
  • name_numericadr: numeric name pointers (nnumeric x 1)
  • name_textadr: text name pointers (ntext x 1)
  • name_tupleadr: tuple name pointers (ntuple x 1)
  • name_keyadr: keyframe name pointers (nkey x 1)
  • name_pluginadr: plugin instance name pointers (nplugin x 1)
  • names: names of all objects, 0-terminated (nnames x 1)
  • names_map: internal hash map of names (nnames_map x 1)
MuJoCo.LibMuJoCo.mjOption_Type
mjOption

Fields

  • timestep: timestep
  • apirate: update rate for remote API (Hz)
  • impratio: ratio of friction-to-normal contact impedance
  • tolerance: main solver tolerance
  • noslip_tolerance: noslip solver tolerance
  • mpr_tolerance: MPR solver tolerance
  • gravity: gravitational acceleration
  • wind: wind (for lift, drag and viscosity)
  • magnetic: global magnetic flux
  • density: density of medium
  • viscosity: viscosity of medium
  • o_margin: margin
  • o_solref: solref
  • o_solimp: solimp
  • integrator: integration mode (mjtIntegrator)
  • collision: collision mode (mjtCollision)
  • cone: type of friction cone (mjtCone)
  • jacobian: type of Jacobian (mjtJacobian)
  • solver: solver algorithm (mjtSolver)
  • iterations: maximum number of main solver iterations
  • noslip_iterations: maximum number of noslip solver iterations
  • mpr_iterations: maximum number of MPR solver iterations
  • disableflags: bit flags for disabling standard features
  • enableflags: bit flags for enabling optional features
MuJoCo.LibMuJoCo.mjSolverStat_Type
mjSolverStat

Fields

  • improvement: cost reduction, scaled by 1/trace(M(qpos0))
  • gradient: gradient norm (primal only, scaled)
  • lineslope: slope in linesearch
  • nactive: number of active constraints
  • nchange: number of constraint state changes
  • neval: number of cost evaluations in line search
  • nupdate: number of Cholesky updates in line search
MuJoCo.LibMuJoCo.mjStatistic_Type
mjStatistic

Fields

  • meaninertia: mean diagonal inertia
  • meanmass: mean body mass
  • meansize: mean body size
  • extent: spatial extent
  • center: center of model
MuJoCo.LibMuJoCo.mjUI_Type
mjUI

Fields

  • spacing: UI theme spacing
  • color: UI theme color
  • predicate: callback to set item state programmatically
  • userdata: pointer to user data (passed to predicate)
  • rectid: index of this ui rectangle in mjuiState
  • auxid: aux buffer index of this ui
  • radiocol: number of radio columns (0 defaults to 2)
  • width: width
  • height: current heigth
  • maxheight: height when all sections open
  • scroll: scroll from top of UI
  • mousesect: 0: none, -1: scroll, otherwise 1+section
  • mouseitem: item within section
  • mousehelp: help button down: print shortcuts
  • editsect: 0: none, otherwise 1+section
  • edititem: item within section
  • editcursor: cursor position
  • editscroll: horizontal scroll
  • edittext: current text
  • editchanged: pointer to changed edit in last mjui_event
  • nsect: number of sections in use
  • sect: preallocated array of sections
MuJoCo.LibMuJoCo.mjVFS_Type
mjVFS

Fields

  • nfile: number of files present
  • filename: file name without path
  • filesize: file size in bytes
  • filedata: buffer with file data
MuJoCo.LibMuJoCo.mjrContext_Type
mjrContext

Fields

  • lineWidth: line width for wireframe rendering
  • shadowClip: clipping radius for directional lights
  • shadowScale: fraction of light cutoff for spot lights
  • fogStart: fog start = stat.extent * vis.map.fogstart
  • fogEnd: fog end = stat.extent * vis.map.fogend
  • fogRGBA: fog rgba
  • shadowSize: size of shadow map texture
  • offWidth: width of offscreen buffer
  • offHeight: height of offscreen buffer
  • offSamples: number of offscreen buffer multisamples
  • fontScale: font scale
  • auxWidth: auxiliary buffer width
  • auxHeight: auxiliary buffer height
  • auxSamples: auxiliary buffer multisamples
  • offFBO: offscreen framebuffer object
  • offFBO_r: offscreen framebuffer for resolving multisamples
  • offColor: offscreen color buffer
  • offColor_r: offscreen color buffer for resolving multisamples
  • offDepthStencil: offscreen depth and stencil buffer
  • offDepthStencil_r: offscreen depth and stencil buffer for resolving multisamples
  • shadowFBO: shadow map framebuffer object
  • shadowTex: shadow map texture
  • auxFBO: auxiliary framebuffer object
  • auxFBO_r: auxiliary framebuffer object for resolving
  • auxColor: auxiliary color buffer
  • auxColor_r: auxiliary color buffer for resolving
  • ntexture: number of allocated textures
  • textureType: type of texture (mjtTexture) (ntexture)
  • texture: texture names
  • basePlane: all planes from model
  • baseMesh: all meshes from model
  • baseHField: all hfields from model
  • baseBuiltin: all buildin geoms, with quality from model
  • baseFontNormal: normal font
  • baseFontShadow: shadow font
  • baseFontBig: big font
  • rangePlane: all planes from model
  • rangeMesh: all meshes from model
  • rangeHField: all hfields from model
  • rangeBuiltin: all builtin geoms, with quality from model
  • rangeFont: all characters in font
  • nskin: number of skins
  • skinvertVBO: skin vertex position VBOs (nskin)
  • skinnormalVBO: skin vertex normal VBOs (nskin)
  • skintexcoordVBO: skin vertex texture coordinate VBOs (nskin)
  • skinfaceVBO: skin face index VBOs (nskin)
  • charWidth: character widths: normal and shadow
  • charWidthBig: chacarter widths: big
  • charHeight: character heights: normal and shadow
  • charHeightBig: character heights: big
  • glInitialized: is OpenGL initialized
  • windowAvailable: is default/window framebuffer available
  • windowSamples: number of samples for default/window framebuffer
  • windowStereo: is stereo available for default/window framebuffer
  • windowDoublebuffer: is default/window framebuffer double buffered
  • currentBuffer: currently active framebuffer: mjFBWINDOW or mjFBOFFSCREEN
  • readPixelFormat: default color pixel format for mjr_readPixels
MuJoCo.LibMuJoCo.mjrRect_Type
mjrRect

Fields

  • left: left (usually 0)
  • bottom: bottom (usually 0)
  • width: width (usually buffer width)
  • height: height (usually buffer height)
MuJoCo.LibMuJoCo.mjuiDef_Type
mjuiDef

Fields

  • type: type (mjtItem); -1: section
  • name: name
  • state: state
  • pdata: pointer to data
  • other: string with type-specific properties
MuJoCo.LibMuJoCo.mjuiItem_Type
mjuiItem

Fields

  • type: type (mjtItem)
  • name: name
  • state: 0: disable, 1: enable, 2+: use predicate
  • pdata: data pointer (type-specific)
  • sectionid: id of section containing item
  • itemid: id of item within section
  • rect: rectangle occupied by item
MuJoCo.LibMuJoCo.mjuiSection_Type
mjuiSection

Fields

  • name: name
  • state: 0: closed, 1: open
  • modifier: 0: none, 1: control, 2: shift; 4: alt
  • shortcut: shortcut key; 0: undefined
  • nitem: number of items in use
  • item: preallocated array of items
  • rtitle: rectangle occupied by title
  • rcontent: rectangle occupied by content
MuJoCo.LibMuJoCo.mjuiState_Type
mjuiState

Fields

  • nrect: number of rectangles used
  • rect: rectangles (index 0: entire window)
  • userdata: pointer to user data (for callbacks)
  • type: (type mjtEvent)
  • left: is left button down
  • right: is right button down
  • middle: is middle button down
  • doubleclick: is last press a double click
  • button: which button was pressed (mjtButton)
  • buttontime: time of last button press
  • x: x position
  • y: y position
  • dx: x displacement
  • dy: y displacement
  • sx: x scroll
  • sy: y scroll
  • control: is control down
  • shift: is shift down
  • alt: is alt down
  • key: which key was pressed
  • keytime: time of last key press
  • mouserect: which rectangle contains mouse
  • dragrect: which rectangle is dragged with mouse
  • dragbutton: which button started drag (mjtButton)
  • dropcount: number of files dropped
  • droppaths: paths to files dropped
MuJoCo.LibMuJoCo.mjuiThemeColor_Type
mjuiThemeColor

Fields

  • master: master background
  • thumb: scrollbar thumb
  • secttitle: section title
  • sectfont: section font
  • sectsymbol: section symbol
  • sectpane: section pane
  • shortcut: shortcut background
  • fontactive: font active
  • fontinactive: font inactive
  • decorinactive: decor inactive
  • decorinactive2: inactive slider color 2
  • button: button
  • check: check
  • radio: radio
  • select: select
  • select2: select pane
  • slider: slider
  • slider2: slider color 2
  • edit: edit
  • edit2: edit invalid
  • cursor: edit cursor
MuJoCo.LibMuJoCo.mjuiThemeSpacing_Type
mjuiThemeSpacing

Fields

  • total: total width
  • scroll: scrollbar width
  • label: label width
  • section: section gap
  • itemside: item side gap
  • itemmid: item middle gap
  • itemver: item vertical gap
  • texthor: text horizontal gap
  • textver: text vertical gap
  • linescroll: number of pixels to scroll
  • samples: number of multisamples
MuJoCo.LibMuJoCo.mjvCamera_Type
mjvCamera

Fields

  • type: camera type (mjtCamera)
  • fixedcamid: fixed camera id
  • trackbodyid: body id to track
  • lookat: lookat point
  • distance: distance to lookat point or tracked body
  • azimuth: camera azimuth (deg)
  • elevation: camera elevation (deg)
MuJoCo.LibMuJoCo.mjvFigure_Type
mjvFigure

Fields

  • flg_legend: show legend
  • flg_ticklabel: show grid tick labels (x,y)
  • flg_extend: automatically extend axis ranges to fit data
  • flg_barplot: isolated line segments (i.e. GL_LINES)
  • flg_selection: vertical selection line
  • flg_symmetric: symmetric y-axis
  • linewidth: line width
  • gridwidth: grid line width
  • gridsize: number of grid points in (x,y)
  • gridrgb: grid line rgb
  • figurergba: figure color and alpha
  • panergba: pane color and alpha
  • legendrgba: legend color and alpha
  • textrgb: text color
  • linergb: line colors
  • range: axis ranges; (min>=max) automatic
  • xformat: x-tick label format for sprintf
  • yformat: y-tick label format for sprintf
  • minwidth: string used to determine min y-tick width
  • title: figure title; subplots separated with 2+ spaces
  • xlabel: x-axis label
  • linename: line names for legend
  • legendoffset: number of lines to offset legend
  • subplot: selected subplot (for title rendering)
  • highlight: if point is in legend rect, highlight line
  • highlightid: if id>=0 and no point, highlight id
  • selection: selection line x-value
  • linepnt: number of points in line; (0) disable
  • linedata: line data (x,y)
  • xaxispixel: range of x-axis in pixels
  • yaxispixel: range of y-axis in pixels
  • xaxisdata: range of x-axis in data units
  • yaxisdata: range of y-axis in data units
MuJoCo.LibMuJoCo.mjvGLCamera_Type
mjvGLCamera

Fields

  • pos: position
  • forward: forward direction
  • up: up direction
  • frustum_center: hor. center (left,right set to match aspect)
  • frustum_bottom: bottom
  • frustum_top: top
  • frustum_near: near
  • frustum_far: far
MuJoCo.LibMuJoCo.mjvGeom_Type
mjvGeom

Fields

  • type: geom type (mjtGeom)
  • dataid: mesh, hfield or plane id; -1: none
  • objtype: mujoco object type; mjOBJ_UNKNOWN for decor
  • objid: mujoco object id; -1 for decor
  • category: visual category
  • texid: texture id; -1: no texture
  • texuniform: uniform cube mapping
  • texcoord: mesh geom has texture coordinates
  • segid: segmentation id; -1: not shown
  • texrepeat: texture repetition for 2D mapping
  • size: size parameters
  • pos: Cartesian position
  • mat: Cartesian orientation
  • rgba: color and transparency
  • emission: emission coef
  • specular: specular coef
  • shininess: shininess coef
  • reflectance: reflectance coef
  • label: text label
  • camdist: distance to camera (used by sorter)
  • modelrbound: geom rbound from model, 0 if not model geom
  • transparent: treat geom as transparent
MuJoCo.LibMuJoCo.mjvLight_Type
mjvLight

Fields

  • pos: position rel. to body frame
  • dir: direction rel. to body frame
  • attenuation: OpenGL attenuation (quadratic model)
  • cutoff: OpenGL cutoff
  • exponent: OpenGL exponent
  • ambient: ambient rgb (alpha=1)
  • diffuse: diffuse rgb (alpha=1)
  • specular: specular rgb (alpha=1)
  • headlight: headlight
  • directional: directional light
  • castshadow: does light cast shadows
MuJoCo.LibMuJoCo.mjvOption_Type
mjvOption

Fields

  • label: what objects to label (mjtLabel)
  • frame: which frame to show (mjtFrame)
  • geomgroup: geom visualization by group
  • sitegroup: site visualization by group
  • jointgroup: joint visualization by group
  • tendongroup: tendon visualization by group
  • actuatorgroup: actuator visualization by group
  • skingroup: skin visualization by group
  • flags: visualization flags (indexed by mjtVisFlag)
  • bvh_depth: depth of the bounding volume hierarchy to be visualized
MuJoCo.LibMuJoCo.mjvPerturb_Type
mjvPerturb

Fields

  • select: selected body id; non-positive: none
  • skinselect: selected skin id; negative: none
  • active: perturbation bitmask (mjtPertBit)
  • active2: secondary perturbation bitmask (mjtPertBit)
  • refpos: reference position for selected object
  • refquat: reference orientation for selected object
  • refselpos: reference position for selection point
  • localpos: selection point in object coordinates
  • localmass: spatial inertia at selection point
  • scale: relative mouse motion-to-space scaling (set by initPerturb)
MuJoCo.LibMuJoCo.mjvSceneState_Type
mjvSceneState

Fields

  • nbuffer: size of the buffer in bytes
  • buffer: heap-allocated memory for all arrays in this struct
  • maxgeom: maximum number of mjvGeom supported by this state object
  • plugincache: scratch space for vis geoms inserted by plugins
MuJoCo.LibMuJoCo.mjvScene_Type
mjvScene

Fields

  • maxgeom: size of allocated geom buffer
  • ngeom: number of geoms currently in buffer
  • geoms: buffer for geoms (ngeom)
  • geomorder: buffer for ordering geoms by distance to camera (ngeom)
  • nskin: number of skins
  • skinfacenum: number of faces in skin (nskin)
  • skinvertadr: address of skin vertices (nskin)
  • skinvertnum: number of vertices in skin (nskin)
  • skinvert: skin vertex data (nskin)
  • skinnormal: skin normal data (nskin)
  • nlight: number of lights currently in buffer
  • lights: buffer for lights (nlight)
  • camera: left and right camera
  • enabletransform: enable model transformation
  • translate: model translation
  • rotate: model quaternion rotation
  • scale: model scaling
  • stereo: stereoscopic rendering (mjtStereo)
  • flags: rendering flags (indexed by mjtRndFlag)
  • framewidth: frame pixel width; 0: disable framing
  • framergb: frame color
MuJoCo.LibMuJoCo.mj_addFileVFSMethod
mj_addFileVFS(vfs, directory, filename)

Add file to VFS, return 0: success, 1: full, 2: repeated name, -1: failed to load.

MuJoCo.LibMuJoCo.mj_addMMethod
mj_addM(m, d, dst, rownnz, rowadr, colind)

Add inertia matrix to destination matrix. Destination can be sparse uncompressed, or dense when all int* are NULL

MuJoCo.LibMuJoCo.mj_applyFTMethod
mj_applyFT(m, d, force, torque, point, body, qfrc_target)

Apply Cartesian force and torque (outside xfrc_applied mechanism).

MuJoCo.LibMuJoCo.mj_constraintUpdateMethod
mj_constraintUpdate(m, d, jar, cost, flg_coneHessian)

Compute efcstate, efcforce, qfrc_constraint, and (optionally) cone Hessians. If cost is not NULL, set cost = s(jar) where jar = Jacqacc-aref.

MuJoCo.LibMuJoCo.mj_copyDataMethod
mj_copyData(dest, m, src)

Copy mjData. m is only required to contain the size fields from MJMODEL_INTS.

MuJoCo.LibMuJoCo.mj_getPluginConfigMethod
mj_getPluginConfig(m, plugin_id, attrib)

Return a config attribute value of a plugin instance; NULL: invalid plugin instance ID or attribute name

MuJoCo.LibMuJoCo.mj_id2nameMethod
mj_id2name(m, type, id)

Get name of object with the specified mjtObj type and id, returns NULL if name not found.

MuJoCo.LibMuJoCo.mj_jacMethod
mj_jac(m, d, jacp, jacr, point, body)

Compute 3/6-by-nv end-effector Jacobian of global point attached to given body.

MuJoCo.LibMuJoCo.mj_jacPointAxisMethod
mj_jacPointAxis(m, d, jacPoint, jacAxis, point, axis, body)

Compute translation end-effector Jacobian of point, and rotation Jacobian of axis.

MuJoCo.LibMuJoCo.mj_loadAllPluginLibrariesMethod
mj_loadAllPluginLibraries(directory, callback)

Scan a directory and load all dynamic libraries. Dynamic libraries in the specified directory are assumed to register one or more plugins. Optionally, if a callback is specified, it is called for each dynamic library encountered that registers plugins.

MuJoCo.LibMuJoCo.mj_loadModelMethod
mj_loadModel(filename, vfs)

Load model from binary MJB file. If vfs is not NULL, look up file in vfs before reading from disk.

MuJoCo.LibMuJoCo.mj_loadXMLMethod
mj_loadXML(filename, vfs, error, error_sz)

Parse XML file in MJCF or URDF format, compile it, return low-level model. If vfs is not NULL, look up files in vfs before reading from disk. If error is not NULL, it must have size error_sz.

MuJoCo.LibMuJoCo.mj_makeDataMethod
mj_makeData(m)

Allocate mjData corresponding to given model. If the model buffer is unallocated the initial configuration will not be set.

MuJoCo.LibMuJoCo.mj_multiRayMethod
mj_multiRay(m, d, pnt, vec, geomgroup, flg_static, bodyexclude, geomid, dist, nray, cutoff)

Intersect multiple rays emanating from a single point. Similar semantics to mj_ray, but vec is an array of (nray x 3) directions.

MuJoCo.LibMuJoCo.mj_name2idMethod
mj_name2id(m, type, name)

Get id of object with the specified mjtObj type and name, returns -1 if id not found.

MuJoCo.LibMuJoCo.mj_objectAccelerationMethod
mj_objectAcceleration(m, d, objtype, objid, res, flg_local)

Compute object 6D acceleration (rot:lin) in object-centered frame, world/local orientation.

MuJoCo.LibMuJoCo.mj_objectVelocityMethod
mj_objectVelocity(m, d, objtype, objid, res, flg_local)

Compute object 6D velocity (rot:lin) in object-centered frame, world/local orientation.

MuJoCo.LibMuJoCo.mj_printFormattedDataMethod
mj_printFormattedData(m, d, filename, float_format)

Print mjData to text file, specifying format. float_format must be a valid printf-style format string for a single float value

MuJoCo.LibMuJoCo.mj_printFormattedModelMethod
mj_printFormattedModel(m, filename, float_format)

Print mjModel to text file, specifying format. float_format must be a valid printf-style format string for a single float value.

MuJoCo.LibMuJoCo.mj_printSchemaMethod
mj_printSchema(filename, buffer, buffer_sz, flg_html, flg_pad)

Print internal XML schema as plain text or HTML, with style-padding or &nbsp;.

MuJoCo.LibMuJoCo.mj_rayMethod
mj_ray(m, d, pnt, vec, geomgroup, flg_static, bodyexclude, geomid)

Intersect ray (pnt+x*vec, x>=0) with visible geoms, except geoms in bodyexclude. Return distance (x) to nearest surface, or -1 if no intersection and output geomid. geomgroup, flg_static are as in mjvOption; geomgroup==NULL skips group exclusion.

MuJoCo.LibMuJoCo.mj_rayHfieldMethod
mj_rayHfield(m, d, geomid, pnt, vec)

Intersect ray with hfield, return nearest distance or -1 if no intersection.

MuJoCo.LibMuJoCo.mj_rayMeshMethod
mj_rayMesh(m, d, geomid, pnt, vec)

Intersect ray with mesh, return nearest distance or -1 if no intersection.

MuJoCo.LibMuJoCo.mj_rneMethod
mj_rne(m, d, flg_acc, result)

RNE: compute M(qpos)*qacc + C(qpos,qvel); flg_acc=0 removes inertial term.

MuJoCo.LibMuJoCo.mj_saveLastXMLMethod
mj_saveLastXML(filename, m, error, error_sz)

Update XML data structures with info from low-level model, save as MJCF. If error is not NULL, it must have size error_sz.

MuJoCo.LibMuJoCo.mj_saveModelMethod
mj_saveModel(m, filename, buffer, buffer_sz)

Save model to binary MJB file or memory buffer; buffer has precedence when given.

MuJoCo.LibMuJoCo.mj_setLengthRangeMethod
mj_setLengthRange(m, d, index, opt, error, error_sz)

Set actuator_lengthrange for specified actuator; return 1 if ok, 0 if error.

MuJoCo.LibMuJoCo.mj_stepMethod
mj_step(m, d)

Advance simulation, use control callback to obtain external force and control.

MuJoCo.LibMuJoCo.mj_step1Method
mj_step1(m, d)

Advance simulation in two steps: before external force and control is set by user.

MuJoCo.LibMuJoCo.mj_step2Method
mj_step2(m, d)

Advance simulation in two steps: after external force and control is set by user.

MuJoCo.LibMuJoCo.mj_warningMethod
mj_warning(d, warning, info)

High-level warning function: count warnings in mjData, print only the first.

MuJoCo.LibMuJoCo.mjd_inverseFDMethod
mjd_inverseFD(m, d, eps, flg_actuation, DfDq, DfDv, DfDa, DsDq, DsDv, DsDa, DmDq)

Finite differenced Jacobians of (force, sensors) = mjinverse(state, acceleration) All outputs are optional. Output dimensions (transposed w.r.t Control Theory convention): DfDq: (nv x nv) DfDv: (nv x nv) DfDa: (nv x nv) DsDq: (nv x nsensordata) DsDv: (nv x nsensordata) DsDa: (nv x nsensordata) DmDq: (nv x nM) single-letter shortcuts: inputs: q=qpos, v=qvel, a=qacc outputs: f=qfrcinverse, s=sensordata, m=qM notes: optionally computes mass matrix Jacobian DmDq flgactuation specifies whether to subtract qfrcactuator from qfrc_inverse

MuJoCo.LibMuJoCo.mjd_transitionFDMethod
mjd_transitionFD(m, d, eps, flg_centered, A, B, C, D)

Finite differenced transition matrices (control theory notation) d(x_next) = Adx + Bdu d(sensor) = Cdx + Ddu required output matrix dimensions: A: (2nv+na x 2nv+na) B: (2nv+na x nu) D: (nsensordata x 2nv+na) C: (nsensordata x nu)

MuJoCo.LibMuJoCo.mjp_getPluginMethod
mjp_getPlugin(name, slot)

Look up a plugin by name. If slot is not NULL, also write its registered slot number into it.

MuJoCo.LibMuJoCo.mjp_registerPluginMethod
mjp_registerPlugin(plugin)

Globally register a plugin. This function is thread-safe. If an identical mjpPlugin is already registered, this function does nothing. If a non-identical mjpPlugin with the same name is already registered, an mju_error is raised. Two mjpPlugins are considered identical if all member function pointers and numbers are equal, and the name and attribute strings are all identical, however the char pointers to the strings need not be the same.

MuJoCo.LibMuJoCo.mjp_registerResourceProviderMethod
mjp_registerResourceProvider(provider)

Globally register a resource provider in a thread-safe manner. The provider must have a prefix that is not a sub-prefix or super-prefix of any current registered providers. This function returns a slot number > 0 on success.

MuJoCo.LibMuJoCo.mjr_addAuxMethod
mjr_addAux(index, width, height, samples, con)

Add Aux buffer with given index to context; free previous Aux buffer.

MuJoCo.LibMuJoCo.mjr_blitBufferMethod
mjr_blitBuffer(src, dst, flg_color, flg_depth, con)

Blit from src viewpoint in current framebuffer to dst viewport in other framebuffer. If src, dst have different size and flgdepth==0, color is interpolated with GLLINEAR.

MuJoCo.LibMuJoCo.mjr_drawPixelsMethod
mjr_drawPixels(rgb, depth, viewport, con)

Draw pixels from client buffer to current OpenGL framebuffer. Viewport is in OpenGL framebuffer; client buffer starts at (0,0).

MuJoCo.LibMuJoCo.mjr_labelMethod
mjr_label(viewport, font, txt, r, g, b, a, rt, gt, bt, con)

Draw rectangle with centered text.

MuJoCo.LibMuJoCo.mjr_overlayMethod
mjr_overlay(font, gridpos, viewport, overlay, overlay2, con)

Draw text overlay; font is mjtFont; gridpos is mjtGridPos.

MuJoCo.LibMuJoCo.mjr_readPixelsMethod
mjr_readPixels(rgb, depth, viewport, con)

Read pixels from current OpenGL framebuffer to client buffer. Viewport is in OpenGL framebuffer; client buffer starts at (0,0).

MuJoCo.LibMuJoCo.mjr_setBufferMethod
mjr_setBuffer(framebuffer, con)

Set OpenGL framebuffer for rendering: mjFBWINDOW or mjFBOFFSCREEN. If only one buffer is available, set that buffer and ignore framebuffer argument.

MuJoCo.LibMuJoCo.mjr_textMethod
mjr_text(font, txt, con, x, y, r, g, b)

Draw text at (x,y) in relative coordinates; font is mjtFont.

MuJoCo.LibMuJoCo.mju_band2DenseMethod
mju_band2Dense(res, mat, ntotal, nband, ndense, flg_sym)

Convert banded matrix to dense matrix, fill upper triangle if flg_sym>0.

MuJoCo.LibMuJoCo.mju_bandMulMatVecMethod
mju_bandMulMatVec(res, mat, vec, ntotal, nband, ndense, nvec, flg_sym)

Multiply band-diagonal matrix with nvec vectors, include upper triangle if flg_sym>0.

MuJoCo.LibMuJoCo.mju_boxQPMethod
mju_boxQP(res, R, index, H, g, n, lower, upper)

minimize 0.5x'Hx + x'g s.t. lower <= x <= upper, return rank or -1 if failed inputs: n - problem dimension H - SPD matrix nn g - bias vector n lower - lower bounds n upper - upper bounds n res - solution warmstart n return value: nfree <= n - rank of unconstrained subspace, -1 if failure outputs (required): res - solution n R - subspace Cholesky factor nfreenfree allocated: n(n+7) outputs (optional): index - set of free dimensions nfree allocated: n notes: the initial value of res is used to warmstart the solver R must have allocatd size n(n+7), but only nfree*nfree values are used in output index (if given) must have allocated size n, but only nfree values are used in output only the lower triangles of H and R and are read from and written to, respectively the convenience function mju_boxQPmalloc allocates the required data structures

MuJoCo.LibMuJoCo.mju_boxQPmallocMethod
mju_boxQPmalloc(res, R, index, H, g, n, lower, upper)

allocate heap memory for box-constrained Quadratic Program as in mjuboxQP, index, lower, and upper are optional free all pointers with mjufree()

MuJoCo.LibMuJoCo.mju_cholFactorMethod
mju_cholFactor(mat, n, mindiag)

Cholesky decomposition: mat = L*L'; return rank, decomposition performed in-place into mat.

MuJoCo.LibMuJoCo.mju_cholFactorBandMethod
mju_cholFactorBand(mat, ntotal, nband, ndense, diagadd, diagmul)

Band-dense Cholesky decomposition. Returns minimum value in the factorized diagonal, or 0 if rank-deficient. mat has (ntotal-ndense) x nband + ndense x ntotal elements. The first (ntotal-ndense) x nband store the band part, left of diagonal, inclusive. The second ndense x ntotal store the band part as entire dense rows. Add diagadd+diagmul*mat_ii to diagonal before factorization.

MuJoCo.LibMuJoCo.mju_muscleBiasMethod
mju_muscleBias(len, lengthrange, acc0, prm)

Muscle passive force, prm = (range[2], force, scale, lmin, lmax, vmax, fpmax, fvmax).

MuJoCo.LibMuJoCo.mju_muscleGainMethod
mju_muscleGain(len, vel, lengthrange, acc0, prm)

Muscle active force, prm = (range[2], force, scale, lmin, lmax, vmax, fpmax, fvmax).

MuJoCo.LibMuJoCo.mju_negPoseMethod
mju_negPose(posres, quatres, pos, quat)

Conjugate pose, corresponding to the opposite spatial transformation.

MuJoCo.LibMuJoCo.mju_rayGeomMethod
mju_rayGeom(pos, mat, size, pnt, vec, geomtype)

Intersect ray with pure geom, return nearest distance or -1 if no intersection.

MuJoCo.LibMuJoCo.mju_raySkinMethod
mju_raySkin(nface, nvert, face, vert, pnt, vec, vertid)

Intersect ray with skin, return nearest distance or -1 if no intersection, and also output nearest vertex id.

MuJoCo.LibMuJoCo.mju_sqrMatTDMethod
mju_sqrMatTD(res, mat, diag, nr, nc)

Set res = mat' * diag * mat if diag is not NULL, and res = mat' * mat otherwise.

MuJoCo.LibMuJoCo.mju_transformSpatialMethod
mju_transformSpatial(res, vec, flg_force, newpos, oldpos, rotnew2old)

Coordinate transform of 6D motion or force vector in rotation:translation format. rotnew2old is 3-by-3, NULL means no rotation; flg_force specifies force or motion type.

MuJoCo.LibMuJoCo.mjv_applyPerturbPoseMethod
mjv_applyPerturbPose(m, d, pert, flg_paused)

Set perturb pos,quat in d->mocap when selected body is mocap, and in d->qpos otherwise. Write d->qpos only if flg_paused and subtree root for selected body has free joint.

MuJoCo.LibMuJoCo.mjv_connectorMethod
mjv_connector(geom, type, width, from, to)

Set (type, size, pos, mat) for connector-type geom between given points. Assume that mjvinitGeom was already called to set all other properties. Width of mjGEOMLINE is denominated in pixels.

MuJoCo.LibMuJoCo.mjv_initGeomMethod
mjv_initGeom(geom, type, size, pos, mat, rgba)

Initialize given geom fields when not NULL, set the rest to their default values.

MuJoCo.LibMuJoCo.mjv_makeConnectorMethod
mjv_makeConnector(geom, type, width, a0, a1, a2, b0, b1, b2)

Set (type, size, pos, mat) for connector-type geom between given points. Assume that mjvinitGeom was already called to set all other properties. Width of mjGEOMLINE is denominated in pixels. Deprecated: use mjv_connector.

MuJoCo.LibMuJoCo.mjv_selectMethod
mjv_select(m, d, vopt, aspectratio, relx, rely, scn, selpnt, geomid, skinid)

Select geom or skin with mouse, return bodyid; -1: none selected.

MuJoCo.LibMuJoCo.mjv_updateSceneFromStateMethod
mjv_updateSceneFromState(scnstate, opt, pert, cam, catmask, scn)

Update entire scene from a scene state, return the number of new mjWARN_VGEOMFULL warnings.