MuJoCo API

MuJoCo

MuJoCo.Wrappers.DataType
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.Wrappers.ModelType
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.Wrappers.OptionsType
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.Wrappers.StatisticsType
mjStatistic

Fields

  • meaninertia: mean diagonal inertia
  • meanmass: mean body mass
  • meansize: mean body size
  • extent: spatial extent
  • center: center of model
MuJoCo.forward!Method
forward!(model::MODEL_TYPES, data::DATA_TYPES)

Same as step! but without integrating in time.

MuJoCo.init_dataMethod
init_data(model::Model)

Creates an instance of the data required for the step! simulation.

Returns a Data object, wrapping the underlying mjData object.

MuJoCo.init_visualiserMethod
init_visualiser()

Loads the packages necessary for the running the visualiser.

Add the following packages to your project to be able to use the visualisation features, or run "install_visualiser()".

Packages:

  • BangBang
  • FFMPEG
  • GLFW
  • Observables
  • PrettyTables
  • Printf
  • StaticArrays
MuJoCo.install_visualiserMethod
install_visualiser()

Installs the necessary packages for the running the visualiser into the current running environment.

Packages:

  • BangBang
  • FFMPEG
  • GLFW
  • Observables
  • PrettyTables
  • Printf
  • StaticArrays
MuJoCo.load_modelMethod
load_model(path)

Determines the type of file by the extension and loads the model into memory.

To use this model in a simulator, you will also need the corresponding data, obtained using init_data.

Expected files types: 'xml', 'mjcf', or 'mjb' (or uppercase variants).

Examples

model = load_model(MuJoCo.humanoid_model_file())
data = init_data(model)
MuJoCo.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

Arguments

  • m::Model -> Constant.
  • d::Data
  • dst::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • rownnz::Vector{Int32} -> A vector of variable size. Check additional info for sizes.
  • rowadr::Vector{Int32} -> A vector of variable size. Check additional info for sizes.
  • colind::Vector{Int32} -> A vector of variable size. Check additional info for sizes.

Additional Info

  • dst should be a vector, not a matrix.
  • rownnz should be a vector, not a matrix.
  • rowadr should be a vector, not a matrix.
  • colind should be a vector, not a matrix.
  • dst should be of size nM
  • rownnz should be of size nv
  • rowadr should be of size nv
  • colind should be of size nM
MuJoCo.mj_applyFTMethod
mj_applyFT(m, d, force, torque, point, body, qfrc_target)

Apply Cartesian force and torque (outside xfrc_applied mechanism).

Arguments

  • m::Model -> Constant.
  • d::Data
  • force::Vector{Float64} -> A vector of size 3. Constant.
  • torque::Vector{Float64} -> A vector of size 3. Constant.
  • point::Vector{Float64} -> A vector of size 3. Constant.
  • body::Int32
  • qfrc_target::Vector{Float64} -> A vector of variable size. Check additional info for sizes.

Additional Info

  • force should be a vector of size 3
  • force should be a vector of size 3.
  • torque should be a vector of size 3
  • torque should be a vector of size 3.
  • point should be a vector of size 3
  • point should be a vector of size 3.
  • qfrc_target should be a vector, not a matrix.
  • qfrc_target should be of size nv
MuJoCo.mj_arrayMethod
mj_array([element_type=mjtNum], dims...)

Allocates an array compatible with the underlying MuJoCo C API.

The C API treats arrays as row-major, while by default arrays in Julia are column-major. This function will create an array which is accessed in a row-major way, but can be treated by a normal array in your Julia code.

Arguments

  • element_type: Defaults to mjtNum (typically Float64).
  • dims: The dimensionality of output array. Can either be a tuple of integers or a series of integers.
MuJoCo.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.

Arguments

  • m::Model -> Constant.
  • d::Data
  • jar::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • cost::Vector{Float64} -> An optional vector of size 1.
  • flg_coneHessian::Int32

