LibMuJoCo API
Auto-generated bindings for the MuJoCo C library.
MuJoCo.LibMuJoCo.mjContact_
— TypemjContact
Fields
dist
: distance between nearest points; neg: penetrationpos
: position of contact point: midpoint between geomsframe
: normal is in [0-2], points from geom[0] to geom[1]includemargin
: include if dist<includemargin=margin-gapfriction
: tangent1, 2, spin, roll1, 2solref
: constraint solver reference, normal directionsolreffriction
: constraint solver reference, friction directionssolimp
: constraint solver impedancemu
: friction of regularized cone, set by mj_makeConstraintH
: cone Hessian, set by mj_constraintUpdatedim
: contact space dimensionality: 1, 3, 4 or 6geom1
: id of geom 1; deprecated, use geom[0]geom2
: id of geom 2; deprecated, use geom[1]geom
: geom ids; -1 for flexflex
: flex ids; -1 for geomelem
: element ids; -1 for geom or flex vertexvert
: vertex ids; -1 for geom or flex elementexclude
: 0: include, 1: in gap, 2: fused, 3: no dofsefc_address
: address in efc; -1: not included
MuJoCo.LibMuJoCo.mjData_
— TypemjData
Fields
narena
: size of the arena in bytes (inclusive of the stack)nbuffer
: size of main buffer in bytesnplugin
: number of plugin instancespstack
: first available mjtNum address in stackpbase
: value of pstack when mj_markStack was last calledparena
: first available byte in arenamaxuse_stack
: maximum stack allocation in bytesmaxuse_threadstack
: maximum stack allocation per thread in bytesmaxuse_arena
: maximum arena allocation in bytesmaxuse_con
: maximum number of contactsmaxuse_efc
: maximum number of scalar constraintswarning
: warning statisticstimer
: timer statisticssolver
: solver statistics per island, per iterationsolver_nisland
: number of islands processed by solversolver_niter
: number of solver iterations, per islandsolver_nnz
: number of non-zeros in Hessian or efc_AR, per islandsolver_fwdinv
: forward-inverse comparison: qfrc, efcne
: number of equality constraintsnf
: number of friction constraintsnl
: number of limit constraintsnefc
: number of constraintsnnzJ
: number of non-zeros in constraint Jacobianncon
: number of detected contactsnisland
: number of detected constraint islandstime
: simulation timeenergy
: potential, kinetic energybuffer
: main buffer; all pointers point in it (nbuffer bytes)arena
: arena+stack buffer (narena 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)eq_active
: enable/disable constraints (neq x 1)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 (rot:lin) (nv x 6)cinert
: com-based body inertia and mass (nbody x 10)flexvert_xpos
: Cartesian flex vertex positions (nflexvert x 3)flexelem_aabb
: flex element bounding boxes (center, size) (nflexelem x 6)flexedge_J_rownnz
: number of non-zeros in Jacobian row (nflexedge x 1)flexedge_J_rowadr
: row start address in colind array (nflexedge x 1)flexedge_J_colind
: column indices in sparse Jacobian (nflexedge x nv)flexedge_J
: flex edge Jacobian (nflexedge x nv)flexedge_length
: flex edge lengths (nflexedge x 1)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_J
: tendon Jacobian (ntendon x nv)ten_length
: tendon lengths (ntendon x 1)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_aabb_dyn
: global bounding box (center, size) (nbvhdynamic x 6)bvh_active
: volume has been added to collisions (nbvh x 1)flexedge_velocity
: flex edge velocities (nflexedge x 1)ten_velocity
: tendon velocities (ntendon x 1)actuator_velocity
: actuator velocities (nu x 1)cvel
: com-based velocity (rot:lin) (nbody x 6)cdof_dot
: time-derivative of cdof (rot:lin) (nv x 6)qfrc_bias
: C(qpos,qvel) (nv x 1)qfrc_spring
: passive spring force (nv x 1)qfrc_damper
: passive damper force (nv x 1)qfrc_gravcomp
: passive gravity compensation force (nv x 1)qfrc_fluid
: passive fluid force (nv x 1)qfrc_passive
: total passive force (nv 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_actuatorcacc
: 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)tendon_efcadr
: first efc address involving tendon; -1: none (ntendon x 1)dof_island
: island id of this dof; -1: none (nv x 1)island_dofnum
: number of dofs in island (nisland x 1)island_dofadr
: start address in island_dofind (nisland x 1)island_dofind
: island dof indices; -1: none (nv x 1)dof_islandind
: dof island indices; -1: none (nv x 1)efc_island
: island id of this constraint (nefc x 1)island_efcnum
: number of constraints in island (nisland x 1)island_efcadr
: start address in island_efcind (nisland x 1)island_efcind
: island constraint indices (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)efc_vel
: velocity in constraint space: J*qvel (nefc x 1)efc_aref
: reference pseudo-acceleration (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)threadpool
: ThreadPool for multithreaded operations
MuJoCo.LibMuJoCo.mjLROpt_
— TypemjLROpt
Fields
mode
: which actuators to process (mjtLRMode)useexisting
: use existing length range if availableuselimit
: use joint and tendon limits if availableaccel
: target acceleration used to compute forcemaxforce
: maximum force; 0: no limittimeconst
: time constant for velocity reduction; min 0.01timestep
: simulation timestep; 0: use mjOption.timestepinttotal
: total simulation time intervalinterval
: evaluation time interval (at the end)tolrange
: convergence tolerance (relative to range)
MuJoCo.LibMuJoCo.mjModel_
— TypemjModel
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 bodiesnbvh
: number of total bounding volumes in all bodiesnbvhstatic
: number of static bounding volumes (aabb stored in mjModel)nbvhdynamic
: number of dynamic bounding volumes (aabb stored in mjData)njnt
: number of jointsngeom
: number of geomsnsite
: number of sitesncam
: number of camerasnlight
: number of lightsnflex
: number of flexesnflexvert
: number of vertices in all flexesnflexedge
: number of edges in all flexesnflexelem
: number of elements in all flexesnflexelemdata
: number of element vertex ids in all flexesnflexshelldata
: number of shell fragment vertex ids in all flexesnflexevpair
: number of element-vertex pairs in all flexesnflextexcoord
: number of vertices with texture coordinatesnmesh
: number of meshesnmeshvert
: number of vertices in all meshesnmeshnormal
: number of normals in all meshesnmeshtexcoord
: number of texcoords in all meshesnmeshface
: number of triangular faces in all meshesnmeshgraph
: number of ints in mesh auxiliary datanskin
: number of skinsnskinvert
: number of vertices in all skinsnskintexvert
: number of vertiex with texcoords in all skinsnskinface
: number of triangular faces in all skinsnskinbone
: number of bones in all skinsnskinbonevert
: number of vertices in all skin bonesnhfield
: number of heightfieldsnhfielddata
: number of data points in all heightfieldsntex
: number of texturesntexdata
: number of bytes in texture rgb datanmat
: number of materialsnpair
: number of predefined geom pairsnexclude
: number of excluded geom pairsneq
: number of equality constraintsntendon
: number of tendonsnwrap
: number of wrap objects in all tendon pathsnsensor
: number of sensorsnnumeric
: number of numeric custom fieldsnnumericdata
: number of mjtNums in all numeric fieldsntext
: number of text custom fieldsntextdata
: number of mjtBytes in all text fieldsntuple
: number of tuple custom fieldsntupledata
: number of objects in all tuple fieldsnkey
: number of keyframesnmocap
: number of mocap bodiesnplugin
: number of plugin instancesnpluginattr
: number of chars in all plugin config attributesnuser_body
: number of mjtNums in body_usernuser_jnt
: number of mjtNums in jnt_usernuser_geom
: number of mjtNums in geom_usernuser_site
: number of mjtNums in site_usernuser_cam
: number of mjtNums in cam_usernuser_tendon
: number of mjtNums in tendon_usernuser_actuator
: number of mjtNums in actuator_usernuser_sensor
: number of mjtNums in sensor_usernnames
: number of chars in all namesnnames_map
: number of slots in the names hash mapnpaths
: number of chars in all pathsnM
: number of non-zeros in sparse inertia matrixnD
: number of non-zeros in sparse dof-dof matrixnB
: number of non-zeros in sparse body-dof matrixntree
: number of kinematic trees under world bodyngravcomp
: number of bodies with nonzero gravcompnemax
: number of potential equality-constraint rowsnjmax
: number of available rows in constraint Jacobiannconmax
: number of potential contacts in contact listnuserdata
: number of mjtNums reserved for the usernsensordata
: number of mjtNums in sensor data vectornpluginstate
: number of mjtNums in plugin state vectornarena
: number of bytes in the mjData arena (inclusive of stack)nbuffer
: number of bytes in bufferopt
: physics optionsvis
: visualization optionsstat
: model statisticsbuffer
: 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_treeid
: id of body's kinematic tree; -1: static (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
: 1: diag M; 2: diag M, sliders only (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_margin
: MAX over all geom margins (nbody x 1)body_user
: user data (nbody x nuser_body)body_plugin
: plugin instance id; -1: not in use (nbody x 1)body_contype
: OR over all geom contypes (nbody x 1)body_conaffinity
: OR over all geom conaffinities (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_nodeid
: geom or elem id of node; -1: non-leaf (nbvh x 1)bvh_aabb
: local bounding box (center, size) (nbvhstatic 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_actgravcomp
: is gravcomp force applied via actuators (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_treeid
: id of dof's kinematic tree (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_plugin
: plugin instance id; -1: not in use (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_resolution
: [width, height] in pixels (ncam x 2)cam_fovy
: y-field of view (deg) (ncam x 1)cam_intrinsic
: focal length; principal pointcam_sensorsize
: sensor size (ncam x 2)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_bulbradius
: light radius for soft 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)flex_contype
: flex contact type (nflex x 1)flex_conaffinity
: flex contact affinity (nflex x 1)flex_condim
: contact dimensionality (1, 3, 4, 6) (nflex x 1)flex_priority
: flex contact priority (nflex x 1)flex_solmix
: mix coef for solref/imp in contact pair (nflex x 1)flex_solref
: constraint solver reference: contact (nflex x mjNREF)flex_solimp
: constraint solver impedance: contact (nflex x mjNIMP)flex_friction
: friction for (slide, spin, roll) (nflex x 3)flex_margin
: detect contact if dist<margin(nflex x 1)flex_gap
: include in solver if dist<margin-gap (nflex x 1)flex_internal
: internal flex collision enabled (nflex x 1)flex_selfcollide
: self collision mode (mjtFlexSelf) (nflex x 1)flex_activelayers
: number of active element layers, 3D only (nflex x 1)flex_dim
: 1: lines, 2: triangles, 3: tetrahedra (nflex x 1)flex_matid
: material id for rendering (nflex x 1)flex_group
: group for visibility (nflex x 1)flex_vertadr
: first vertex address (nflex x 1)flex_vertnum
: number of vertices (nflex x 1)flex_edgeadr
: first edge address (nflex x 1)flex_edgenum
: number of edges (nflex x 1)flex_elemadr
: first element address (nflex x 1)flex_elemnum
: number of elements (nflex x 1)flex_elemdataadr
: first element vertex id address (nflex x 1)flex_shellnum
: number of shells (nflex x 1)flex_shelldataadr
: first shell data address (nflex x 1)flex_evpairadr
: first evpair address (nflex x 1)flex_evpairnum
: number of evpairs (nflex x 1)flex_texcoordadr
: address in flex_texcoord; -1: none (nflex x 1)flex_vertbodyid
: vertex body ids (nflexvert x 1)flex_edge
: edge vertex ids (2 per edge) (nflexedge x 2)flex_elem
: element vertex ids (dim+1 per elem) (nflexelemdata x 1)flex_elemlayer
: element distance from surface, 3D only (nflexelem x 1)flex_shell
: shell fragment vertex ids (dim per frag) (nflexshelldata x 1)flex_evpair
: (element, vertex) collision pairs (nflexevpair x 2)flex_vert
: vertex positions in local body frames (nflexvert x 3)flex_xvert0
: Cartesian vertex positions in qpos0 (nflexvert x 3)flexedge_length0
: edge lengths in qpos0 (nflexedge x 1)flexedge_invweight0
: edge inv. weight in qpos0 (nflexedge x 1)flex_radius
: radius around primitive element (nflex x 1)flex_edgestiffness
: edge stiffness (nflex x 1)flex_edgedamping
: edge damping (nflex x 1)flex_edgeequality
: is edge equality constraint defined (nflex x 1)flex_rigid
: are all verices in the same body (nflex x 1)flexedge_rigid
: are both edge vertices in same body (nflexedge x 1)flex_centered
: are all vertex coordinates (0,0,0) (nflex x 1)flex_flatskin
: render flex skin with flat shading (nflex x 1)flex_bvhadr
: address of bvh root; -1: no bvh (nflex x 1)flex_bvhnum
: number of bounding volumes (nflex x 1)flex_rgba
: rgba when material is omitted (nflex x 4)flex_texcoord
: vertex texture coordinates (nflextexcoord x 2)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)mesh_scale
: scaling applied to asset vertices (nmesh x 3)mesh_pos
: translation applied to asset vertices (nmesh x 3)mesh_quat
: rotation applied to asset vertices (nmesh x 4)mesh_pathadr
: address of asset path for mesh; -1: none (nmesh 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)skin_pathadr
: address of asset path for skin; -1: none (nskin 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)hfield_pathadr
: address of hfield asset path; -1: none (nhfield 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)tex_pathadr
: address of texture asset path; -1: none (ntex 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_metallic
: metallic coef (nmat x 1)mat_roughness
: roughness coef (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<<16 + body2 (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<<16 + body2 (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_active0
: initial enable/disable constraint state (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_actearly
: step activation before force (nu x 1)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_flexadr
: flex name pointers (nflex 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)paths
: paths to assets, 0-terminated (npaths x 1)
MuJoCo.LibMuJoCo.mjOption_
— TypemjOption
Fields
timestep
: timestepapirate
: update rate for remote API (Hz)impratio
: ratio of friction-to-normal contact impedancetolerance
: main solver tolerancels_tolerance
: CG/Newton linesearch tolerancenoslip_tolerance
: noslip solver tolerancempr_tolerance
: MPR solver tolerancegravity
: gravitational accelerationwind
: wind (for lift, drag and viscosity)magnetic
: global magnetic fluxdensity
: density of mediumviscosity
: viscosity of mediumo_margin
: margino_solref
: solrefo_solimp
: solimpo_friction
: frictionintegrator
: integration mode (mjtIntegrator)cone
: type of friction cone (mjtCone)jacobian
: type of Jacobian (mjtJacobian)solver
: solver algorithm (mjtSolver)iterations
: maximum number of main solver iterationsls_iterations
: maximum number of CG/Newton linesearch iterationsnoslip_iterations
: maximum number of noslip solver iterationsmpr_iterations
: maximum number of MPR solver iterationsdisableflags
: bit flags for disabling standard featuresenableflags
: bit flags for enabling optional featuresdisableactuator
: bit flags for disabling actuators by group idsdf_initpoints
: number of starting points for gradient descentsdf_iterations
: max number of iterations for gradient descent
MuJoCo.LibMuJoCo.mjSolverStat_
— TypemjSolverStat
Fields
improvement
: cost reduction, scaled by 1/trace(M(qpos0))gradient
: gradient norm (primal only, scaled)lineslope
: slope in linesearchnactive
: number of active constraintsnchange
: number of constraint state changesneval
: number of cost evaluations in line searchnupdate
: number of Cholesky updates in line search
MuJoCo.LibMuJoCo.mjStatistic_
— TypemjStatistic
Fields
meaninertia
: mean diagonal inertiameanmass
: mean body massmeansize
: mean body sizeextent
: spatial extentcenter
: center of model
MuJoCo.LibMuJoCo.mjTask_
— TypemjTask
Fields
func
: pointer to the function that implements the taskargs
: arguments to funcstatus
: status of the task
MuJoCo.LibMuJoCo.mjThreadPool_
— TypemjThreadPool
Fields
nworker
: number of workers in the pool
MuJoCo.LibMuJoCo.mjTimerStat_
— TypemjTimerStat
Fields
duration
: cumulative durationnumber
: how many times was timer called
MuJoCo.LibMuJoCo.mjUI_
— TypemjUI
Fields
spacing
: UI theme spacingcolor
: UI theme colorpredicate
: callback to set item state programmaticallyuserdata
: pointer to user data (passed to predicate)rectid
: index of this ui rectangle in mjuiStateauxid
: aux buffer index of this uiradiocol
: number of radio columns (0 defaults to 2)width
: widthheight
: current heigthmaxheight
: height when all sections openscroll
: scroll from top of UImousesect
: 0: none, -1: scroll, otherwise 1+sectionmouseitem
: item within sectionmousehelp
: help button down: print shortcutseditsect
: 0: none, otherwise 1+sectionedititem
: item within sectioneditcursor
: cursor positioneditscroll
: horizontal scrolledittext
: current texteditchanged
: pointer to changed edit in last mjui_eventnsect
: number of sections in usesect
: preallocated array of sections
MuJoCo.LibMuJoCo.mjVFS_
— TypemjVFS
Fields
nfile
: number of files presentfilename
: file name without pathfilesize
: file size in bytesfiledata
: buffer with file datafilestamp
: checksum of the file data
MuJoCo.LibMuJoCo.mjVisual_
— TypemjVisual
MuJoCo.LibMuJoCo.mjWarningStat_
— TypemjWarningStat
Fields
lastinfo
: info from last warningnumber
: how many times was warning raised
MuJoCo.LibMuJoCo.mjrContext_
— TypemjrContext
Fields
lineWidth
: line width for wireframe renderingshadowClip
: clipping radius for directional lightsshadowScale
: fraction of light cutoff for spot lightsfogStart
: fog start = stat.extent * vis.map.fogstartfogEnd
: fog end = stat.extent * vis.map.fogendfogRGBA
: fog rgbashadowSize
: size of shadow map textureoffWidth
: width of offscreen bufferoffHeight
: height of offscreen bufferoffSamples
: number of offscreen buffer multisamplesfontScale
: font scaleauxWidth
: auxiliary buffer widthauxHeight
: auxiliary buffer heightauxSamples
: auxiliary buffer multisamplesoffFBO
: offscreen framebuffer objectoffFBO_r
: offscreen framebuffer for resolving multisamplesoffColor
: offscreen color bufferoffColor_r
: offscreen color buffer for resolving multisamplesoffDepthStencil
: offscreen depth and stencil bufferoffDepthStencil_r
: offscreen depth and stencil buffer for resolving multisamplesshadowFBO
: shadow map framebuffer objectshadowTex
: shadow map textureauxFBO
: auxiliary framebuffer objectauxFBO_r
: auxiliary framebuffer object for resolvingauxColor
: auxiliary color bufferauxColor_r
: auxiliary color buffer for resolvingntexture
: number of allocated texturestextureType
: type of texture (mjtTexture) (ntexture)texture
: texture namesbasePlane
: all planes from modelbaseMesh
: all meshes from modelbaseHField
: all hfields from modelbaseBuiltin
: all buildin geoms, with quality from modelbaseFontNormal
: normal fontbaseFontShadow
: shadow fontbaseFontBig
: big fontrangePlane
: all planes from modelrangeMesh
: all meshes from modelrangeHField
: all hfields from modelrangeBuiltin
: all builtin geoms, with quality from modelrangeFont
: all characters in fontnskin
: number of skinsskinvertVBO
: 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 shadowcharWidthBig
: chacarter widths: bigcharHeight
: character heights: normal and shadowcharHeightBig
: character heights: bigglInitialized
: is OpenGL initializedwindowAvailable
: is default/window framebuffer availablewindowSamples
: number of samples for default/window framebufferwindowStereo
: is stereo available for default/window framebufferwindowDoublebuffer
: is default/window framebuffer double bufferedcurrentBuffer
: currently active framebuffer: mjFBWINDOW or mjFBOFFSCREENreadPixelFormat
: default color pixel format for mjr_readPixelsreadDepthMap
: depth mapping: mjDEPTHZERONEAR or mjDEPTHZEROFAR
MuJoCo.LibMuJoCo.mjrRect_
— TypemjrRect
Fields
left
: left (usually 0)bottom
: bottom (usually 0)width
: width (usually buffer width)height
: height (usually buffer height)
MuJoCo.LibMuJoCo.mjuiDef_
— TypemjuiDef
Fields
type
: type (mjtItem); -1: sectionname
: namestate
: statepdata
: pointer to dataother
: string with type-specific properties
MuJoCo.LibMuJoCo.mjuiItem_
— TypemjuiItem
Fields
type
: type (mjtItem)name
: namestate
: 0: disable, 1: enable, 2+: use predicatepdata
: data pointer (type-specific)sectionid
: id of section containing itemitemid
: id of item within sectionrect
: rectangle occupied by item
MuJoCo.LibMuJoCo.mjuiSection_
— TypemjuiSection
Fields
name
: namestate
: 0: closed, 1: openmodifier
: 0: none, 1: control, 2: shift; 4: altshortcut
: shortcut key; 0: undefinednitem
: number of items in useitem
: preallocated array of itemsrtitle
: rectangle occupied by titlercontent
: rectangle occupied by content
MuJoCo.LibMuJoCo.mjuiState_
— TypemjuiState
Fields
nrect
: number of rectangles usedrect
: rectangles (index 0: entire window)userdata
: pointer to user data (for callbacks)type
: (type mjtEvent)left
: is left button downright
: is right button downmiddle
: is middle button downdoubleclick
: is last press a double clickbutton
: which button was pressed (mjtButton)buttontime
: time of last button pressx
: x positiony
: y positiondx
: x displacementdy
: y displacementsx
: x scrollsy
: y scrollcontrol
: is control downshift
: is shift downalt
: is alt downkey
: which key was pressedkeytime
: time of last key pressmouserect
: which rectangle contains mousedragrect
: which rectangle is dragged with mousedragbutton
: which button started drag (mjtButton)dropcount
: number of files droppeddroppaths
: paths to files dropped
MuJoCo.LibMuJoCo.mjuiThemeColor_
— TypemjuiThemeColor
Fields
master
: master backgroundthumb
: scrollbar thumbsecttitle
: section titlesectfont
: section fontsectsymbol
: section symbolsectpane
: section paneshortcut
: shortcut backgroundfontactive
: font activefontinactive
: font inactivedecorinactive
: decor inactivedecorinactive2
: inactive slider color 2button
: buttoncheck
: checkradio
: radioselect
: selectselect2
: select paneslider
: sliderslider2
: slider color 2edit
: editedit2
: edit invalidcursor
: edit cursor
MuJoCo.LibMuJoCo.mjuiThemeSpacing_
— TypemjuiThemeSpacing
Fields
total
: total widthscroll
: scrollbar widthlabel
: label widthsection
: section gapitemside
: item side gapitemmid
: item middle gapitemver
: item vertical gaptexthor
: text horizontal gaptextver
: text vertical gaplinescroll
: number of pixels to scrollsamples
: number of multisamples
MuJoCo.LibMuJoCo.mjvCamera_
— TypemjvCamera
Fields
type
: camera type (mjtCamera)fixedcamid
: fixed camera idtrackbodyid
: body id to tracklookat
: lookat pointdistance
: distance to lookat point or tracked bodyazimuth
: camera azimuth (deg)elevation
: camera elevation (deg)
MuJoCo.LibMuJoCo.mjvFigure_
— TypemjvFigure
Fields
flg_legend
: show legendflg_ticklabel
: show grid tick labels (x,y)flg_extend
: automatically extend axis ranges to fit dataflg_barplot
: isolated line segments (i.e. GL_LINES)flg_selection
: vertical selection lineflg_symmetric
: symmetric y-axislinewidth
: line widthgridwidth
: grid line widthgridsize
: number of grid points in (x,y)gridrgb
: grid line rgbfigurergba
: figure color and alphapanergba
: pane color and alphalegendrgba
: legend color and alphatextrgb
: text colorlinergb
: line colorsrange
: axis ranges; (min>=max) automaticxformat
: x-tick label format for sprintfyformat
: y-tick label format for sprintfminwidth
: string used to determine min y-tick widthtitle
: figure title; subplots separated with 2+ spacesxlabel
: x-axis labellinename
: line names for legendlegendoffset
: number of lines to offset legendsubplot
: selected subplot (for title rendering)highlight
: if point is in legend rect, highlight linehighlightid
: if id>=0 and no point, highlight idselection
: selection line x-valuelinepnt
: number of points in line; (0) disablelinedata
: line data (x,y)xaxispixel
: range of x-axis in pixelsyaxispixel
: range of y-axis in pixelsxaxisdata
: range of x-axis in data unitsyaxisdata
: range of y-axis in data units
MuJoCo.LibMuJoCo.mjvGLCamera_
— TypemjvGLCamera
Fields
pos
: positionforward
: forward directionup
: up directionfrustum_center
: hor. center (left,right set to match aspect)frustum_width
: width (not used for rendering)frustum_bottom
: bottomfrustum_top
: topfrustum_near
: nearfrustum_far
: far
MuJoCo.LibMuJoCo.mjvGeom_
— TypemjvGeom
Fields
type
: geom type (mjtGeom)dataid
: mesh, hfield or plane id; -1: noneobjtype
: mujoco object type; mjOBJ_UNKNOWN for decorobjid
: mujoco object id; -1 for decorcategory
: visual categorytexid
: texture id; -1: no texturetexuniform
: uniform cube mappingtexcoord
: mesh or flex geom has texture coordinatessegid
: segmentation id; -1: not showntexrepeat
: texture repetition for 2D mappingsize
: size parameterspos
: Cartesian positionmat
: Cartesian orientationrgba
: color and transparencyemission
: emission coefspecular
: specular coefshininess
: shininess coefreflectance
: reflectance coeflabel
: text labelcamdist
: distance to camera (used by sorter)modelrbound
: geom rbound from model, 0 if not model geomtransparent
: treat geom as transparent
MuJoCo.LibMuJoCo.mjvLight_
— TypemjvLight
Fields
pos
: position rel. to body framedir
: direction rel. to body frameattenuation
: OpenGL attenuation (quadratic model)cutoff
: OpenGL cutoffexponent
: OpenGL exponentambient
: ambient rgb (alpha=1)diffuse
: diffuse rgb (alpha=1)specular
: specular rgb (alpha=1)headlight
: headlightdirectional
: directional lightcastshadow
: does light cast shadowsbulbradius
: bulb radius for soft shadows
MuJoCo.LibMuJoCo.mjvOption_
— TypemjvOption
Fields
label
: what objects to label (mjtLabel)frame
: which frame to show (mjtFrame)geomgroup
: geom visualization by groupsitegroup
: site visualization by groupjointgroup
: joint visualization by grouptendongroup
: tendon visualization by groupactuatorgroup
: actuator visualization by groupflexgroup
: flex visualization by groupskingroup
: skin visualization by groupflags
: visualization flags (indexed by mjtVisFlag)bvh_depth
: depth of the bounding volume hierarchy to be visualizedflex_layer
: element layer to be visualized for 3D flex
MuJoCo.LibMuJoCo.mjvPerturb_
— TypemjvPerturb
Fields
select
: selected body id; non-positive: noneflexselect
: selected flex id; negative: noneskinselect
: selected skin id; negative: noneactive
: perturbation bitmask (mjtPertBit)active2
: secondary perturbation bitmask (mjtPertBit)refpos
: reference position for selected objectrefquat
: reference orientation for selected objectrefselpos
: reference position for selection pointlocalpos
: selection point in object coordinateslocalmass
: spatial inertia at selection pointscale
: relative mouse motion-to-space scaling (set by initPerturb)
MuJoCo.LibMuJoCo.mjvSceneState_
— TypemjvSceneState
Fields
nbuffer
: size of the buffer in bytesbuffer
: heap-allocated memory for all arrays in this structmaxgeom
: maximum number of mjvGeom supported by this state objectscratch
: scratch space for vis geoms inserted by the user and plugins
MuJoCo.LibMuJoCo.mjvScene_
— TypemjvScene
Fields
maxgeom
: size of allocated geom bufferngeom
: number of geoms currently in buffergeoms
: buffer for geoms (ngeom)geomorder
: buffer for ordering geoms by distance to camera (ngeom)nflex
: number of flexesflexedgeadr
: address of flex edges (nflex)flexedgenum
: number of edges in flex (nflex)flexvertadr
: address of flex vertices (nflex)flexvertnum
: number of vertices in flex (nflex)flexfaceadr
: address of flex faces (nflex)flexfacenum
: number of flex faces allocated (nflex)flexfaceused
: number of flex faces currently in use (nflex)flexedge
: flex edge data (2*nflexedge)flexvert
: flex vertices (3*nflexvert)flexface
: flex faces vertices (9*sum(flexfacenum))flexnormal
: flex face normals (9*sum(flexfacenum))flextexcoord
: flex face texture coordinates (6*sum(flexfacenum))flexvertopt
: copy of mjVIS_FLEXVERT mjvOption flagflexedgeopt
: copy of mjVIS_FLEXEDGE mjvOption flagflexfaceopt
: copy of mjVIS_FLEXFACE mjvOption flagflexskinopt
: copy of mjVIS_FLEXSKIN mjvOption flagnskin
: number of skinsskinfacenum
: number of faces in skin (nskin)skinvertadr
: address of skin vertices (nskin)skinvertnum
: number of vertices in skin (nskin)skinvert
: skin vertex data (3*nskinvert)skinnormal
: skin normal data (3*nskinvert)nlight
: number of lights currently in bufferlights
: buffer for lights (nlight)camera
: left and right cameraenabletransform
: enable model transformationtranslate
: model translationrotate
: model quaternion rotationscale
: model scalingstereo
: stereoscopic rendering (mjtStereo)flags
: rendering flags (indexed by mjtRndFlag)framewidth
: frame pixel width; 0: disable framingframergb
: frame color
MuJoCo.LibMuJoCo.mj_Euler
— Methodmj_Euler(m, d)
Euler integrator, semi-implicit in velocity.
MuJoCo.LibMuJoCo.mj_RungeKutta
— Methodmj_RungeKutta(m, d, N)
Runge-Kutta explicit order-N integrator.
MuJoCo.LibMuJoCo.mj_addBufferVFS
— Methodmj_addBufferVFS(vfs, name, buffer, nbuffer)
Add file to VFS from buffer, return 0: success, 1: full, 2: repeated name, -1: failed to load.
MuJoCo.LibMuJoCo.mj_addContact
— Methodmj_addContact(m, d, con)
Add contact to d->contact list; return 0 if success; 1 if buffer full.
MuJoCo.LibMuJoCo.mj_addFileVFS
— Methodmj_addFileVFS(vfs, directory, filename)
Add file to VFS, return 0: success, 1: full, 2: repeated name, -1: failed to load.
MuJoCo.LibMuJoCo.mj_addM
— Methodmj_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_angmomMat
— Methodmj_angmomMat(m, d, mat, body)
Compute subtree angular momentum matrix.
MuJoCo.LibMuJoCo.mj_applyFT
— Methodmj_applyFT(m, d, force, torque, point, body, qfrc_target)
Apply Cartesian force and torque (outside xfrc_applied mechanism).
MuJoCo.LibMuJoCo.mj_camlight
— Methodmj_camlight(m, d)
Compute camera and light positions and orientations.
MuJoCo.LibMuJoCo.mj_checkAcc
— Methodmj_checkAcc(m, d)
Check qacc, reset if any element is too big or nan.
MuJoCo.LibMuJoCo.mj_checkPos
— Methodmj_checkPos(m, d)
Check qpos, reset if any element is too big or nan.
MuJoCo.LibMuJoCo.mj_checkVel
— Methodmj_checkVel(m, d)
Check qvel, reset if any element is too big or nan.
MuJoCo.LibMuJoCo.mj_collision
— Methodmj_collision(m, d)
Run collision detection.
MuJoCo.LibMuJoCo.mj_comPos
— Methodmj_comPos(m, d)
Map inertias and motion dofs to global frame centered at CoM.
MuJoCo.LibMuJoCo.mj_comVel
— Methodmj_comVel(m, d)
Compute cvel, cdof_dot.
MuJoCo.LibMuJoCo.mj_compareFwdInv
— Methodmj_compareFwdInv(m, d)
Compare forward and inverse dynamics, save results in fwdinv.
MuJoCo.LibMuJoCo.mj_constraintUpdate
— Methodmj_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_contactForce
— Methodmj_contactForce(m, d, id, result)
Extract 6D force:torque given contact id, in the contact frame.
MuJoCo.LibMuJoCo.mj_copyData
— Methodmj_copyData(dest, m, src)
Copy mjData. m is only required to contain the size fields from MJMODEL_INTS.
MuJoCo.LibMuJoCo.mj_copyModel
— Methodmj_copyModel(dest, src)
Copy mjModel, allocate new if dest is NULL.
MuJoCo.LibMuJoCo.mj_crb
— Methodmj_crb(m, d)
Run composite rigid body inertia algorithm (CRB).
MuJoCo.LibMuJoCo.mj_defaultLROpt
— Methodmj_defaultLROpt(opt)
Set default options for length range computation.
MuJoCo.LibMuJoCo.mj_defaultOption
— Methodmj_defaultOption(opt)
Set physics options to default values.
MuJoCo.LibMuJoCo.mj_defaultSolRefImp
— Methodmj_defaultSolRefImp(solref, solimp)
Set solver parameters to default values.
MuJoCo.LibMuJoCo.mj_defaultVFS
— Methodmj_defaultVFS(vfs)
Initialize VFS to empty (no deallocation).
MuJoCo.LibMuJoCo.mj_defaultVisual
— Methodmj_defaultVisual(vis)
Set visual options to default values.
MuJoCo.LibMuJoCo.mj_deleteData
— Methodmj_deleteData(d)
Free memory allocation in mjData.
MuJoCo.LibMuJoCo.mj_deleteFileVFS
— Methodmj_deleteFileVFS(vfs, filename)
Delete file from VFS, return 0: success, -1: not found in VFS.
MuJoCo.LibMuJoCo.mj_deleteModel
— Methodmj_deleteModel(m)
Free memory allocation in model.
MuJoCo.LibMuJoCo.mj_deleteVFS
— Methodmj_deleteVFS(vfs)
Delete all files from VFS.
MuJoCo.LibMuJoCo.mj_differentiatePos
— Methodmj_differentiatePos(m, qvel, dt, qpos1, qpos2)
Compute velocity by finite-differencing two positions.
MuJoCo.LibMuJoCo.mj_energyPos
— Methodmj_energyPos(m, d)
Evaluate position-dependent energy (potential).
MuJoCo.LibMuJoCo.mj_energyVel
— Methodmj_energyVel(m, d)
Evaluate velocity-dependent energy (kinetic).
MuJoCo.LibMuJoCo.mj_factorM
— Methodmj_factorM(m, d)
Compute sparse L'DL factorizaton of inertia matrix.
MuJoCo.LibMuJoCo.mj_findFileVFS
— Methodmj_findFileVFS(vfs, filename)
Return file index in VFS, or -1 if not found in VFS.
MuJoCo.LibMuJoCo.mj_flex
— Methodmj_flex(m, d)
Compute flex-related quantities.
MuJoCo.LibMuJoCo.mj_forward
— Methodmj_forward(m, d)
Forward dynamics: same as mj_step but do not integrate in time.
MuJoCo.LibMuJoCo.mj_forwardSkip
— Methodmj_forwardSkip(m, d, skipstage, skipsensor)
Forward dynamics with skip; skipstage is mjtStage.
MuJoCo.LibMuJoCo.mj_freeLastXML
— Methodmj_freeLastXML()
Free last XML model if loaded. Called internally at each load.
MuJoCo.LibMuJoCo.mj_freeStack
— Methodmj_freeStack(d)
Free the current mjData stack frame. All pointers returned by mjstackAlloc since the last call to mjmarkStack must no longer be used afterwards.
MuJoCo.LibMuJoCo.mj_fullM
— Methodmj_fullM(m, dst, M)
Convert sparse inertia matrix M into full (i.e. dense) matrix.
MuJoCo.LibMuJoCo.mj_fwdAcceleration
— Methodmj_fwdAcceleration(m, d)
Add up all non-constraint forces, compute qacc_smooth.
MuJoCo.LibMuJoCo.mj_fwdActuation
— Methodmj_fwdActuation(m, d)
Compute actuator force qfrc_actuator.
MuJoCo.LibMuJoCo.mj_fwdConstraint
— Methodmj_fwdConstraint(m, d)
Run selected constraint solver.
MuJoCo.LibMuJoCo.mj_fwdPosition
— Methodmj_fwdPosition(m, d)
Run position-dependent computations.
MuJoCo.LibMuJoCo.mj_fwdVelocity
— Methodmj_fwdVelocity(m, d)
Run velocity-dependent computations.
MuJoCo.LibMuJoCo.mj_geomDistance
— Methodmj_geomDistance(m, d, geom1, geom2, distmax, fromto)
Returns smallest signed distance between two geoms and optionally segment from geom1 to geom2.
MuJoCo.LibMuJoCo.mj_getPluginConfig
— Methodmj_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_getState
— Methodmj_getState(m, d, state, spec)
Get state.
MuJoCo.LibMuJoCo.mj_getTotalmass
— Methodmj_getTotalmass(m)
Sum all body masses.
MuJoCo.LibMuJoCo.mj_id2name
— Methodmj_id2name(m, type, id)
Get name of object with the specified mjtObj type and id, returns NULL if name not found.
MuJoCo.LibMuJoCo.mj_implicit
— Methodmj_implicit(m, d)
Implicit-in-velocity integrators.
MuJoCo.LibMuJoCo.mj_integratePos
— Methodmj_integratePos(m, qpos, qvel, dt)
Integrate position with given velocity.
MuJoCo.LibMuJoCo.mj_invConstraint
— Methodmj_invConstraint(m, d)
Apply the analytical formula for inverse constraint dynamics.
MuJoCo.LibMuJoCo.mj_invPosition
— Methodmj_invPosition(m, d)
Run position-dependent computations in inverse dynamics.
MuJoCo.LibMuJoCo.mj_invVelocity
— Methodmj_invVelocity(m, d)
Run velocity-dependent computations in inverse dynamics.
MuJoCo.LibMuJoCo.mj_inverse
— Methodmj_inverse(m, d)
Inverse dynamics: qacc must be set before calling.
MuJoCo.LibMuJoCo.mj_inverseSkip
— Methodmj_inverseSkip(m, d, skipstage, skipsensor)
Inverse dynamics with skip; skipstage is mjtStage.
MuJoCo.LibMuJoCo.mj_isDual
— Methodmj_isDual(m)
Determine type of solver (PGS is dual, CG and Newton are primal).
MuJoCo.LibMuJoCo.mj_isPyramidal
— Methodmj_isPyramidal(m)
Determine type of friction cone.
MuJoCo.LibMuJoCo.mj_isSparse
— Methodmj_isSparse(m)
Determine type of constraint Jacobian.
MuJoCo.LibMuJoCo.mj_island
— Methodmj_island(m, d)
Find constraint islands.
MuJoCo.LibMuJoCo.mj_jac
— Methodmj_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_jacBody
— Methodmj_jacBody(m, d, jacp, jacr, body)
Compute body frame end-effector Jacobian.
MuJoCo.LibMuJoCo.mj_jacBodyCom
— Methodmj_jacBodyCom(m, d, jacp, jacr, body)
Compute body center-of-mass end-effector Jacobian.
MuJoCo.LibMuJoCo.mj_jacGeom
— Methodmj_jacGeom(m, d, jacp, jacr, geom)
Compute geom end-effector Jacobian.
MuJoCo.LibMuJoCo.mj_jacPointAxis
— Methodmj_jacPointAxis(m, d, jacPoint, jacAxis, point, axis, body)
Compute translation end-effector Jacobian of point, and rotation Jacobian of axis.
MuJoCo.LibMuJoCo.mj_jacSite
— Methodmj_jacSite(m, d, jacp, jacr, site)
Compute site end-effector Jacobian.
MuJoCo.LibMuJoCo.mj_jacSubtreeCom
— Methodmj_jacSubtreeCom(m, d, jacp, body)
Compute subtree center-of-mass end-effector Jacobian.
MuJoCo.LibMuJoCo.mj_kinematics
— Methodmj_kinematics(m, d)
Run forward kinematics.
MuJoCo.LibMuJoCo.mj_loadAllPluginLibraries
— Methodmj_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_loadModel
— Methodmj_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_loadPluginLibrary
— Methodmj_loadPluginLibrary(path)
Load a dynamic library. The dynamic library is assumed to register one or more plugins.
MuJoCo.LibMuJoCo.mj_loadXML
— Methodmj_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_local2Global
— Methodmj_local2Global(d, xpos, xmat, pos, quat, body, sameframe)
Map from body local to global Cartesian coordinates.
MuJoCo.LibMuJoCo.mj_makeConstraint
— Methodmj_makeConstraint(m, d)
Construct constraints.
MuJoCo.LibMuJoCo.mj_makeData
— Methodmj_makeData(m)
Allocate mjData corresponding to given model. If the model buffer is unallocated the initial configuration will not be set.
MuJoCo.LibMuJoCo.mj_makeEmptyFileVFS
— Methodmj_makeEmptyFileVFS(vfs, filename, filesize)
deprecated: use mj_copyBufferVFS.
MuJoCo.LibMuJoCo.mj_markStack
— Methodmj_markStack(d)
Mark a new frame on the mjData stack.
MuJoCo.LibMuJoCo.mj_mulJacTVec
— Methodmj_mulJacTVec(m, d, res, vec)
Multiply dense or sparse constraint Jacobian transpose by vector.
MuJoCo.LibMuJoCo.mj_mulJacVec
— Methodmj_mulJacVec(m, d, res, vec)
Multiply dense or sparse constraint Jacobian by vector.
MuJoCo.LibMuJoCo.mj_mulM
— Methodmj_mulM(m, d, res, vec)
Multiply vector by inertia matrix.
MuJoCo.LibMuJoCo.mj_mulM2
— Methodmj_mulM2(m, d, res, vec)
Multiply vector by (inertia matrix)^(1/2).
MuJoCo.LibMuJoCo.mj_multiRay
— Methodmj_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_name2id
— Methodmj_name2id(m, type, name)
Get id of object with the specified mjtObj type and name, returns -1 if id not found.
MuJoCo.LibMuJoCo.mj_normalizeQuat
— Methodmj_normalizeQuat(m, qpos)
Normalize all quaternions in qpos-type vector.
MuJoCo.LibMuJoCo.mj_objectAcceleration
— Methodmj_objectAcceleration(m, d, objtype, objid, res, flg_local)
Compute object 6D acceleration (rot:lin) in object-centered frame, world/local orientation.
MuJoCo.LibMuJoCo.mj_objectVelocity
— Methodmj_objectVelocity(m, d, objtype, objid, res, flg_local)
Compute object 6D velocity (rot:lin) in object-centered frame, world/local orientation.
MuJoCo.LibMuJoCo.mj_passive
— Methodmj_passive(m, d)
Compute qfrc_passive from spring-dampers, gravity compensation and fluid forces.
MuJoCo.LibMuJoCo.mj_printData
— Methodmj_printData(m, d, filename)
Print data to text file.
MuJoCo.LibMuJoCo.mj_printFormattedData
— Methodmj_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_printFormattedModel
— Methodmj_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_printModel
— Methodmj_printModel(m, filename)
Print model to text file.
MuJoCo.LibMuJoCo.mj_printSchema
— Methodmj_printSchema(filename, buffer, buffer_sz, flg_html, flg_pad)
Print internal XML schema as plain text or HTML, with style-padding or .
MuJoCo.LibMuJoCo.mj_projectConstraint
— Methodmj_projectConstraint(m, d)
Compute inverse constraint inertia efc_AR.
MuJoCo.LibMuJoCo.mj_ray
— Methodmj_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_rayHfield
— Methodmj_rayHfield(m, d, geomid, pnt, vec)
Intersect ray with hfield, return nearest distance or -1 if no intersection.
MuJoCo.LibMuJoCo.mj_rayMesh
— Methodmj_rayMesh(m, d, geomid, pnt, vec)
Intersect ray with mesh, return nearest distance or -1 if no intersection.
MuJoCo.LibMuJoCo.mj_referenceConstraint
— Methodmj_referenceConstraint(m, d)
Compute efcvel, efcaref.
MuJoCo.LibMuJoCo.mj_resetCallbacks
— Methodmj_resetCallbacks()
Reset all callbacks to NULL pointers (NULL is the default).
MuJoCo.LibMuJoCo.mj_resetData
— Methodmj_resetData(m, d)
Reset data to defaults.
MuJoCo.LibMuJoCo.mj_resetDataDebug
— Methodmj_resetDataDebug(m, d, debug_value)
Reset data to defaults, fill everything else with debug_value.
MuJoCo.LibMuJoCo.mj_resetDataKeyframe
— Methodmj_resetDataKeyframe(m, d, key)
Reset data. If 0 <= key < nkey, set fields from specified keyframe.
MuJoCo.LibMuJoCo.mj_rne
— Methodmj_rne(m, d, flg_acc, result)
RNE: compute M(qpos)*qacc + C(qpos,qvel); flg_acc=0 removes inertial term.
MuJoCo.LibMuJoCo.mj_rnePostConstraint
— Methodmj_rnePostConstraint(m, d)
RNE with complete data: compute cacc, cfrcext, cfrcint.
MuJoCo.LibMuJoCo.mj_saveLastXML
— Methodmj_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_saveModel
— Methodmj_saveModel(m, filename, buffer, buffer_sz)
Save model to binary MJB file or memory buffer; buffer has precedence when given.
MuJoCo.LibMuJoCo.mj_sensorAcc
— Methodmj_sensorAcc(m, d)
Evaluate acceleration and force-dependent sensors.
MuJoCo.LibMuJoCo.mj_sensorPos
— Methodmj_sensorPos(m, d)
Evaluate position-dependent sensors.
MuJoCo.LibMuJoCo.mj_sensorVel
— Methodmj_sensorVel(m, d)
Evaluate velocity-dependent sensors.
MuJoCo.LibMuJoCo.mj_setConst
— Methodmj_setConst(m, d)
Set constant fields of mjModel, corresponding to qpos0 configuration.
MuJoCo.LibMuJoCo.mj_setLengthRange
— Methodmj_setLengthRange(m, d, index, opt, error, error_sz)
Set actuator_lengthrange for specified actuator; return 1 if ok, 0 if error.
MuJoCo.LibMuJoCo.mj_setState
— Methodmj_setState(m, d, state, spec)
Set state.
MuJoCo.LibMuJoCo.mj_setTotalmass
— Methodmj_setTotalmass(m, newmass)
Scale body masses and inertias to achieve specified total mass.
MuJoCo.LibMuJoCo.mj_sizeModel
— Methodmj_sizeModel(m)
Return size of buffer needed to hold model.
MuJoCo.LibMuJoCo.mj_solveM
— Methodmj_solveM(m, d, x, y, n)
Solve linear system M * x = y using factorization: x = inv(L'DL)*y
MuJoCo.LibMuJoCo.mj_solveM2
— Methodmj_solveM2(m, d, x, y, n)
Half of linear solve: x = sqrt(inv(D))inv(L')y
MuJoCo.LibMuJoCo.mj_stackAllocByte
— Methodmj_stackAllocByte(d, bytes, alignment)
Allocate a number of bytes on mjData stack at a specific alignment. Call mju_error on stack overflow.
MuJoCo.LibMuJoCo.mj_stackAllocInt
— Methodmj_stackAllocInt(d, size)
Allocate array of ints on mjData stack. Call mju_error on stack overflow.
MuJoCo.LibMuJoCo.mj_stackAllocNum
— Methodmj_stackAllocNum(d, size)
Allocate array of mjtNums on mjData stack. Call mju_error on stack overflow.
MuJoCo.LibMuJoCo.mj_stateSize
— Methodmj_stateSize(m, spec)
Return size of state specification.
MuJoCo.LibMuJoCo.mj_step
— Methodmj_step(m, d)
Advance simulation, use control callback to obtain external force and control.
MuJoCo.LibMuJoCo.mj_step1
— Methodmj_step1(m, d)
Advance simulation in two steps: before external force and control is set by user.
MuJoCo.LibMuJoCo.mj_step2
— Methodmj_step2(m, d)
Advance simulation in two steps: after external force and control is set by user.
MuJoCo.LibMuJoCo.mj_subtreeVel
— Methodmj_subtreeVel(m, d)
Sub-tree linear velocity and angular momentum: compute subtreelinvel, subtreeangmom.
MuJoCo.LibMuJoCo.mj_tendon
— Methodmj_tendon(m, d)
Compute tendon lengths, velocities and moment arms.
MuJoCo.LibMuJoCo.mj_transmission
— Methodmj_transmission(m, d)
Compute actuator transmission lengths and moments.
MuJoCo.LibMuJoCo.mj_version
— Methodmj_version()
Return version number: 1.0.2 is encoded as 102.
MuJoCo.LibMuJoCo.mj_versionString
— Methodmj_versionString()
Return the current version of MuJoCo as a null-terminated string.
MuJoCo.LibMuJoCo.mj_warning
— Methodmj_warning(d, warning, info)
High-level warning function: count warnings in mjData, print only the first.
MuJoCo.LibMuJoCo.mjd_inverseFD
— Methodmjd_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_quatIntegrate
— Methodmjd_quatIntegrate(vel, scale, Dquat, Dvel, Dscale)
Derivatives of mju_quatIntegrate.
MuJoCo.LibMuJoCo.mjd_subQuat
— Methodmjd_subQuat(qa, qb, Da, Db)
Derivatives of mju_subQuat.
MuJoCo.LibMuJoCo.mjd_transitionFD
— Methodmjd_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_defaultPlugin
— Methodmjp_defaultPlugin(plugin)
Set default plugin definition.
MuJoCo.LibMuJoCo.mjp_defaultResourceProvider
— Methodmjp_defaultResourceProvider(provider)
Set default resource provider definition.
MuJoCo.LibMuJoCo.mjp_getPlugin
— Methodmjp_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_getPluginAtSlot
— Methodmjp_getPluginAtSlot(slot)
Look up a plugin by the registered slot number that was returned by mjp_registerPlugin.
MuJoCo.LibMuJoCo.mjp_getResourceProvider
— Methodmjp_getResourceProvider(resource_name)
Return the resource provider with the prefix that matches against the resource name. If no match, return NULL.
MuJoCo.LibMuJoCo.mjp_getResourceProviderAtSlot
— Methodmjp_getResourceProviderAtSlot(slot)
Look up a resource provider by slot number returned by mjp_registerResourceProvider. If invalid slot number, return NULL.
MuJoCo.LibMuJoCo.mjp_pluginCount
— Methodmjp_pluginCount()
Return the number of globally registered plugins.
MuJoCo.LibMuJoCo.mjp_registerPlugin
— Methodmjp_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_registerResourceProvider
— Methodmjp_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.mjp_resourceProviderCount
— Methodmjp_resourceProviderCount()
Return the number of globally registered resource providers.
MuJoCo.LibMuJoCo.mjr_addAux
— Methodmjr_addAux(index, width, height, samples, con)
Add Aux buffer with given index to context; free previous Aux buffer.
MuJoCo.LibMuJoCo.mjr_blitAux
— Methodmjr_blitAux(index, src, left, bottom, con)
Blit from Aux buffer to con->currentBuffer.
MuJoCo.LibMuJoCo.mjr_blitBuffer
— Methodmjr_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_changeFont
— Methodmjr_changeFont(fontscale, con)
Change font of existing context.
MuJoCo.LibMuJoCo.mjr_defaultContext
— Methodmjr_defaultContext(con)
Set default mjrContext.
MuJoCo.LibMuJoCo.mjr_drawPixels
— Methodmjr_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_figure
— Methodmjr_figure(viewport, fig, con)
Draw 2D figure.
MuJoCo.LibMuJoCo.mjr_findRect
— Methodmjr_findRect(x, y, nrect, rect)
Find first rectangle containing mouse, -1: not found.
MuJoCo.LibMuJoCo.mjr_finish
— Methodmjr_finish()
Call glFinish.
MuJoCo.LibMuJoCo.mjr_freeContext
— Methodmjr_freeContext(con)
Free resources in custom OpenGL context, set to default.
MuJoCo.LibMuJoCo.mjr_getError
— Methodmjr_getError()
Call glGetError and return result.
MuJoCo.LibMuJoCo.mjr_label
— Methodmjr_label(viewport, font, txt, r, g, b, a, rt, gt, bt, con)
Draw rectangle with centered text.
MuJoCo.LibMuJoCo.mjr_makeContext
— Methodmjr_makeContext(m, con, fontscale)
Allocate resources in custom OpenGL context; fontscale is mjtFontScale.
MuJoCo.LibMuJoCo.mjr_maxViewport
— Methodmjr_maxViewport(con)
Get maximum viewport for active buffer.
MuJoCo.LibMuJoCo.mjr_overlay
— Methodmjr_overlay(font, gridpos, viewport, overlay, overlay2, con)
Draw text overlay; font is mjtFont; gridpos is mjtGridPos.
MuJoCo.LibMuJoCo.mjr_readPixels
— Methodmjr_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_rectangle
— Methodmjr_rectangle(viewport, r, g, b, a)
Draw rectangle.
MuJoCo.LibMuJoCo.mjr_render
— Methodmjr_render(viewport, scn, con)
Render 3D scene.
MuJoCo.LibMuJoCo.mjr_resizeOffscreen
— Methodmjr_resizeOffscreen(width, height, con)
Resize offscreen buffers.
MuJoCo.LibMuJoCo.mjr_restoreBuffer
— Methodmjr_restoreBuffer(con)
Make con->currentBuffer current again.
MuJoCo.LibMuJoCo.mjr_setAux
— Methodmjr_setAux(index, con)
Set Aux buffer for custom OpenGL rendering (call restoreBuffer when done).
MuJoCo.LibMuJoCo.mjr_setBuffer
— Methodmjr_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_text
— Methodmjr_text(font, txt, con, x, y, r, g, b)
Draw text at (x,y) in relative coordinates; font is mjtFont.
MuJoCo.LibMuJoCo.mjr_uploadHField
— Methodmjr_uploadHField(m, con, hfieldid)
Upload height field to GPU, overwriting previous upload if any.
MuJoCo.LibMuJoCo.mjr_uploadMesh
— Methodmjr_uploadMesh(m, con, meshid)
Upload mesh to GPU, overwriting previous upload if any.
MuJoCo.LibMuJoCo.mjr_uploadTexture
— Methodmjr_uploadTexture(m, con, texid)
Upload texture to GPU, overwriting previous upload if any.
MuJoCo.LibMuJoCo.mju_Halton
— Methodmju_Halton(index, base)
Generate Halton sequence.
MuJoCo.LibMuJoCo.mju_L1
— Methodmju_L1(vec, n)
Return L1 norm: sum(abs(vec)).
MuJoCo.LibMuJoCo.mju_add
— Methodmju_add(res, vec1, vec2, n)
Set res = vec1 + vec2.
MuJoCo.LibMuJoCo.mju_add3
— Methodmju_add3(res, vec1, vec2)
Set res = vec1 + vec2.
MuJoCo.LibMuJoCo.mju_addScl
— Methodmju_addScl(res, vec1, vec2, scl, n)
Set res = vec1 + vec2*scl.
MuJoCo.LibMuJoCo.mju_addScl3
— Methodmju_addScl3(res, vec1, vec2, scl)
Set res = vec1 + vec2*scl.
MuJoCo.LibMuJoCo.mju_addTo
— Methodmju_addTo(res, vec, n)
Set res = res + vec.
MuJoCo.LibMuJoCo.mju_addTo3
— Methodmju_addTo3(res, vec)
Set res = res + vec.
MuJoCo.LibMuJoCo.mju_addToScl
— Methodmju_addToScl(res, vec, scl, n)
Set res = res + vec*scl.
MuJoCo.LibMuJoCo.mju_addToScl3
— Methodmju_addToScl3(res, vec, scl)
Set res = res + vec*scl.
MuJoCo.LibMuJoCo.mju_axisAngle2Quat
— Methodmju_axisAngle2Quat(res, axis, angle)
Convert axisAngle to quaternion.
MuJoCo.LibMuJoCo.mju_band2Dense
— Methodmju_band2Dense(res, mat, ntotal, nband, ndense, flg_sym)
Convert banded matrix to dense matrix, fill upper triangle if flg_sym>0.
MuJoCo.LibMuJoCo.mju_bandDiag
— Methodmju_bandDiag(i, ntotal, nband, ndense)
Address of diagonal element i in band-dense matrix representation.
MuJoCo.LibMuJoCo.mju_bandMulMatVec
— Methodmju_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_bindThreadPool
— Methodmju_bindThreadPool(d, thread_pool)
Adds a thread pool to mjData and configures it for multi-threaded use.
MuJoCo.LibMuJoCo.mju_boxQP
— Methodmju_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_boxQPmalloc
— Methodmju_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_cholFactor
— Methodmju_cholFactor(mat, n, mindiag)
Cholesky decomposition: mat = L*L'; return rank, decomposition performed in-place into mat.
MuJoCo.LibMuJoCo.mju_cholFactorBand
— Methodmju_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_cholSolve
— Methodmju_cholSolve(res, mat, vec, n)
Solve (mat*mat') * res = vec, where mat is a Cholesky factor.
MuJoCo.LibMuJoCo.mju_cholSolveBand
— Methodmju_cholSolveBand(res, mat, vec, ntotal, nband, ndense)
Solve (matmat')res = vec where mat is a band-dense Cholesky factor.
MuJoCo.LibMuJoCo.mju_cholUpdate
— Methodmju_cholUpdate(mat, x, n, flg_plus)
Cholesky rank-one update: LL' +/- xx'; return rank.
MuJoCo.LibMuJoCo.mju_clearHandlers
— Methodmju_clearHandlers()
Clear user error and memory handlers.
MuJoCo.LibMuJoCo.mju_clip
— Methodmju_clip(x, min, max)
Clip x to the range [min, max].
MuJoCo.LibMuJoCo.mju_copy
— Methodmju_copy(res, vec, n)
Set res = vec.
MuJoCo.LibMuJoCo.mju_copy3
— Methodmju_copy3(res, data)
Set res = vec.
MuJoCo.LibMuJoCo.mju_copy4
— Methodmju_copy4(res, data)
Set res = vec.
MuJoCo.LibMuJoCo.mju_cross
— Methodmju_cross(res, a, b)
Compute cross-product: res = cross(a, b).
MuJoCo.LibMuJoCo.mju_d2n
— Methodmju_d2n(res, vec, n)
Convert from double to mjtNum.
MuJoCo.LibMuJoCo.mju_decodePyramid
— Methodmju_decodePyramid(force, pyramid, mu, dim)
Convert pyramid representation to contact force.
MuJoCo.LibMuJoCo.mju_defaultTask
— Methodmju_defaultTask(task)
Initialize an mjTask.
MuJoCo.LibMuJoCo.mju_dense2Band
— Methodmju_dense2Band(res, mat, ntotal, nband, ndense)
Convert dense matrix to banded matrix.
MuJoCo.LibMuJoCo.mju_derivQuat
— Methodmju_derivQuat(res, quat, vel)
Compute time-derivative of quaternion, given 3D rotational velocity.
MuJoCo.LibMuJoCo.mju_dist3
— Methodmju_dist3(pos1, pos2)
Return Cartesian distance between 3D vectors pos1 and pos2.
MuJoCo.LibMuJoCo.mju_dot
— Methodmju_dot(vec1, vec2, n)
Return dot-product of vec1 and vec2.
MuJoCo.LibMuJoCo.mju_dot3
— Methodmju_dot3(vec1, vec2)
Return dot-product of vec1 and vec2.
MuJoCo.LibMuJoCo.mju_eig3
— Methodmju_eig3(eigval, eigvec, quat, mat)
Eigenvalue decomposition of symmetric 3x3 matrix, mat = eigvec * diag(eigval) * eigvec'.
MuJoCo.LibMuJoCo.mju_encodePyramid
— Methodmju_encodePyramid(pyramid, force, mu, dim)
Convert contact force to pyramid representation.
MuJoCo.LibMuJoCo.mju_error_i
— Methodmju_error_i(msg, i)
Deprecated: use mju_error.
MuJoCo.LibMuJoCo.mju_error_s
— Methodmju_error_s(msg, text)
Deprecated: use mju_error.
MuJoCo.LibMuJoCo.mju_euler2Quat
— Methodmju_euler2Quat(quat, euler, seq)
Convert sequence of Euler angles (radians) to quaternion. seq[0,1,2] must be in 'xyzXYZ', lower/upper-case mean intrinsic/extrinsic rotations.
MuJoCo.LibMuJoCo.mju_eye
— Methodmju_eye(mat, n)
Set mat to the identity matrix.
MuJoCo.LibMuJoCo.mju_f2n
— Methodmju_f2n(res, vec, n)
Convert from float to mjtNum.
MuJoCo.LibMuJoCo.mju_fill
— Methodmju_fill(res, val, n)
Set res = val.
MuJoCo.LibMuJoCo.mju_free
— Methodmju_free(ptr)
Free memory, using free() by default.
MuJoCo.LibMuJoCo.mju_insertionSort
— Methodmju_insertionSort(list, n)
Insertion sort, resulting list is in increasing order.
MuJoCo.LibMuJoCo.mju_insertionSortInt
— Methodmju_insertionSortInt(list, n)
Integer insertion sort, resulting list is in increasing order.
MuJoCo.LibMuJoCo.mju_isBad
— Methodmju_isBad(x)
Return 1 if nan or abs(x)>mjMAXVAL, 0 otherwise. Used by check functions.
MuJoCo.LibMuJoCo.mju_isZero
— Methodmju_isZero(vec, n)
Return 1 if all elements are 0.
MuJoCo.LibMuJoCo.mju_malloc
— Methodmju_malloc(size)
Allocate memory; byte-align on 64; pad size to multiple of 64.
MuJoCo.LibMuJoCo.mju_mat2Quat
— Methodmju_mat2Quat(quat, mat)
Convert 3D rotation matrix to quaternion.
MuJoCo.LibMuJoCo.mju_max
— Methodmju_max(a, b)
Return max(a,b) with single evaluation of a and b.
MuJoCo.LibMuJoCo.mju_min
— Methodmju_min(a, b)
Return min(a,b) with single evaluation of a and b.
MuJoCo.LibMuJoCo.mju_mulMatMat
— Methodmju_mulMatMat(res, mat1, mat2, r1, c1, c2)
Multiply matrices: res = mat1 * mat2.
MuJoCo.LibMuJoCo.mju_mulMatMatT
— Methodmju_mulMatMatT(res, mat1, mat2, r1, c1, r2)
Multiply matrices, second argument transposed: res = mat1 * mat2'.
MuJoCo.LibMuJoCo.mju_mulMatTMat
— Methodmju_mulMatTMat(res, mat1, mat2, r1, c1, c2)
Multiply matrices, first argument transposed: res = mat1' * mat2.
MuJoCo.LibMuJoCo.mju_mulMatTVec
— Methodmju_mulMatTVec(res, mat, vec, nr, nc)
Multiply transposed matrix and vector: res = mat' * vec.
MuJoCo.LibMuJoCo.mju_mulMatVec
— Methodmju_mulMatVec(res, mat, vec, nr, nc)
Multiply matrix and vector: res = mat * vec.
MuJoCo.LibMuJoCo.mju_mulPose
— Methodmju_mulPose(posres, quatres, pos1, quat1, pos2, quat2)
Multiply two poses.
MuJoCo.LibMuJoCo.mju_mulQuat
— Methodmju_mulQuat(res, quat1, quat2)
Multiply quaternions.
MuJoCo.LibMuJoCo.mju_mulQuatAxis
— Methodmju_mulQuatAxis(res, quat, axis)
Multiply quaternion and axis.
MuJoCo.LibMuJoCo.mju_mulVecMatVec
— Methodmju_mulVecMatVec(vec1, mat, vec2, n)
Multiply square matrix with vectors on both sides: returns vec1' * mat * vec2.
MuJoCo.LibMuJoCo.mju_muscleBias
— Methodmju_muscleBias(len, lengthrange, acc0, prm)
Muscle passive force, prm = (range[2], force, scale, lmin, lmax, vmax, fpmax, fvmax).
MuJoCo.LibMuJoCo.mju_muscleDynamics
— Methodmju_muscleDynamics(ctrl, act, prm)
Muscle activation dynamics, prm = (tauact, taudeact, smoothing_width).
MuJoCo.LibMuJoCo.mju_muscleGain
— Methodmju_muscleGain(len, vel, lengthrange, acc0, prm)
Muscle active force, prm = (range[2], force, scale, lmin, lmax, vmax, fpmax, fvmax).
MuJoCo.LibMuJoCo.mju_n2d
— Methodmju_n2d(res, vec, n)
Convert from mjtNum to double.
MuJoCo.LibMuJoCo.mju_n2f
— Methodmju_n2f(res, vec, n)
Convert from mjtNum to float.
MuJoCo.LibMuJoCo.mju_negPose
— Methodmju_negPose(posres, quatres, pos, quat)
Conjugate pose, corresponding to the opposite spatial transformation.
MuJoCo.LibMuJoCo.mju_negQuat
— Methodmju_negQuat(res, quat)
Conjugate quaternion, corresponding to opposite rotation.
MuJoCo.LibMuJoCo.mju_norm
— Methodmju_norm(res, n)
Return vector length (without normalizing vector).
MuJoCo.LibMuJoCo.mju_norm3
— Methodmju_norm3(vec)
Return vector length (without normalizing the vector).
MuJoCo.LibMuJoCo.mju_normalize
— Methodmju_normalize(res, n)
Normalize vector, return length before normalization.
MuJoCo.LibMuJoCo.mju_normalize3
— Methodmju_normalize3(vec)
Normalize vector, return length before normalization.
MuJoCo.LibMuJoCo.mju_normalize4
— Methodmju_normalize4(vec)
Normalize vector, return length before normalization.
MuJoCo.LibMuJoCo.mju_printMat
— Methodmju_printMat(mat, nr, nc)
Print matrix to screen.
MuJoCo.LibMuJoCo.mju_printMatSparse
— Methodmju_printMatSparse(mat, nr, rownnz, rowadr, colind)
Print sparse matrix to screen.
MuJoCo.LibMuJoCo.mju_quat2Mat
— Methodmju_quat2Mat(res, quat)
Convert quaternion to 3D rotation matrix.
MuJoCo.LibMuJoCo.mju_quat2Vel
— Methodmju_quat2Vel(res, quat, dt)
Convert quaternion (corresponding to orientation difference) to 3D velocity.
MuJoCo.LibMuJoCo.mju_quatIntegrate
— Methodmju_quatIntegrate(quat, vel, scale)
Integrate quaternion given 3D angular velocity.
MuJoCo.LibMuJoCo.mju_quatZ2Vec
— Methodmju_quatZ2Vec(quat, vec)
Construct quaternion performing rotation from z-axis to given vector.
MuJoCo.LibMuJoCo.mju_rayFlex
— Methodmju_rayFlex(m, d, flex_layer, flg_vert, flg_edge, flg_face, flg_skin, flexid, pnt, vec, vertid)
Intersect ray with flex, return nearest distance or -1 if no intersection, and also output nearest vertex id.
MuJoCo.LibMuJoCo.mju_rayGeom
— Methodmju_rayGeom(pos, mat, size, pnt, vec, geomtype)
Intersect ray with pure geom, return nearest distance or -1 if no intersection.
MuJoCo.LibMuJoCo.mju_raySkin
— Methodmju_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_rotVecMat
— Methodmju_rotVecMat(res, vec, mat)
Multiply vector by 3D rotation matrix: res = mat * vec.
MuJoCo.LibMuJoCo.mju_rotVecMatT
— Methodmju_rotVecMatT(res, vec, mat)
Multiply vector by transposed 3D rotation matrix: res = mat' * vec.
MuJoCo.LibMuJoCo.mju_rotVecQuat
— Methodmju_rotVecQuat(res, vec, quat)
Rotate vector by quaternion.
MuJoCo.LibMuJoCo.mju_round
— Methodmju_round(x)
Round x to nearest integer.
MuJoCo.LibMuJoCo.mju_scl
— Methodmju_scl(res, vec, scl, n)
Set res = vec*scl.
MuJoCo.LibMuJoCo.mju_scl3
— Methodmju_scl3(res, vec, scl)
Set res = vec*scl.
MuJoCo.LibMuJoCo.mju_sigmoid
— Methodmju_sigmoid(x)
Sigmoid function over 0<=x<=1 using quintic polynomial.
MuJoCo.LibMuJoCo.mju_sign
— Methodmju_sign(x)
Return sign of x: +1, -1 or 0.
MuJoCo.LibMuJoCo.mju_springDamper
— Methodmju_springDamper(pos0, vel0, Kp, Kv, dt)
Integrate spring-damper analytically, return pos(dt).
MuJoCo.LibMuJoCo.mju_sqrMatTD
— Methodmju_sqrMatTD(res, mat, diag, nr, nc)
Set res = mat' * diag * mat if diag is not NULL, and res = mat' * mat otherwise.
MuJoCo.LibMuJoCo.mju_standardNormal
— Methodmju_standardNormal(num2)
Standard normal random number generator (optional second number).
MuJoCo.LibMuJoCo.mju_str2Type
— Methodmju_str2Type(str)
Convert type name to type id (mjtObj).
MuJoCo.LibMuJoCo.mju_strncpy
— Methodmju_strncpy(dst, src, n)
Call strncpy, then set dst[n-1] = 0.
MuJoCo.LibMuJoCo.mju_sub
— Methodmju_sub(res, vec1, vec2, n)
Set res = vec1 - vec2.
MuJoCo.LibMuJoCo.mju_sub3
— Methodmju_sub3(res, vec1, vec2)
Set res = vec1 - vec2.
MuJoCo.LibMuJoCo.mju_subFrom
— Methodmju_subFrom(res, vec, n)
Set res = res - vec.
MuJoCo.LibMuJoCo.mju_subFrom3
— Methodmju_subFrom3(res, vec)
Set res = res - vec.
MuJoCo.LibMuJoCo.mju_subQuat
— Methodmju_subQuat(res, qa, qb)
Subtract quaternions, express as 3D velocity: qb*quat(res) = qa.
MuJoCo.LibMuJoCo.mju_sum
— Methodmju_sum(vec, n)
Return sum(vec).
MuJoCo.LibMuJoCo.mju_symmetrize
— Methodmju_symmetrize(res, mat, n)
Symmetrize square matrix res = (mat + mat')/2.
MuJoCo.LibMuJoCo.mju_taskJoin
— Methodmju_taskJoin(task)
Wait for a task to complete.
MuJoCo.LibMuJoCo.mju_threadPoolCreate
— Methodmju_threadPoolCreate(number_of_threads)
Create a thread pool with the specified number of threads running.
MuJoCo.LibMuJoCo.mju_threadPoolDestroy
— Methodmju_threadPoolDestroy(thread_pool)
Destroy a thread pool.
MuJoCo.LibMuJoCo.mju_threadPoolEnqueue
— Methodmju_threadPoolEnqueue(thread_pool, task)
Enqueue a task in a thread pool.
MuJoCo.LibMuJoCo.mju_transformSpatial
— Methodmju_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.mju_transpose
— Methodmju_transpose(res, mat, nr, nc)
Transpose matrix: res = mat'.
MuJoCo.LibMuJoCo.mju_trnVecPose
— Methodmju_trnVecPose(res, pos, quat, vec)
Transform vector by pose.
MuJoCo.LibMuJoCo.mju_type2Str
— Methodmju_type2Str(type)
Convert type id (mjtObj) to type name.
MuJoCo.LibMuJoCo.mju_unit4
— Methodmju_unit4(res)
Set res = (1,0,0,0).
MuJoCo.LibMuJoCo.mju_warningText
— Methodmju_warningText(warning, info)
Construct a warning message given the warning type and info.
MuJoCo.LibMuJoCo.mju_warning_i
— Methodmju_warning_i(msg, i)
Deprecated: use mju_warning.
MuJoCo.LibMuJoCo.mju_warning_s
— Methodmju_warning_s(msg, text)
Deprecated: use mju_warning.
MuJoCo.LibMuJoCo.mju_writeLog
— Methodmju_writeLog(type, msg)
Write [datetime, type: message] to MUJOCO_LOG.TXT.
MuJoCo.LibMuJoCo.mju_writeNumBytes
— Methodmju_writeNumBytes(nbytes)
Return human readable number of bytes using standard letter suffix.
MuJoCo.LibMuJoCo.mju_zero
— Methodmju_zero(res, n)
Set res = 0.
MuJoCo.LibMuJoCo.mju_zero3
— Methodmju_zero3(res)
Set res = 0.
MuJoCo.LibMuJoCo.mju_zero4
— Methodmju_zero4(res)
Set res = 0.
MuJoCo.LibMuJoCo.mjui_add
— Methodmjui_add(ui, def)
Add definitions to UI.
MuJoCo.LibMuJoCo.mjui_addToSection
— Methodmjui_addToSection(ui, sect, def)
Add definitions to UI section.
MuJoCo.LibMuJoCo.mjui_event
— Methodmjui_event(ui, state, con)
Handle UI event, return pointer to changed item, NULL if no change.
MuJoCo.LibMuJoCo.mjui_render
— Methodmjui_render(ui, state, con)
Copy UI image to current buffer.
MuJoCo.LibMuJoCo.mjui_resize
— Methodmjui_resize(ui, con)
Compute UI sizes.
MuJoCo.LibMuJoCo.mjui_themeColor
— Methodmjui_themeColor(ind)
Get builtin UI theme color (ind: 0-3).
MuJoCo.LibMuJoCo.mjui_themeSpacing
— Methodmjui_themeSpacing(ind)
Get builtin UI theme spacing (ind: 0-1).
MuJoCo.LibMuJoCo.mjui_update
— Methodmjui_update(section, item, ui, state, con)
Update specific section/item; -1: update all.
MuJoCo.LibMuJoCo.mjv_addGeoms
— Methodmjv_addGeoms(m, d, opt, pert, catmask, scn)
Add geoms from selected categories.
MuJoCo.LibMuJoCo.mjv_alignToCamera
— Methodmjv_alignToCamera(res, vec, forward)
Rotate 3D vec in horizontal plane by angle between (0,1) and (forwardx,forwardy).
MuJoCo.LibMuJoCo.mjv_applyPerturbForce
— Methodmjv_applyPerturbForce(m, d, pert)
Set perturb force,torque in d->xfrc_applied, if selected body is dynamic.
MuJoCo.LibMuJoCo.mjv_applyPerturbPose
— Methodmjv_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_averageCamera
— Methodmjv_averageCamera(cam1, cam2)
Return the average of two OpenGL cameras.
MuJoCo.LibMuJoCo.mjv_cameraInModel
— Methodmjv_cameraInModel(headpos, forward, up, scn)
Get camera info in model space; average left and right OpenGL cameras.
MuJoCo.LibMuJoCo.mjv_cameraInRoom
— Methodmjv_cameraInRoom(headpos, forward, up, scn)
Get camera info in room space; average left and right OpenGL cameras.
MuJoCo.LibMuJoCo.mjv_connector
— Methodmjv_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_defaultCamera
— Methodmjv_defaultCamera(cam)
Set default camera.
MuJoCo.LibMuJoCo.mjv_defaultFigure
— Methodmjv_defaultFigure(fig)
Set default figure.
MuJoCo.LibMuJoCo.mjv_defaultFreeCamera
— Methodmjv_defaultFreeCamera(m, cam)
Set default free camera.
MuJoCo.LibMuJoCo.mjv_defaultOption
— Methodmjv_defaultOption(opt)
Set default visualization options.
MuJoCo.LibMuJoCo.mjv_defaultPerturb
— Methodmjv_defaultPerturb(pert)
Set default perturbation.
MuJoCo.LibMuJoCo.mjv_defaultScene
— Methodmjv_defaultScene(scn)
Set default abstract scene.
MuJoCo.LibMuJoCo.mjv_defaultSceneState
— Methodmjv_defaultSceneState(scnstate)
Set default scene state.
MuJoCo.LibMuJoCo.mjv_freeScene
— Methodmjv_freeScene(scn)
Free abstract scene.
MuJoCo.LibMuJoCo.mjv_freeSceneState
— Methodmjv_freeSceneState(scnstate)
Free scene state.
MuJoCo.LibMuJoCo.mjv_frustumHeight
— Methodmjv_frustumHeight(scn)
Get frustum height at unit distance from camera; average left and right OpenGL cameras.
MuJoCo.LibMuJoCo.mjv_initGeom
— Methodmjv_initGeom(geom, type, size, pos, mat, rgba)
Initialize given geom fields when not NULL, set the rest to their default values.
MuJoCo.LibMuJoCo.mjv_initPerturb
— Methodmjv_initPerturb(m, d, scn, pert)
Copy perturb pos,quat from selected body; set scale for perturbation.
MuJoCo.LibMuJoCo.mjv_makeConnector
— Methodmjv_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_makeLights
— Methodmjv_makeLights(m, d, scn)
Make list of lights.
MuJoCo.LibMuJoCo.mjv_makeScene
— Methodmjv_makeScene(m, scn, maxgeom)
Allocate resources in abstract scene.
MuJoCo.LibMuJoCo.mjv_makeSceneState
— Methodmjv_makeSceneState(m, d, scnstate, maxgeom)
Allocate resources and initialize a scene state object.
MuJoCo.LibMuJoCo.mjv_model2room
— Methodmjv_model2room(roompos, roomquat, modelpos, modelquat, scn)
Transform pose from model to room space.
MuJoCo.LibMuJoCo.mjv_moveCamera
— Methodmjv_moveCamera(m, action, reldx, reldy, scn, cam)
Move camera with mouse; action is mjtMouse.
MuJoCo.LibMuJoCo.mjv_moveCameraFromState
— Methodmjv_moveCameraFromState(scnstate, action, reldx, reldy, scn, cam)
Move camera with mouse given a scene state; action is mjtMouse.
MuJoCo.LibMuJoCo.mjv_moveModel
— Methodmjv_moveModel(m, action, reldx, reldy, roomup, scn)
Move model with mouse; action is mjtMouse.
MuJoCo.LibMuJoCo.mjv_movePerturb
— Methodmjv_movePerturb(m, d, action, reldx, reldy, scn, pert)
Move perturb object with mouse; action is mjtMouse.
MuJoCo.LibMuJoCo.mjv_movePerturbFromState
— Methodmjv_movePerturbFromState(scnstate, action, reldx, reldy, scn, pert)
Move perturb object with mouse given a scene state; action is mjtMouse.
MuJoCo.LibMuJoCo.mjv_room2model
— Methodmjv_room2model(modelpos, modelquat, roompos, roomquat, scn)
Transform pose from room to model space.
MuJoCo.LibMuJoCo.mjv_select
— Methodmjv_select(m, d, vopt, aspectratio, relx, rely, scn, selpnt, geomid, flexid, skinid)
Select geom, flex or skin with mouse, return bodyid; -1: none selected.
MuJoCo.LibMuJoCo.mjv_updateCamera
— Methodmjv_updateCamera(m, d, cam, scn)
Update camera.
MuJoCo.LibMuJoCo.mjv_updateScene
— Methodmjv_updateScene(m, d, opt, pert, cam, catmask, scn)
Update entire scene given model state.
MuJoCo.LibMuJoCo.mjv_updateSceneFromState
— Methodmjv_updateSceneFromState(scnstate, opt, pert, cam, catmask, scn)
Update entire scene from a scene state, return the number of new mjWARN_VGEOMFULL warnings.
MuJoCo.LibMuJoCo.mjv_updateSceneState
— Methodmjv_updateSceneState(m, d, opt, scnstate)
Update a scene state from model and data.
MuJoCo.LibMuJoCo.mjv_updateSkin
— Methodmjv_updateSkin(m, d, scn)
Update skins.