Additional Info

  • jar should be a vector, not a matrix.
  • cost should be a vector of size 1
  • cost should be a vector of size 1.
  • size of jar should equal nefc
MuJoCo.mj_differentiatePosMethod
mj_differentiatePos(m, qvel, dt, qpos1, qpos2)

Compute velocity by finite-differencing two positions.

Arguments

  • m::Model -> Constant.
  • qvel::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • dt::Float64
  • qpos1::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • qpos2::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • qvel should be a vector, not a matrix.
  • qpos1 should be a vector, not a matrix.
  • qpos2 should be a vector, not a matrix.
  • qvel should be of size nv
  • qpos1 should be of size nq
  • qpos2 should be of size nq
MuJoCo.mj_fullMMethod
mj_fullM(m, dst, M)

Convert sparse inertia matrix M into full (i.e. dense) matrix.

Arguments

  • m::Model -> Constant.
  • dst::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • M::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • M should be a vector, not a matrix.
  • M should be of size nM
  • dst should be of shape (nv, nv)
MuJoCo.mj_getStateMethod
mj_getState(m, d, state, spec)

Get state.

Arguments

  • m::Model -> Constant.
  • d::Data -> Constant.
  • state::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • spec::Int32

Additional Info

  • state should be a vector, not a matrix.
  • state size should equal mj_stateSize(m, spec)
MuJoCo.mj_integratePosMethod
mj_integratePos(m, qpos, qvel, dt)

Integrate position with given velocity.

Arguments

  • m::Model -> Constant.
  • qpos::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • qvel::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • dt::Float64

Additional Info

  • qpos should be a vector, not a matrix.
  • qvel should be a vector, not a matrix.
  • qpos should be of size nq
  • qvel should be of size nv
MuJoCo.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.

Arguments

  • m::Model -> Constant.
  • d::Data
  • jacp::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • jacr::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • point::Vector{Float64} -> A vector of size 3. Constant.
  • body::Int32

Additional Info

  • point should be a vector of size 3
  • point should be a vector of size 3.
  • jacp should be of shape (3, nv)
  • jacr should be of shape (3, nv)
MuJoCo.mj_jacBodyMethod
mj_jacBody(m, d, jacp, jacr, body)

Compute body frame end-effector Jacobian.

Arguments

  • m::Model -> Constant.
  • d::Data
  • jacp::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • jacr::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • body::Int32

Additional Info

  • jacp should be of shape (3, nv)
  • jacr should be of shape (3, nv)
MuJoCo.mj_jacBodyComMethod
mj_jacBodyCom(m, d, jacp, jacr, body)

Compute body center-of-mass end-effector Jacobian.

Arguments

  • m::Model -> Constant.
  • d::Data
  • jacp::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • jacr::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • body::Int32

Additional Info

  • jacp should be of shape (3, nv)
  • jacr should be of shape (3, nv)
MuJoCo.mj_jacGeomMethod
mj_jacGeom(m, d, jacp, jacr, geom)

Compute geom end-effector Jacobian.

Arguments

  • m::Model -> Constant.
  • d::Data
  • jacp::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • jacr::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • geom::Int32

Additional Info

  • jacp should be of shape (3, nv)
  • jacr should be of shape (3, nv)
MuJoCo.mj_jacPointAxisMethod
mj_jacPointAxis(m, d, jacp, jacr, point, axis, body)

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

Arguments

  • m::Model -> Constant.
  • d::Data
  • jacp::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • jacr::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • point::Vector{Float64} -> A vector of size 3. Constant.
  • axis::Vector{Float64} -> A vector of size 3. Constant.
  • body::Int32

Additional Info

  • point should be a vector of size 3
  • point should be a vector of size 3.
  • axis should be a vector of size 3
  • axis should be a vector of size 3.
  • jacp should be of shape (3, nv)
  • jacr should be of shape (3, nv)
MuJoCo.mj_jacSiteMethod
mj_jacSite(m, d, jacp, jacr, site)

Compute site end-effector Jacobian.

Arguments

  • m::Model -> Constant.
  • d::Data
  • jacp::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • jacr::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • site::Int32

Additional Info

  • jacp should be of shape (3, nv)
  • jacr should be of shape (3, nv)
MuJoCo.mj_jacSubtreeComMethod
mj_jacSubtreeCom(m, d, jacp, body)

Compute subtree center-of-mass end-effector Jacobian.

Arguments

  • m::Model -> Constant.
  • d::Data
  • jacp::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • body::Int32

Additional Info

  • jacp should be of shape (3, nv)
MuJoCo.mj_mulJacTVecMethod
mj_mulJacTVec(m, d, res, vec)

Multiply dense or sparse constraint Jacobian transpose by vector.

Arguments

  • m::Model -> Constant.
  • d::Data
  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
  • res should be of length nv
  • vec should be of length nefc
MuJoCo.mj_mulJacVecMethod
mj_mulJacVec(m, d, res, vec)

Multiply dense or sparse constraint Jacobian by vector.

Arguments

  • m::Model -> Constant.
  • d::Data
  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
  • res should be of length nefc
  • vec should be of length nv
MuJoCo.mj_mulMMethod
mj_mulM(m, d, res, vec)

Multiply vector by inertia matrix.

Arguments

  • m::Model -> Constant.
  • d::Data -> Constant.
  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
  • res should be of size nv
  • vec should be of size nv
MuJoCo.mj_mulM2Method
mj_mulM2(m, d, res, vec)

Multiply vector by (inertia matrix)^(1/2).

Arguments

  • m::Model -> Constant.
  • d::Data -> Constant.
  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
  • res should be of size nv
  • vec should be of size nv
MuJoCo.mj_normalizeQuatMethod
mj_normalizeQuat(m, qpos)

Normalize all quaternions in qpos-type vector.

Arguments

  • m::Model -> Constant.
  • qpos::Vector{Float64} -> A vector of variable size. Check additional info for sizes.

Additional Info

  • qpos should be a vector, not a matrix.
  • qpos should be of size nq
MuJoCo.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.

Arguments

  • m::Model -> Constant.
  • d::Data -> Constant.
  • pnt::Vector{Float64} -> A vector of size 3. Constant.
  • vec::Vector{Float64} -> A vector of size 3. Constant.
  • geomgroup::Vector{UInt8} -> An optional vector of size 6. Constant.
  • flg_static::UInt8
  • bodyexclude::Int32
  • geomid::Vector{Int32} -> A vector of size 1.

Additional Info

  • pnt should be a vector of size 3
  • pnt should be a vector of size 3.
  • vec should be a vector of size 3
  • vec should be a vector of size 3.
  • geomgroup should be a vector of size 6
  • geomgroup should be a vector of size 6.
  • geomid should be a vector of size 1
  • geomid should be a vector of size 1.
MuJoCo.mj_rneMethod
mj_rne(m, d, flg_acc, result)

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

Arguments

  • m::Model -> Constant.
  • d::Data
  • flg_acc::Int32
  • result::Vector{Float64} -> A vector of variable size. Check additional info for sizes.

Additional Info

  • result should be a vector, not a matrix.
  • result should have length nv
MuJoCo.mj_setStateMethod
mj_setState(m, d, state, spec)

Set state.

Arguments

  • m::Model -> Constant.
  • d::Data
  • state::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • spec::Int32

Additional Info

  • state should be a vector, not a matrix.
  • state size should equal mj_stateSize(m, spec)
MuJoCo.mj_solveMMethod
mj_solveM(m, d, x, y)

Solve linear system M * x = y using factorization: x = inv(L'DL)*y

Arguments

  • m::Model -> Constant.
  • d::Data
  • x::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • y::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.
MuJoCo.mj_solveM2Method
mj_solveM2(m, d, x, y)

Half of linear solve: x = sqrt(inv(D))inv(L')y

Arguments

  • m::Model -> Constant.
  • d::Data
  • x::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • y::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.
MuJoCo.mj_zerosMethod
mj_zeros([element_type=mjtNum], dims...)

Allocates an array full of zeros, compatible with the underlying MuJoCo C API.

The C API treats arrays as row-major, while by default arrays in Julia are column-major. This function will create an array which is accessed in a row-major way, but can be treated by a normal array in your Julia code.

Arguments

  • element_type: The element type of the array. Defaults to mjtNum (typically Float64).
  • dims: The dimensionality of output array. Can either be a tuple of integers or a series of integers.
MuJoCo.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

Arguments

  • m::Model -> Constant.
  • d::Data
  • eps::Float64
  • flg_actuation::UInt8
  • DfDq::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • DfDv::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • DfDa::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • DsDq::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • DsDv::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • DsDa::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • DmDq::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.

Additional Info

  • DfDq should be of shape (nv, nv)
  • DfDv should be of shape (nv, nv)
  • DfDa should be of shape (nv, nv)
  • DsDq should be of shape (nv, nsensordata)
  • DsDv should be of shape (nv, nsensordata)
  • DsDa should be of shape (nv, nsensordata)
  • DmDq should be of shape (nv, nM)
MuJoCo.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)

Arguments

  • m::Model -> Constant.
  • d::Data
  • eps::Float64
  • flg_centered::UInt8
  • A::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • B::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • C::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • D::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.

Additional Info

  • A should be of shape (2nv+na, 2nv+na)
  • B should be of shape (2*nv+na, nu)
  • C should be of shape (nsensordata, 2*nv+na)
  • D should be of shape (nsensordata, nu)
MuJoCo.mju_L1Method
mju_L1(vec)

Return L1 norm: sum(abs(vec)).

Arguments

  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes.

Additional Info

  • vec should be a vector, not a matrix.
MuJoCo.mju_addMethod
mju_add(res, vec1, vec2)

Set res = vec1 + vec2.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • vec1::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • vec2::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • vec1 should be a vector, not a matrix.
  • vec2 should be a vector, not a matrix.
  • res and vec1 should have the same size
  • res and vec2 should have the same size
MuJoCo.mju_addSclMethod
mju_addScl(res, vec1, vec2, scl)

Set res = vec1 + vec2*scl.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • vec1::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • vec2::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • scl::Float64

Additional Info

  • res should be a vector, not a matrix.
  • vec1 should be a vector, not a matrix.
  • vec2 should be a vector, not a matrix.
  • res and vec1 should have the same size
  • res and vec2 should have the same size
MuJoCo.mju_addToMethod
mju_addTo(res, vec)

Set res = res + vec.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
  • res and vec should have the same size
MuJoCo.mju_addToSclMethod
mju_addToScl(res, vec, scl)

Set res = res + vec*scl.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • scl::Float64

Additional Info

  • res should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
  • res and vec should have the same size
MuJoCo.mju_band2DenseMethod
mju_band2Dense(res, mat, ntotal, nband, ndense, flg_sym)

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

Arguments

  • res::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • mat::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • ntotal::Int32
  • nband::Int32
  • ndense::Int32
  • flg_sym::UInt8

Additional Info

  • mat should be a vector, not a matrix.
  • res should have ntotal rows
  • res should have ntotal columns
MuJoCo.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.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • mat::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.
  • vec::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.
  • ntotal::Int32
  • nband::Int32
  • ndense::Int32
  • nVec::Int32
  • flg_sym::UInt8

Additional Info

  • res should be a vector, not a matrix.
  • res should have ntotal rows
  • res should have nVec columns
  • vec should have ntotal rows
  • vec should have nVec columns
MuJoCo.mju_boxQPMethod
mju_boxQP(res, R, index, H, g, 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

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • R::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • index::Vector{Int32} -> An optional vector of variable size. Check additional info for sizes.
  • H::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.
  • g::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • lower::Vector{Float64} -> An optional vector of variable size. Check additional info for sizes. Constant.
  • upper::Vector{Float64} -> An optional vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • index should be a vector, not a matrix.
  • g should be a vector, not a matrix.
  • lower should be a vector, not a matrix.
  • upper should be a vector, not a matrix.
  • size of R should be n*(n+7)
  • size of index should equal n
  • H should be of shape (n, n)
  • size of g should equal n
  • size of lower should equal n
  • size of upper should equal n
MuJoCo.mju_cholFactorMethod
mju_cholFactor(mat, mindiag)

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

Arguments

  • mat::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • mindiag::Float64

Additional Info

  • mat should be a square matrix
MuJoCo.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.

Arguments

  • mat::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • ntotal::Int32
  • nband::Int32
  • ndense::Int32
  • diagadd::Float64
  • diagmul::Float64

Additional Info

  • mat should be a vector, not a matrix.
MuJoCo.mju_cholSolveMethod
mju_cholSolve(res, mat, vec)

Solve (mat*mat') * res = vec, where mat is a Cholesky factor.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • mat::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.
  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
  • mat should be a square matrix
MuJoCo.mju_cholSolveBandMethod
mju_cholSolveBand(res, mat, vec, ntotal, nband, ndense)

Solve (matmat')res = vec where mat is a band-dense Cholesky factor.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • mat::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • ntotal::Int32
  • nband::Int32
  • ndense::Int32

Additional Info

  • res should be a vector, not a matrix.
  • mat should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
  • size of res should equal ntotal
  • size of vec should equal ntotal
MuJoCo.mju_cholUpdateMethod
mju_cholUpdate(mat, x, flg_plus)

Cholesky rank-one update: LL' +/- xx'; return rank.

Arguments

  • mat::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • x::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • flg_plus::Int32

Additional Info

  • x should be a vector, not a matrix.
  • mat should be a square matrix
MuJoCo.mju_copyMethod
mju_copy(res, data)

Set res = vec.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • data::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • data should be a vector, not a matrix.
  • res and data should have the same size
MuJoCo.mju_d2nMethod
mju_d2n(res, vec)

Convert from double to mjtNum.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
  • res and vec should have the same size
MuJoCo.mju_decodePyramidMethod
mju_decodePyramid(force, pyramid, mu)

Convert pyramid representation to contact force.

Arguments

  • force::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • pyramid::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • mu::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • force should be a vector, not a matrix.
  • pyramid should be a vector, not a matrix.
  • mu should be a vector, not a matrix.
MuJoCo.mju_dense2BandMethod
mju_dense2Band(res, mat, ntotal, nband, ndense)

Convert dense matrix to banded matrix.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • mat::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.
  • ntotal::Int32
  • nband::Int32
  • ndense::Int32

Additional Info

  • res should be a vector, not a matrix.
  • mat should have ntotal rows
  • mat should have ntotal columns
MuJoCo.mju_dotMethod
mju_dot(vec1, vec2)

Return dot-product of vec1 and vec2.

Arguments

  • vec1::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • vec2::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • vec1 should be a vector, not a matrix.
  • vec2 should be a vector, not a matrix.
  • vec1 and vec2 should have the same size
MuJoCo.mju_encodePyramidMethod
mju_encodePyramid(pyramid, force, mu)

Convert contact force to pyramid representation.

Arguments

  • pyramid::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • force::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • mu::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • pyramid should be a vector, not a matrix.
  • force should be a vector, not a matrix.
  • mu should be a vector, not a matrix.
MuJoCo.mju_eyeMethod
mju_eye(mat)

Set mat to the identity matrix.

Arguments

  • mat::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.

Additional Info

  • mat should be square
MuJoCo.mju_f2nMethod
mju_f2n(res, vec)

Convert from float to mjtNum.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • vec::Vector{Float32} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
  • res and vec should have the same size
MuJoCo.mju_fillMethod
mju_fill(res, val)

Set res = val.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • val::Float64

Additional Info

  • res should be a vector, not a matrix.
MuJoCo.mju_insertionSortMethod
mju_insertionSort(res)

Insertion sort, resulting list is in increasing order.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.

Additional Info

  • res should be a vector, not a matrix.
MuJoCo.mju_insertionSortIntMethod
mju_insertionSortInt(res)

Integer insertion sort, resulting list is in increasing order.

Arguments

  • res::Vector{Int32} -> A vector of variable size. Check additional info for sizes.

Additional Info

  • res should be a vector, not a matrix.
MuJoCo.mju_isZeroMethod
mju_isZero(vec)

Return 1 if all elements are 0.

Arguments

  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes.

Additional Info

  • vec should be a vector, not a matrix.
MuJoCo.mju_mulMatMatMethod
mju_mulMatMat(res, mat1, mat2)

Multiply matrices: res = mat1 * mat2.

Arguments

  • res::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • mat1::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.
  • mat2::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.

Additional Info

  • #rows in res should equal #rows in mat1
  • #columns in mat1 should equal #rows in mat2
MuJoCo.mju_mulMatMatTMethod
mju_mulMatMatT(res, mat1, mat2)

Multiply matrices, second argument transposed: res = mat1 * mat2'.

Arguments

  • res::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • mat1::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.
  • mat2::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.

Additional Info

  • #rows in res should equal #rows in mat1
  • #columns in res should equal #rows in mat2
MuJoCo.mju_mulMatTMatMethod
mju_mulMatTMat(res, mat1, mat2)

Multiply matrices, first argument transposed: res = mat1' * mat2.

Arguments

  • res::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • mat1::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.
  • mat2::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.

Additional Info

  • #rows in res should equal #columns in mat1
  • #rows in mat1 should equal #rows in mat2
MuJoCo.mju_mulMatTVecMethod
mju_mulMatTVec(res, mat, vec)

Multiply transposed matrix and vector: res = mat' * vec.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • mat::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.
  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
MuJoCo.mju_mulMatVecMethod
mju_mulMatVec(res, mat, vec)

Multiply matrix and vector: res = mat * vec.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • mat::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.
  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
MuJoCo.mju_mulVecMatVecMethod
mju_mulVecMatVec(vec1, mat, vec2)

Multiply square matrix with vectors on both sides: returns vec1' * mat * vec2.

Arguments

  • vec1::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • mat::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.
  • vec2::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • vec1 should be a vector, not a matrix.
  • vec2 should be a vector, not a matrix.
MuJoCo.mju_n2dMethod
mju_n2d(res, vec)

Convert from mjtNum to double.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
  • res and vec should have the same size
MuJoCo.mju_n2fMethod
mju_n2f(res, vec)

Convert from mjtNum to float.

Arguments

  • res::Vector{Float32} -> A vector of variable size. Check additional info for sizes.
  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
  • res and vec should have the same size
MuJoCo.mju_normMethod
mju_norm(vec)

Return vector length (without normalizing vector).

Arguments

  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • vec should be a vector, not a matrix.
MuJoCo.mju_normalizeMethod
mju_normalize(vec)

Normalize vector, return length before normalization.

Arguments

  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes.

Additional Info

  • vec should be a vector, not a matrix.
MuJoCo.mju_printMatMethod
mju_printMat(mat)

Print matrix to screen.

Arguments

  • mat::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.
MuJoCo.mju_sclMethod
mju_scl(res, vec, scl)

Set res = vec*scl.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • scl::Float64

Additional Info

  • res should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
  • res and vec should have the same size
MuJoCo.mju_sqrMatTDMethod
mju_sqrMatTD(res, mat, diag)

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

Arguments

  • res::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • mat::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.
  • diag::Vector{Float64} -> An optional vector of variable size. Check additional info for sizes.

Additional Info

  • diag should be a vector, not a matrix.
  • #rows in res should equal #columns in mat
  • #rows in res should equal #columns in mat
MuJoCo.mju_subMethod
mju_sub(res, vec1, vec2)

Set res = vec1 - vec2.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • vec1::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.
  • vec2::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • vec1 should be a vector, not a matrix.
  • vec2 should be a vector, not a matrix.
  • res and vec1 should have the same size
  • res and vec2 should have the same size
MuJoCo.mju_subFromMethod
mju_subFrom(res, vec)

Set res = res - vec.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.
  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes. Constant.

Additional Info

  • res should be a vector, not a matrix.
  • vec should be a vector, not a matrix.
  • res and vec should have the same size
MuJoCo.mju_sumMethod
mju_sum(vec)

Return sum(vec).

Arguments

  • vec::Vector{Float64} -> A vector of variable size. Check additional info for sizes.

Additional Info

  • vec should be a vector, not a matrix.
MuJoCo.mju_symmetrizeMethod
mju_symmetrize(res, mat)

Symmetrize square matrix res = (mat + mat')/2.

Arguments

  • res::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • mat::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.

Additional Info

  • mat should be square
  • res and mat should have the same shape
MuJoCo.mju_transposeMethod
mju_transpose(res, mat)

Transpose matrix: res = mat'.

Arguments

  • res::Matrix{Float64} -> A matrix variable size. Check additional info for sizes.
  • mat::Matrix{Float64} -> A matrix variable size. Check additional info for sizes. Constant.

Additional Info

  • #columns in res should equal #rows in mat
  • #rows in res should equal #columns in mat
MuJoCo.mju_zeroMethod
mju_zero(res)

Set res = 0.

Arguments

  • res::Vector{Float64} -> A vector of variable size. Check additional info for sizes.

Additional Info

  • res should be a vector, not a matrix.
MuJoCo.reset!Method
reset!(m::Model, d::Data)

Resets the data values to their default states. You may equivalently use mj_resetData.

MuJoCo.resetkey!Method
resetkey!(m::Model, d::Data, [keyframe = 1])

Resets the data struct to values in the supplied keyframe.

If no keyframe is specified, the first keyframe is used. The keyframe is a 1-based index into the list supplied by the model's specification.

MuJoCo.resetkey!Method

Resets the data struct to values in the first key frame.

MuJoCo.sample_model_and_dataMethod
sample_model_and_data()

A utility module to create and initialise example Model and Data objects, reflecting the underlying mjModel and mjData structs to provide REPL code completition to aid development.

Returns a (model, data) tuple.

MuJoCo.set_physics_state!Method
set_physics_state!(m::Model, d::Data, x::AbstractVector)

Set the state vector of a MuJoCo model.

The state vector is [joint positions, joint velocities, actuator states] with dimension (nq, nv, na). Call forward! after setting the state to compute all derived quantities in the Data object according to the new state.

See also mj_setState and get_physics_state.

MuJoCo.step!Method
step!(model::Model, data::Data)

Runs the simulation forward one time step, modifying the underlying data object.

MuJoCo.timestepMethod
timestep(model::MODEL_TYPES)

Extract the solver time-step for the given model.

Visualiser

MuJoCo.Visualiser.visualise!Function
visualise!(m::Model, d::Data; controller=nothing)

Starts an interactive visualization of a MuJoCo model specified by an instance of Model and Data.

The visualizer has three "modes" that allow you to visualize passive dynamics, run a controller interactively, or play back recorded trajectories. The passive dynamics mode is always available, while the controller and trajectory modes are specified by the keyword arguments below.

Press F1 for help after running the visualiser to print the available mouse/button options in the terminal. Switch between modes with CTRL+RightArrow and CTRL+LeftArrow (or CMD for Mac). The different visualiser modes are ordered as follows:

  1. Controller mode (if controller keyword is provided)
  2. Trajectory mode (if trajectories keyword is provided)
  3. Passive mode (always available)

Keywords

  • controller: a callback function with the signature controller(m, d), called at each timestep, that applies a control input to the system (or does any other operation you like).

  • trajectories: a single trajectory or Vector of trajectories, where each trajectory is an AbstractMatrix of states with size (nx, T) where nx = model.nq + model.nv + model.na and T is the length of the trajectory. Note that each trajectory can have a different length.

Examples

using MuJoCo
install_visualiser() # Run this to install dependencies only once
init_visualiser()    # Load required dependencies into session

# Load a model
model, data = MuJoCo.sample_model_and_data()

# Simulate and record a trajectory
T = 200
nx = model.nq + model.nv + model.na
states = zeros(nx, T)
for t in 1:T
    states[:,t] = get_physics_state(model, data)
    step!(model, data)
end

# Define a controller
function ctrl!(m,d)
    d.ctrl .= 2*rand(m.nu) .- 1
end

# Run the visualiser
reset!(model, data)
visualise!(model, data, controller=ctrl!, trajectories = states)

Named Access

MuJoCo.Wrappers.NamedAccess.actuatorFunction
actuator([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, ctrl, length, moment, velocity, force)

MuJoCo.Wrappers.NamedAccess.bodyFunction
body([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, applied, xpos, xquat, xmat, xipos, ximat, com, cinert, crb, cvel, linvel, angmom, cacc, int, ext)

MuJoCo.Wrappers.NamedAccess.camFunction
cam([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, xpos, xmat)

MuJoCo.Wrappers.NamedAccess.eqFunction
eq([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, type, obj1id, obj2id, active, solref, solimp, data)

MuJoCo.Wrappers.NamedAccess.excludeFunction
exclude([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, signature)

MuJoCo.Wrappers.NamedAccess.geomFunction
geom([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, xpos, xmat)

MuJoCo.Wrappers.NamedAccess.hfieldFunction
hfield([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, size, nrow, ncol, adr)

MuJoCo.Wrappers.NamedAccess.jntFunction
jnt([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, xanchor, xaxis)

MuJoCo.Wrappers.NamedAccess.keyFunction
key([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, time, qpos, qvel, act, mpos, mquat)

MuJoCo.Wrappers.NamedAccess.lightFunction
light([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, xpos, xdir)

MuJoCo.Wrappers.NamedAccess.matFunction
mat([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, texid, texuniform, texrepeat, emission, specular, shininess, reflectance, rgba)

MuJoCo.Wrappers.NamedAccess.meshFunction
mesh([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, vertadr, vertnum, texcoordadr, faceadr, facenum, graphadr)

MuJoCo.Wrappers.NamedAccess.numericFunction
numeric([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, adr, size)

MuJoCo.Wrappers.NamedAccess.pairFunction
pair([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, dim, geom1, geom2, signature, solref, solimp, margin, gap, friction)

MuJoCo.Wrappers.NamedAccess.sensorFunction
sensor([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name)

MuJoCo.Wrappers.NamedAccess.siteFunction
site([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, xpos, xmat)

MuJoCo.Wrappers.NamedAccess.skinFunction
skin([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, matid, rgba, inflate, vertadr, vertnum, texcoordadr, faceadr, facenum, boneadr, bonenum)

MuJoCo.Wrappers.NamedAccess.tendonFunction
tendon([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, wrapadr, wrapnum, Jrownnz, Jrowadr, J_colind, length, J, velocity)

MuJoCo.Wrappers.NamedAccess.texFunction
tex([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, type, height, width, adr)

MuJoCo.Wrappers.NamedAccess.tupleFunction
tuple([model, data], [name, index])

Creates an object with access to views of the supplied model or data object, based either on an index or a name. Index refers to MuJoCo IDs, which start at 0. Properties available are: (id, name, adr, size)