MuJoCo Warp API#
Public API for MJWarp.
- class Model[source]#
Model definition and parameters.
- nq#
number of generalized coordinates
- Type:
int
- nv#
number of degrees of freedom
- Type:
int
- nu#
number of actuators/controls
- Type:
int
- na#
number of activation states
- Type:
int
- nbody#
number of bodies
- Type:
int
- noct#
number of total octree cells in all meshes
- Type:
int
- njnt#
number of joints
- Type:
int
- nM#
number of non-zeros in sparse inertia matrix
- Type:
int
- nC#
number of non-zeros in sparse body-dof matrix
- Type:
int
- ngeom#
number of geoms
- Type:
int
- nsite#
number of sites
- Type:
int
- ncam#
number of cameras
- Type:
int
- nlight#
number of lights
- Type:
int
- nflex#
number of flexes
- Type:
int
- nflexvert#
number of vertices in all flexes
- Type:
int
- nflexedge#
number of edges in all flexes
- Type:
int
- nflexelem#
number of elements in all flexes
- Type:
int
- nflexelemdata#
number of element vertex ids in all flexes
- Type:
int
- nflexelemedge#
number of element edge ids in all flexes
- Type:
int
- nmesh#
number of meshes
- Type:
int
- nmeshvert#
number of vertices for all meshes
- Type:
int
- nmeshnormal#
number of normals in all meshes
- Type:
int
- nmeshface#
number of faces for all meshes
- Type:
int
- nmeshgraph#
number of ints in mesh auxiliary data
- Type:
int
- nmeshpoly#
number of polygons in all meshes
- Type:
int
- nmeshpolyvert#
number of vertices in all polygons
- Type:
int
- nmeshpolymap#
number of polygons in vertex map
- Type:
int
- nhfield#
number of heightfields
- Type:
int
- nhfielddata#
size of elevation data
- Type:
int
- nmat#
number of materials
- Type:
int
- npair#
number of predefined geom pairs
- Type:
int
- nexclude#
number of excluded geom pairs
- Type:
int
- neq#
number of equality constraints
- Type:
int
- ntendon#
number of tendons
- Type:
int
- nwrap#
number of wrap objects in all tendon paths
- Type:
int
- nsensor#
number of sensors
- Type:
int
- nmocap#
number of mocap bodies
- Type:
int
- nplugin#
number of plugin instances
- Type:
int
- ngravcomp#
number of bodies with nonzero gravcomp
- Type:
int
- nsensordata#
number of elements in sensor data vector
- Type:
int
- opt#
physics options
- stat#
model statistics
- body_parentid#
id of body’s parent (nbody,)
- Type:
array(ndim=1, dtype=int32)
- body_rootid#
id of root above body (nbody,)
- Type:
array(ndim=1, dtype=int32)
- body_weldid#
id of body that this body is welded to (nbody,)
- Type:
array(ndim=1, dtype=int32)
- body_mocapid#
id of mocap data; -1: none (nbody,)
- Type:
array(ndim=1, dtype=int32)
- body_jntnum#
number of joints for this body (nbody,)
- Type:
array(ndim=1, dtype=int32)
- body_jntadr#
start addr of joints; -1: no joints (nbody,)
- Type:
array(ndim=1, dtype=int32)
- body_dofnum#
number of motion degrees of freedom (nbody,)
- Type:
array(ndim=1, dtype=int32)
- body_dofadr#
start addr of dofs; -1: no dofs (nbody,)
- Type:
array(ndim=1, dtype=int32)
- body_geomnum#
number of geoms (nbody,)
- Type:
array(ndim=1, dtype=int32)
- body_geomadr#
start addr of geoms; -1: no geoms (nbody,)
- Type:
array(ndim=1, dtype=int32)
- body_subtreemass#
mass of subtree starting at this body (*, nbody,)
- Type:
array(ndim=2, dtype=float32)
- body_gravcomp#
antigravity force, units of body weight (*, nbody)
- Type:
array(ndim=2, dtype=float32)
- body_contype#
OR over all geom contypes (nbody,)
- Type:
array(ndim=1, dtype=int32)
- body_conaffinity#
OR over all geom conaffinities (nbody,)
- Type:
array(ndim=1, dtype=int32)
- oct_child#
octree children (noct, 8)
- Type:
array(ndim=1, dtype=vector(length=8, dtype=int32))
- oct_aabb#
octree axis-aligned bounding boxes (noct, 2, 3)
- Type:
array(ndim=2, dtype=vec3f)
- oct_coeff#
octree interpolation coefficients (noct, 8)
- Type:
array(ndim=1, dtype=vector(length=8, dtype=float32))
- jnt_type#
type of joint (JointType) (njnt,)
- Type:
array(ndim=1, dtype=int32)
- jnt_qposadr#
start addr in ‘qpos’ for joint’s data (njnt,)
- Type:
array(ndim=1, dtype=int32)
- jnt_dofadr#
start addr in ‘qvel’ for joint’s data (njnt,)
- Type:
array(ndim=1, dtype=int32)
- jnt_bodyid#
id of joint’s body (njnt,)
- Type:
array(ndim=1, dtype=int32)
- jnt_limited#
does joint have limits (njnt,)
- Type:
array(ndim=1, dtype=int32)
- jnt_actfrclimited#
does joint have actuator force limits (njnt,)
- Type:
array(ndim=1, dtype=warp._src.types.bool)
- jnt_actgravcomp#
is gravcomp force applied via actuators (njnt,)
- Type:
array(ndim=1, dtype=int32)
- jnt_solimp#
constraint solver impedance: limit (*, njnt, mjNIMP)
- Type:
array(ndim=2, dtype=vector(length=5, dtype=float32))
- dof_bodyid#
id of dof’s body (nv,)
- Type:
array(ndim=1, dtype=int32)
- dof_jntid#
id of dof’s joint (nv,)
- Type:
array(ndim=1, dtype=int32)
- dof_parentid#
id of dof’s parent; -1: none (nv,)
- Type:
array(ndim=1, dtype=int32)
- dof_Madr#
dof address in M-diagonal (nv,)
- Type:
array(ndim=1, dtype=int32)
- dof_solref#
constraint solver reference: frictionloss (*, nv, NREF)
- Type:
array(ndim=2, dtype=vec2f)
- dof_solimp#
constraint solver impedance: frictionloss (*, nv, NIMP)
- Type:
array(ndim=2, dtype=vector(length=5, dtype=float32))
- geom_type#
geometric type (GeomType) (ngeom,)
- Type:
array(ndim=1, dtype=int32)
- geom_contype#
geom contact type (ngeom,)
- Type:
array(ndim=1, dtype=int32)
- geom_conaffinity#
geom contact affinity (ngeom,)
- Type:
array(ndim=1, dtype=int32)
- geom_condim#
contact dimensionality (1, 3, 4, 6) (ngeom,)
- Type:
array(ndim=1, dtype=int32)
- geom_bodyid#
id of geom’s body (ngeom,)
- Type:
array(ndim=1, dtype=int32)
- geom_dataid#
id of geom’s mesh/hfield; -1: none (ngeom,)
- Type:
array(ndim=1, dtype=int32)
- geom_group#
geom group inclusion/exclusion mask (ngeom,)
- Type:
array(ndim=1, dtype=int32)
- geom_priority#
geom contact priority (ngeom,)
- Type:
array(ndim=1, dtype=int32)
- geom_solref#
constraint solver reference: contact (*, ngeom, mjNREF)
- Type:
array(ndim=2, dtype=vec2f)
- geom_solimp#
constraint solver impedance: contact (*, ngeom, mjNIMP)
- Type:
array(ndim=2, dtype=vector(length=5, dtype=float32))
- geom_fluid#
fluid interaction parameters (ngeom, mjNFLUID)
- Type:
array(ndim=2, dtype=float32)
- site_type#
geom type for rendering (GeomType) (nsite,)
- Type:
array(ndim=1, dtype=int32)
- site_bodyid#
id of site’s body (nsite,)
- Type:
array(ndim=1, dtype=int32)
- site_size#
geom size for rendering (nsite, 3)
- Type:
array(ndim=1, dtype=vec3f)
- cam_mode#
camera tracking mode (CamLightType) (ncam,)
- Type:
array(ndim=1, dtype=int32)
- cam_bodyid#
id of camera’s body (ncam,)
- Type:
array(ndim=1, dtype=int32)
- cam_targetbodyid#
id of targeted body; -1: none (ncam,)
- Type:
array(ndim=1, dtype=int32)
- cam_fovy#
y field-of-view (ortho ? len : deg) (ncam,)
- Type:
array(ndim=1, dtype=float32)
- cam_resolution#
resolution: pixels [width, height] (ncam, 2)
- Type:
array(ndim=1, dtype=vec2i)
- cam_sensorsize#
sensor size: length [width, height] (ncam, 2)
- Type:
array(ndim=1, dtype=vec2f)
- cam_intrinsic#
[focal length; principal point] (ncam, 4)
- Type:
array(ndim=1, dtype=vec4f)
- light_mode#
light tracking mode (CamLightType) (nlight,)
- Type:
array(ndim=1, dtype=int32)
- light_bodyid#
id of light’s body (nlight,)
- Type:
array(ndim=1, dtype=int32)
- light_targetbodyid#
id of targeted body; -1: none (nlight,)
- Type:
array(ndim=1, dtype=int32)
- light_castshadow#
does light cast shadows (*, nlight)
- Type:
array(ndim=2, dtype=warp._src.types.bool)
- light_poscom0#
global position rel. to sub-com in qpos0 (*, nlight, 3)
- Type:
array(ndim=2, dtype=vec3f)
- flex_dim#
1: lines, 2: triangles, 3: tetrahedra (nflex,)
- Type:
array(ndim=1, dtype=int32)
- flex_vertadr#
first vertex address (nflex,)
- Type:
array(ndim=1, dtype=int32)
- flex_vertnum#
number of vertices (nflex,)
- Type:
array(ndim=1, dtype=int32)
- flex_edgeadr#
first edge address (nflex,)
- Type:
array(ndim=1, dtype=int32)
- flex_elemedgeadr#
first element address (nflex,)
- Type:
array(ndim=1, dtype=int32)
- flex_vertbodyid#
vertex body ids (nflexvert,)
- Type:
array(ndim=1, dtype=int32)
- flex_edge#
edge vertex ids (2 per edge) (nflexedge, 2)
- Type:
array(ndim=1, dtype=vec2i)
- flex_edgeflap#
adjacent vertex ids (dim=2 only) (nflexedge, 2)
- Type:
array(ndim=1, dtype=vec2i)
- flex_elem#
element vertex ids (dim+1 per elem) (nflexelemdata,)
- Type:
array(ndim=1, dtype=int32)
- flex_elemedge#
element edge ids (nflexelemedge,)
- Type:
array(ndim=1, dtype=int32)
- flexedge_length0#
edge lengths in qpos0 (nflexedge,)
- Type:
array(ndim=1, dtype=float32)
- flex_stiffness#
finite element stiffness matrix (nflexelem, 21)
- Type:
array(ndim=2, dtype=float32)
- flex_bending#
bending stiffness (nflexedge, 17)
- Type:
array(ndim=2, dtype=float32)
- flex_damping#
Rayleigh’s damping coefficient (nflex,)
- Type:
array(ndim=1, dtype=float32)
- mesh_vertadr#
first vertex address (nmesh,)
- Type:
array(ndim=1, dtype=int32)
- mesh_vertnum#
number of vertices (nmesh,)
- Type:
array(ndim=1, dtype=int32)
- mesh_faceadr#
first face address (nmesh,)
- Type:
array(ndim=1, dtype=int32)
- mesh_normaladr#
first normal address (nmesh,)
- Type:
array(ndim=1, dtype=int32)
- mesh_graphadr#
graph data address; -1: no graph (nmesh,)
- Type:
array(ndim=1, dtype=int32)
- mesh_vert#
vertex positions for all meshes (nmeshvert, 3)
- Type:
array(ndim=1, dtype=vec3f)
- mesh_normal#
normals for all meshes (nmeshnormal, 3)
- Type:
array(ndim=1, dtype=vec3f)
- mesh_face#
face indices for all meshes (nface, 3)
- Type:
array(ndim=1, dtype=vec3i)
- mesh_graph#
convex graph data (nmeshgraph,)
- Type:
array(ndim=1, dtype=int32)
- mesh_quat#
rotation applied to asset vertices (nmesh, 4)
- Type:
array(ndim=1, dtype=quatf)
- mesh_polynum#
number of polygons per mesh (nmesh,)
- Type:
array(ndim=1, dtype=int32)
- mesh_polyadr#
first polygon address per mesh (nmesh,)
- Type:
array(ndim=1, dtype=int32)
- mesh_polynormal#
all polygon normals (nmeshpoly, 3)
- Type:
array(ndim=1, dtype=vec3f)
- mesh_polyvertadr#
polygon vertex start address (nmeshpoly,)
- Type:
array(ndim=1, dtype=int32)
- mesh_polyvertnum#
number of vertices per polygon (nmeshpoly,)
- Type:
array(ndim=1, dtype=int32)
- mesh_polyvert#
all polygon vertices (nmeshpolyvert,)
- Type:
array(ndim=1, dtype=int32)
- mesh_polymapadr#
first polygon address per vertex (nmeshvert,)
- Type:
array(ndim=1, dtype=int32)
- mesh_polymapnum#
number of polygons per vertex (nmeshvert,)
- Type:
array(ndim=1, dtype=int32)
- mesh_polymap#
vertex to polygon map (nmeshpolymap,)
- Type:
array(ndim=1, dtype=int32)
- hfield_size#
(x, y, z_top, z_bottom) (nhfield, 4)
- Type:
array(ndim=1, dtype=vec4f)
- hfield_nrow#
number of rows in grid (nhfield,)
- Type:
array(ndim=1, dtype=int32)
- hfield_ncol#
number of columns in grid (nhfield,)
- Type:
array(ndim=1, dtype=int32)
- hfield_adr#
start address in hfield_data (nhfield,)
- Type:
array(ndim=1, dtype=int32)
- hfield_data#
elevation data (nhfielddata,)
- Type:
array(ndim=1, dtype=float32)
- mat_texid#
texture id for rendering (nmat, mjNTEXROLE)
- Type:
array(ndim=2, dtype=int32)
- pair_dim#
contact dimensionality (npair,)
- Type:
array(ndim=1, dtype=int32)
- pair_geom1#
id of geom1 (npair,)
- Type:
array(ndim=1, dtype=int32)
- pair_geom2#
id of geom2 (npair,)
- Type:
array(ndim=1, dtype=int32)
- pair_solreffriction#
solver reference: contact friction (*, npair, mjNREF)
- Type:
array(ndim=2, dtype=vec2f)
- pair_solimp#
solver impedance: contact (*, npair, mjNIMP)
- Type:
array(ndim=2, dtype=vector(length=5, dtype=float32))
- pair_friction#
tangent1, 2, spin, roll1, 2 (*, npair, 5)
- Type:
array(ndim=2, dtype=vector(length=5, dtype=float32))
- exclude_signature#
body1 << 16 + body2 (nexclude,)
- Type:
array(ndim=1, dtype=int32)
- eq_type#
constraint type (EqType) (neq,)
- Type:
array(ndim=1, dtype=int32)
- eq_obj1id#
id of object 1 (neq,)
- Type:
array(ndim=1, dtype=int32)
- eq_obj2id#
id of object 2 (neq,)
- Type:
array(ndim=1, dtype=int32)
- eq_objtype#
type of both objects (ObjType) (neq,)
- Type:
array(ndim=1, dtype=int32)
- eq_active0#
initial enable/disable constraint state (neq,)
- Type:
array(ndim=1, dtype=warp._src.types.bool)
- eq_solimp#
constraint solver impedance (*, neq, mjNIMP)
- Type:
array(ndim=2, dtype=vector(length=5, dtype=float32))
- eq_data#
numeric data for constraint (*, neq, mjNEQDATA)
- Type:
array(ndim=2, dtype=vector(length=11, dtype=float32))
- tendon_adr#
address of first object in tendon’s path (ntendon,)
- Type:
array(ndim=1, dtype=int32)
- tendon_num#
number of objects in tendon’s path (ntendon,)
- Type:
array(ndim=1, dtype=int32)
- tendon_limited#
does tendon have length limits (ntendon,)
- Type:
array(ndim=1, dtype=int32)
- tendon_actfrclimited#
does ten have actuator force limit (ntendon,)
- Type:
array(ndim=1, dtype=warp._src.types.bool)
- tendon_solref_lim#
constraint solver reference: limit (*, ntendon, mjNREF)
- Type:
array(ndim=2, dtype=vec2f)
- tendon_solimp_lim#
constraint solver impedance: limit (*, ntendon, mjNIMP)
- Type:
array(ndim=2, dtype=vector(length=5, dtype=float32))
- tendon_solref_fri#
constraint solver reference: friction (*, ntendon, mjNREF)
- Type:
array(ndim=2, dtype=vec2f)
- tendon_solimp_fri#
constraint solver impedance: friction (*, ntendon, mjNIMP)
- Type:
array(ndim=2, dtype=vector(length=5, dtype=float32))
- tendon_armature#
inertia associated with tendon velocity (*, ntendon)
- Type:
array(ndim=2, dtype=float32)
- wrap_type#
wrap object type (WrapType) (nwrap,)
- Type:
array(ndim=1, dtype=int32)
- wrap_objid#
object id: geom, site, joint (nwrap,)
- Type:
array(ndim=1, dtype=int32)
- wrap_prm#
divisor, joint coef, or site id (nwrap,)
- Type:
array(ndim=1, dtype=float32)
- actuator_trntype#
transmission type (TrnType) (nu,)
- Type:
array(ndim=1, dtype=int32)
- actuator_dyntype#
dynamics type (DynType) (nu,)
- Type:
array(ndim=1, dtype=int32)
- actuator_gaintype#
gain type (GainType) (nu,)
- Type:
array(ndim=1, dtype=int32)
- actuator_biastype#
bias type (BiasType) (nu,)
- Type:
array(ndim=1, dtype=int32)
- actuator_trnid#
transmission id: joint, tendon, site (nu, 2)
- Type:
array(ndim=1, dtype=vec2i)
- actuator_actadr#
first activation address; -1: stateless (nu,)
- Type:
array(ndim=1, dtype=int32)
- actuator_actnum#
number of activation variables (nu,)
- Type:
array(ndim=1, dtype=int32)
- actuator_ctrllimited#
is control limited (nu,)
- Type:
array(ndim=1, dtype=warp._src.types.bool)
- actuator_forcelimited#
is force limited (nu,)
- Type:
array(ndim=1, dtype=warp._src.types.bool)
- actuator_actlimited#
is activation limited (nu,)
- Type:
array(ndim=1, dtype=warp._src.types.bool)
- actuator_dynprm#
dynamics parameters (*, nu, mjNDYN)
- Type:
array(ndim=2, dtype=vector(length=10, dtype=float32))
- actuator_gainprm#
gain parameters (*, nu, mjNGAIN)
- Type:
array(ndim=2, dtype=vector(length=10, dtype=float32))
- actuator_biasprm#
bias parameters (*, nu, mjNBIAS)
- Type:
array(ndim=2, dtype=vector(length=10, dtype=float32))
- actuator_actearly#
step activation before force (nu,)
- Type:
array(ndim=1, dtype=warp._src.types.bool)
- actuator_gear#
scale length and transmitted force (*, nu, 6)
- Type:
array(ndim=2, dtype=vector(length=6, dtype=float32))
- actuator_cranklength#
crank length for slider-crank (nu,)
- Type:
array(ndim=1, dtype=float32)
- actuator_acc0#
acceleration from unit force in qpos0 (nu,)
- Type:
array(ndim=1, dtype=float32)
- actuator_lengthrange#
feasible actuator length range (nu, 2)
- Type:
array(ndim=1, dtype=vec2f)
- sensor_type#
sensor type (SensorType) (nsensor,)
- Type:
array(ndim=1, dtype=int32)
- sensor_datatype#
numeric data type (DataType) (nsensor,)
- Type:
array(ndim=1, dtype=int32)
- sensor_objtype#
type of sensorized object (ObjType) (nsensor,)
- Type:
array(ndim=1, dtype=int32)
- sensor_objid#
id of sensorized object (nsensor,)
- Type:
array(ndim=1, dtype=int32)
- sensor_reftype#
type of reference frame (ObjType) (nsensor,)
- Type:
array(ndim=1, dtype=int32)
- sensor_refid#
id of reference frame; -1: global frame (nsensor,)
- Type:
array(ndim=1, dtype=int32)
- sensor_intprm#
sensor parameters (nsensor, mjNSENS)
- Type:
array(ndim=2, dtype=int32)
- sensor_dim#
number of scalar outputs (nsensor,)
- Type:
array(ndim=1, dtype=int32)
- sensor_adr#
address in sensor array (nsensor,)
- Type:
array(ndim=1, dtype=int32)
- sensor_cutoff#
cutoff for real and positive; 0: ignore (nsensor,)
- Type:
array(ndim=1, dtype=float32)
- plugin#
globally registered plugin slot number (nplugin,)
- Type:
array(ndim=1, dtype=int32)
- plugin_attr#
config attributes of geom plugin (nplugin, 3)
- Type:
array(ndim=1, dtype=vec3f)
- M_rownnz#
number of non-zeros in each row of qM (nv,)
- Type:
array(ndim=1, dtype=int32)
- M_rowadr#
index of each row in qM (nv,)
- Type:
array(ndim=1, dtype=int32)
- M_colind#
column indices of non-zeros in qM (nM,)
- Type:
array(ndim=1, dtype=int32)
- mapM2M#
index mapping from M (legacy) to M (CSR) (nC)
- Type:
array(ndim=1, dtype=int32)
- nacttrnbody#
number of actuators with body transmission
- Type:
int
- nsensorcollision#
number of unique collisions for geom distance sensors
- Type:
int
- nsensortaxel#
number of taxels in all tactile sensors
- Type:
int
- nsensorcontact#
number of contact sensors
- Type:
int
- nrangefinder#
number of rangefinder sensors
- Type:
int
- nmaxcondim#
maximum condim for geoms
- Type:
int
- nmaxpyramid#
maximum number of pyramid directions
- Type:
int
- nmaxpolygon#
maximum number of verts per polygon
- Type:
int
- nmaxmeshdeg#
maximum number of polygons per vert
- Type:
int
- has_sdf_geom#
whether the model contains SDF geoms
- Type:
bool
- block_dim#
block dim options
- Type:
mujoco_warp._src.types.BlockDim
- body_tree#
list of body ids by tree level
- Type:
tuple[array(ndim=1, dtype=int32), …]
- mocap_bodyid#
id of body for mocap (nmocap,)
- Type:
array(ndim=1, dtype=int32)
- body_fluid_ellipsoid#
does body use ellipsoid fluid (nbody,)
- Type:
array(ndim=1, dtype=warp._src.types.bool)
- jnt_limited_slide_hinge_adr#
limited/slide/hinge jntadr
- Type:
array(ndim=1, dtype=int32)
- jnt_limited_ball_adr#
limited/ball jntadr
- Type:
array(ndim=1, dtype=int32)
- dof_tri_row#
dof lower triangle row (used in solver)
- Type:
array(ndim=1, dtype=int32)
- dof_tri_col#
dof lower triangle col (used in solver)
- Type:
array(ndim=1, dtype=int32)
- nxn_geom_pair#
collision pair geom ids [-2, ngeom-1]
- Type:
array(ndim=1, dtype=vec2i)
- nxn_geom_pair_filtered#
valid collision pair geom ids [-1, ngeom - 1]
- Type:
array(ndim=1, dtype=vec2i)
- nxn_pairid#
- contact pair id, -1 if not predefined,
-2 if skipped
collision id, else -1
- Type:
array(ndim=1, dtype=vec2i)
- nxn_pairid_filtered#
active subset of nxn_pairid
- Type:
array(ndim=1, dtype=vec2i)
- geom_pair_type_count#
count of max number of each potential collision
- Type:
tuple[int, …]
- geom_plugin_index#
geom index in plugin array (ngeom,)
- Type:
array(ndim=1, dtype=int32)
- eq_connect_adr#
eq_* addresses of type
CONNECT- Type:
array(ndim=1, dtype=int32)
- eq_wld_adr#
eq_* addresses of type
WELD- Type:
array(ndim=1, dtype=int32)
- eq_jnt_adr#
eq_* addresses of type
JOINT- Type:
array(ndim=1, dtype=int32)
- eq_ten_adr#
eq_* addresses of type
TENDON- Type:
array(ndim=1, dtype=int32)
- tendon_jnt_adr#
joint tendon address
- Type:
array(ndim=1, dtype=int32)
- tendon_site_pair_adr#
site pair tendon address
- Type:
array(ndim=1, dtype=int32)
- tendon_geom_adr#
geom tendon address
- Type:
array(ndim=1, dtype=int32)
- tendon_limited_adr#
addresses for limited tendons
- Type:
array(ndim=1, dtype=int32)
- ten_wrapadr_site#
wrap object starting address for sites
- Type:
array(ndim=1, dtype=int32)
- ten_wrapnum_site#
number of site wrap objects per tendon
- Type:
array(ndim=1, dtype=int32)
- wrap_jnt_adr#
addresses for joint tendon wrap object
- Type:
array(ndim=1, dtype=int32)
- wrap_site_adr#
addresses for site tendon wrap object
- Type:
array(ndim=1, dtype=int32)
- wrap_site_pair_adr#
first address for site wrap pair
- Type:
array(ndim=1, dtype=int32)
- wrap_geom_adr#
addresses for geom tendon wrap object
- Type:
array(ndim=1, dtype=int32)
- wrap_pulley_scale#
pulley scaling (nwrap,)
- Type:
array(ndim=1, dtype=float32)
- actuator_trntype_body_adr#
addresses for actuators with body transmission
- Type:
array(ndim=1, dtype=int32)
- sensor_pos_adr#
addresses for position sensors
- Type:
array(ndim=1, dtype=int32)
- sensor_limitpos_adr#
address for limit position sensors
- Type:
array(ndim=1, dtype=int32)
- sensor_vel_adr#
addresses for velocity sensors (excluding limit velocity sensors)
- Type:
array(ndim=1, dtype=int32)
- sensor_limitvel_adr#
address for limit velocity sensors
- Type:
array(ndim=1, dtype=int32)
- sensor_acc_adr#
addresses for acceleration sensors
- Type:
array(ndim=1, dtype=int32)
- sensor_rangefinder_adr#
addresses for rangefinder sensors
- Type:
array(ndim=1, dtype=int32)
- rangefinder_sensor_adr#
map sensor id to rangefinder id (excluding touch sensors) (excluding limit force sensors)
- Type:
array(ndim=1, dtype=int32)
- sensor_collision_start_adr#
address for sensor’s first item in collision
- Type:
array(ndim=1, dtype=int32)
- collision_sensor_adr#
map sensor id to collision id (nsensor,)
- Type:
array(ndim=1, dtype=int32)
- sensor_touch_adr#
addresses for touch sensors
- Type:
array(ndim=1, dtype=int32)
- sensor_limitfrc_adr#
address for limit force sensors
- Type:
array(ndim=1, dtype=int32)
- sensor_e_potential#
evaluate energy_pos
- Type:
bool
- sensor_e_kinetic#
evaluate energy_vel
- Type:
bool
- sensor_tendonactfrc_adr#
address for tendonactfrc sensor
- Type:
array(ndim=1, dtype=int32)
- sensor_subtree_vel#
evaluate subtree_vel
- Type:
bool
- sensor_contact_adr#
addresses for contact sensors (nsensorcontact,)
- Type:
array(ndim=1, dtype=int32)
- sensor_adr_to_contact_adr#
map sensor adr to contact adr (nsensor,)
- Type:
array(ndim=1, dtype=int32)
- sensor_rne_postconstraint#
evaluate rne_postconstraint
- Type:
bool
- sensor_rangefinder_bodyid#
bodyid for rangefinder (nrangefinder,)
- Type:
array(ndim=1, dtype=int32)
- taxel_vertadr#
tactile sensor vertex address (nsensortaxel,)
- Type:
array(ndim=1, dtype=int32)
- taxel_sensorid#
address for tactile sensors
- Type:
array(ndim=1, dtype=int32)
- qM_tiles#
tiling configuration
- Type:
tuple[mujoco_warp._src.types.TileSet, …]
- qLD_updates#
tuple of index triples for sparse factorization
- Type:
tuple[array(ndim=1, dtype=vec3i), …]
- qM_fullm_i#
sparse mass matrix addressing
- Type:
array(ndim=1, dtype=int32)
- qM_fullm_j#
sparse mass matrix addressing
- Type:
array(ndim=1, dtype=int32)
- qM_mulm_i#
sparse matmul addressing
- Type:
array(ndim=1, dtype=int32)
- qM_mulm_j#
sparse matmul addressing
- Type:
array(ndim=1, dtype=int32)
- qM_madr_ij#
sparse matmul addressing
- Type:
array(ndim=1, dtype=int32)
- class Data[source]#
Dynamic state that updates each step.
- solver_niter#
number of solver iterations (nworld,)
- Type:
array(ndim=1, dtype=int32)
- ne#
number of equality constraints (nworld,)
- Type:
array(ndim=1, dtype=int32)
- nf#
number of friction constraints (nworld,)
- Type:
array(ndim=1, dtype=int32)
- nl#
number of limit constraints (nworld,)
- Type:
array(ndim=1, dtype=int32)
- nefc#
number of constraints (nworld,)
- Type:
array(ndim=1, dtype=int32)
- time#
simulation time (nworld,)
- Type:
array(ndim=1, dtype=float32)
- energy#
potential, kinetic energy (nworld, 2)
- Type:
array(ndim=1, dtype=vec2f)
- qpos#
position (nworld, nq)
- Type:
array(ndim=2, dtype=float32)
- qvel#
velocity (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- act#
actuator activation (nworld, na)
- Type:
array(ndim=2, dtype=float32)
- qacc_warmstart#
acceleration used for warmstart (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- ctrl#
control (nworld, nu)
- Type:
array(ndim=2, dtype=float32)
- qfrc_applied#
applied generalized force (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- xfrc_applied#
applied Cartesian force/torque (nworld, nbody, 6)
- Type:
array(ndim=2, dtype=vector(length=6, dtype=float32))
- eq_active#
enable/disable constraints (nworld, neq)
- Type:
array(ndim=2, dtype=warp._src.types.bool)
- mocap_pos#
position of mocap bodies (nworld, nmocap, 3)
- Type:
array(ndim=2, dtype=vec3f)
- mocap_quat#
orientation of mocap bodies (nworld, nmocap, 4)
- Type:
array(ndim=2, dtype=quatf)
- qacc#
acceleration (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- act_dot#
time-derivative of actuator activation (nworld, na)
- Type:
array(ndim=2, dtype=float32)
- sensordata#
sensor data array (nworld, nsensordata,)
- Type:
array(ndim=2, dtype=float32)
- xpos#
Cartesian position of body frame (nworld, nbody, 3)
- Type:
array(ndim=2, dtype=vec3f)
- xquat#
Cartesian orientation of body frame (nworld, nbody, 4)
- Type:
array(ndim=2, dtype=quatf)
- xmat#
Cartesian orientation of body frame (nworld, nbody, 3, 3)
- Type:
array(ndim=2, dtype=mat33(f))
- xipos#
Cartesian position of body com (nworld, nbody, 3)
- Type:
array(ndim=2, dtype=vec3f)
- ximat#
Cartesian orientation of body inertia (nworld, nbody, 3, 3)
- Type:
array(ndim=2, dtype=mat33(f))
- xanchor#
Cartesian position of joint anchor (nworld, njnt, 3)
- Type:
array(ndim=2, dtype=vec3f)
- xaxis#
Cartesian joint axis (nworld, njnt, 3)
- Type:
array(ndim=2, dtype=vec3f)
- geom_xpos#
Cartesian geom position (nworld, ngeom, 3)
- Type:
array(ndim=2, dtype=vec3f)
- geom_xmat#
Cartesian geom orientation (nworld, ngeom, 3, 3)
- Type:
array(ndim=2, dtype=mat33(f))
- site_xpos#
Cartesian site position (nworld, nsite, 3)
- Type:
array(ndim=2, dtype=vec3f)
- site_xmat#
Cartesian site orientation (nworld, nsite, 3, 3)
- Type:
array(ndim=2, dtype=mat33(f))
- cam_xpos#
Cartesian camera position (nworld, ncam, 3)
- Type:
array(ndim=2, dtype=vec3f)
- cam_xmat#
Cartesian camera orientation (nworld, ncam, 3, 3)
- Type:
array(ndim=2, dtype=mat33(f))
- light_xpos#
Cartesian light position (nworld, nlight, 3)
- Type:
array(ndim=2, dtype=vec3f)
- light_xdir#
Cartesian light direction (nworld, nlight, 3)
- Type:
array(ndim=2, dtype=vec3f)
- subtree_com#
center of mass of each subtree (nworld, nbody, 3)
- Type:
array(ndim=2, dtype=vec3f)
- cdof#
com-based motion axis of each dof (rot:lin) (nworld, nv, 6)
- Type:
array(ndim=2, dtype=vector(length=6, dtype=float32))
- cinert#
com-based body inertia and mass (nworld, nbody, 10)
- Type:
array(ndim=2, dtype=vector(length=10, dtype=float32))
- flexvert_xpos#
cartesian flex vertex positions (nworld, nflexvert, 3)
- Type:
array(ndim=2, dtype=vec3f)
- flexedge_length#
flex edge lengths (nworld, nflexedge, 1)
- Type:
array(ndim=2, dtype=float32)
- ten_wrapadr#
start address of tendon’s path (nworld, ntendon)
- Type:
array(ndim=2, dtype=int32)
- ten_wrapnum#
number of wrap points in path (nworld, ntendon)
- Type:
array(ndim=2, dtype=int32)
- ten_J#
tendon Jacobian (nworld, ntendon, nv)
- Type:
array(ndim=3, dtype=float32)
- ten_length#
tendon lengths (nworld, ntendon)
- Type:
array(ndim=2, dtype=float32)
- wrap_obj#
geomid; -1: site; -2: pulley (nworld, nwrap, 2)
- Type:
array(ndim=2, dtype=vec2i)
- wrap_xpos#
Cartesian 3D points in all paths (nworld, nwrap, 6)
- Type:
array(ndim=2, dtype=vector(length=6, dtype=float32))
- actuator_length#
actuator lengths (nworld, nu)
- Type:
array(ndim=2, dtype=float32)
- actuator_moment#
actuator moments (nworld, nu, nv)
- Type:
array(ndim=3, dtype=float32)
- crb#
com-based composite inertia and mass (nworld, nbody, 10)
- Type:
array(ndim=2, dtype=vector(length=10, dtype=float32))
- qM#
total inertia (nworld, nv, nv) if dense (nworld, 1, nM) if sparse
- Type:
array(ndim=3, dtype=float32)
- qLD#
L’*D*L factorization of M (nworld, nv, nv) if dense (nworld, 1, nC) if sparse
- Type:
array(ndim=3, dtype=float32)
- qLDiagInv#
1/diag(D) (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- flexedge_velocity#
flex edge velocities (nworld, nflexedge,)
- Type:
array(ndim=2, dtype=float32)
- ten_velocity#
tendon velocities (nworld, ntendon)
- Type:
array(ndim=2, dtype=float32)
- actuator_velocity#
actuator velocities (nworld, nu)
- Type:
array(ndim=2, dtype=float32)
- cvel#
com-based velocity (rot:lin) (nworld, nbody, 6)
- Type:
array(ndim=2, dtype=vector(length=6, dtype=float32))
- cdof_dot#
time-derivative of cdof (rot:lin) (nworld, nv, 6)
- Type:
array(ndim=2, dtype=vector(length=6, dtype=float32))
- qfrc_bias#
C(qpos,qvel) (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- qfrc_spring#
passive spring force (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- qfrc_damper#
passive damper force (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- qfrc_gravcomp#
passive gravity compensation force (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- qfrc_fluid#
passive fluid force (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- qfrc_passive#
total passive force (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- subtree_linvel#
linear velocity of subtree com (nworld, nbody, 3)
- Type:
array(ndim=2, dtype=vec3f)
- subtree_angmom#
angular momentum about subtree com (nworld, nbody, 3)
- Type:
array(ndim=2, dtype=vec3f)
- actuator_force#
actuator force in actuation space (nworld, nu)
- Type:
array(ndim=2, dtype=float32)
- qfrc_actuator#
actuator force (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- qfrc_smooth#
net unconstrained force (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- qacc_smooth#
unconstrained acceleration (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- qfrc_constraint#
constraint force (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- qfrc_inverse#
net external force; should equal: (nworld, nv) qfrc_applied + J.T @ xfrc_applied + qfrc_actuator
- Type:
array(ndim=2, dtype=float32)
- cacc#
com-based acceleration (nworld, nbody, 6)
- Type:
array(ndim=2, dtype=vector(length=6, dtype=float32))
- cfrc_int#
com-based interaction force with parent (nworld, nbody, 6)
- Type:
array(ndim=2, dtype=vector(length=6, dtype=float32))
- cfrc_ext#
com-based external force on body (nworld, nbody, 6)
- Type:
array(ndim=2, dtype=vector(length=6, dtype=float32))
- contact#
contact data
- efc#
constraint data
- nworld#
number of worlds
- Type:
int
- naconmax#
maximum number of contacts (shared across all worlds)
- Type:
int
- njmax#
maximum number of constraints per world
- Type:
int
- nacon#
number of detected contacts (across all worlds) (1,)
- Type:
array(ndim=1, dtype=int32)
- ne_connect#
number of equality connect constraints (nworld,)
- Type:
array(ndim=1, dtype=int32)
- ne_weld#
number of equality weld constraints (nworld,)
- Type:
array(ndim=1, dtype=int32)
- ne_jnt#
number of equality joint constraints (nworld,)
- Type:
array(ndim=1, dtype=int32)
- ne_ten#
number of equality tendon constraints (nworld,)
- Type:
array(ndim=1, dtype=int32)
- nsolving#
number of unconverged worlds (1,)
- Type:
array(ndim=1, dtype=int32)
- subtree_bodyvel#
subtree body velocity (ang, vel) (nworld, nbody, 6)
- Type:
array(ndim=2, dtype=vector(length=6, dtype=float32))
- collision_pair#
collision pairs from broadphase (naconmax, 2)
- Type:
array(ndim=1, dtype=vec2i)
- collision_pairid#
ids from broadphase (naconmax, 2)
- Type:
array(ndim=1, dtype=vec2i)
- collision_worldid#
collision world ids from broadphase (naconmax,)
- Type:
array(ndim=1, dtype=int32)
- ncollision#
collision count from broadphase (1,)
- Type:
array(ndim=1, dtype=int32)
- collision(m: Model, d: Data)[source]#
Runs the full collision detection pipeline.
This function orchestrates the broadphase and narrowphase collision detection stages. It first identifies potential collision pairs using a broadphase algorithm (either N-squared or Sweep-and-Prune, based on
m.opt.broadphase). Then, for each potential pair, it performs narrowphase collision detection to compute detailed contact information like distance, position, and frame.The results are used to populate the
d.contactarray, and the total number of contacts is stored ind.nacon. Ifd.naconis larger thand.naconmaxthen an overflow has occurred and the remaining contacts will be skipped. If this happens, raise thenconmaxparameter inio.make_dataorio.put_data.This function will do nothing except zero out arrays if collision detection is disabled via
m.opt.disableflagsor ifd.naconis 0.
- nxn_broadphase(m: Model, d: Data)[source]#
Runs broadphase collision detection using a brute-force N-squared approach.
This function iterates through a pre-filtered list of all possible geometry pairs and performs a quick bounding sphere check to identify potential collisions.
For each pair that passes the sphere check, it populates the collision arrays in
d(d.collision_pair,d.collision_pairid, etc.), which are then consumed by the narrowphase.The initial list of pairs is filtered at model creation time to exclude pairs based on
contype/conaffinity, parent-child relationships, and explicit<exclude>tags.
- sap_broadphase(m: Model, d: Data)[source]#
Runs broadphase collision detection using a sweep-and-prune (SAP) algorithm.
This method is more efficient than the N-squared approach for large numbers of objects. It works by projecting the bounding spheres of all geoms onto a single axis and sorting them. It then sweeps along the axis, only checking for overlaps between geoms whose projections are close to each other.
For each potentially colliding pair identified by the sweep, a more precise bounding sphere check is performed. If this check passes, the pair is added to the collision arrays in
dfor the narrowphase stage.Two sorting strategies are supported, controlled by
m.opt.broadphaseSAP_TILE: Uses a tile-based sort.SAP_SEGMENTED: Uses a segmented sort.
- primitive_narrowphase(m: Model, d: Data)[source]#
Runs collision detection on primitive geom pairs discovered during broadphase.
This function processes collision pairs involving primitive shapes that were identified during the broadphase stage. It computes detailed contact information such as distance, position, and frame, and populates the
d.contactarray.The primitive geom types:
PLANE,SPHERE,CAPSULE,CYLINDER, andBOX.Additionally, collisions between planes and convex hulls.
To improve performance, it dynamically builds and launches a kernel tailored to the specific primitive collision types present in the model, avoiding unnecessary checks for non-existent collision pairs.
- deriv_smooth_vel(m: Model, d: Data, qDeriv: array(ndim=2, dtype=float32))[source]#
Analytical derivative of smooth forces w.r.t. velocities.
- Parameters:
m – The model containing kinematic and dynamic information (device).
d – The data object containing the current state and output arrays (device).
qDeriv – Analytical derivative of smooth forces w.r.t. velocity.
- fwd_acceleration(m: Model, d: Data, factorize: bool = False)[source]#
Add up all non-constraint forces, compute qacc_smooth.
- Parameters:
m – The model containing kinematic and dynamic information.
d – The data object containing the current state and output arrays.
factorize – Flag to factorize inertia matrix.
- fwd_position(m: Model, d: Data, factorize: bool = True)[source]#
Position-dependent computations.
- Parameters:
m – The model containing kinematic and dynamic information.
d – The data object containing the current state and output arrays.
factorize – Flag to factorize interia matrix.
- get_data_into(result: MjData, mjm: MjModel, d: Data, world_id: int = 0)[source]#
Gets data from a device into an existing mujoco.MjData.
- Parameters:
result – The data object containing the current state and output arrays (host).
mjm – The model containing kinematic and dynamic information (host).
d – The data object containing the current state and output arrays (device).
world_id – The id of the world to get the data from.
- make_data(mjm: MjModel, nworld: int = 1, nconmax: int | None = None, njmax: int | None = None, naconmax: int | None = None) Data[source]#
Creates a data object on device.
- Parameters:
mjm – The model containing kinematic and dynamic information (host).
nworld – Number of worlds.
nconmax – Number of contacts to allocate per world. Contacts exist in large heterogeneous arrays: one world may have more than nconmax contacts.
njmax – Number of constraints to allocate per world. Constraint arrays are batched by world: no world may have more than njmax constraints.
naconmax – Number of contacts to allocate for all worlds. Overrides nconmax.
- Returns:
The data object containing the current state and output arrays (device).
- put_data(mjm: MjModel, mjd: MjData, nworld: int = 1, nconmax: int | None = None, njmax: int | None = None, naconmax: int | None = None) Data[source]#
Moves data from host to a device.
- Parameters:
mjm – The model containing kinematic and dynamic information (host).
mjd – The data object containing current state and output arrays (host).
nworld – The number of worlds.
nconmax – Number of contacts to allocate per world. Contacts exist in large heterogenous arrays: one world may have more than nconmax contacts.
njmax – Number of constraints to allocate per world. Constraint arrays are batched by world: no world may have more than njmax constraints.
naconmax – Number of contacts to allocate for all worlds. Overrides nconmax.
- Returns:
The data object containing the current state and output arrays (device).
- put_model(mjm: MjModel) Model[source]#
Creates a model on device.
- Parameters:
mjm – The model containing kinematic and dynamic information (host).
- Returns:
The model containing kinematic and dynamic information (device).
- reset_data(m: Model, d: Data, reset: array | None = None)[source]#
Clear data, set defaults; optionally by world.
- Parameters:
m – The model containing kinematic and dynamic information (device).
d – The data object containing the current state and output arrays (device).
reset – Per-world bitmask. Reset if True.
- ray(m: Model, d: Data, pnt: array(ndim=2, dtype=vec3f), vec: array(ndim=2, dtype=vec3f), geomgroup: vec6f | None = None, flg_static: bool = True, bodyexclude: int = -1) Tuple[array, array][source]#
Returns the distance at which rays intersect with primitive geoms.
- Parameters:
m – The model containing kinematic and dynamic information (device).
d – The data object containing the current state and output arrays (device).
pnt – Ray origin points.
vec – Ray directions.
geomgroup – Group inclusion/exclusion mask. If all are wp.inf, ignore.
flg_static – If True, allows rays to intersect with static geoms.
bodyexclude – Ignore geoms on specified body id (-1 to disable).
- Returns:
Distances from ray origins to geom surfaces and IDs of intersected geoms (-1 if none).
- camlight(m: Model, d: Data)[source]#
Computes camera and light positions and orientations.
Updates the global positions and orientations for all cameras and lights in the model, including special handling for tracking and target modes.
- com_pos(m: Model, d: Data)[source]#
Computes subtree center of mass positions.
Transforms inertia and motion to global frame centered at subtree CoM. Accumulates the mass-weighted positions up the kinematic tree, divides by total mass, and computes composite inertias and motion degrees of freedom in the subtree CoM frame.
- com_vel(m: Model, d: Data)[source]#
Computes the spatial velocities (cvel) and the derivative
cdof_dotfor all bodies.Propagates velocities down the kinematic tree, updating the spatial velocity and derivative for each body.
- crb(m: Model, d: Data)[source]#
Computes composite rigid body inertias for each body and the joint-space inertia matrix.
Accumulates composite rigid body inertias up the kinematic tree and computes the joint-space inertia matrix in either sparse or dense format, depending on model options.
- kinematics(m: Model, d: Data)[source]#
Computes forward kinematics for all bodies, sites, geoms, and flexible elements.
This function updates the global positions and orientations of all bodies, as well as the derived positions and orientations of geoms, sites, and flexible elements, based on the current joint positions and any attached mocap bodies.
- rne(m: Model, d: Data, flg_acc: bool = False)[source]#
Computes inverse dynamics using the recursive Newton-Euler algorithm.
Computes the bias forces (
qfrc_bias) and internal forces (cfrc_int) for the current state, including the effects of gravity and optionally joint accelerations.- Parameters:
m – The model containing kinematic and dynamic information.
d – The data object containing the current state and output arrays.
flg_acc – If True, includes joint accelerations in the computation.
- rne_postconstraint(m: Model, d: Data)[source]#
Computes the recursive Newton-Euler algorithm after constraints are applied.
Computes
cacc,cfrc_ext, andcfrc_int, including the effects of applied forces, equality constraints, and contacts.
- solve_m(m: Model, d: Data, x: array(ndim=2, dtype=float32), y: array(ndim=2, dtype=float32))[source]#
Computes backsubstitution: x = qLD * y.
- Parameters:
m – The model containing inertia and factorization information.
d – The data object containing factorization results.
x – Output array for the solution.
y – Input right-hand side array.
- subtree_vel(m: Model, d: Data)[source]#
Computes subtree linear velocity and angular momentum.
Computes the linear momentum and angular momentum for each subtree, accumulating contributions up the kinematic tree.
- tendon(m: Model, d: Data)[source]#
Computes tendon lengths and moments.
Updates the tendon length and moment arrays for all tendons in the model, including joint, site, and geom tendons.
- transmission(m: Model, d: Data)[source]#
Computes actuator/transmission lengths and moments.
Updates the actuator length and moments for all actuators in the model, including joint and tendon transmissions.
- contact_force(m: Model, d: Data, contact_ids: array(ndim=1, dtype=int32), to_world_frame: bool, force: array(ndim=1, dtype=vector(length=6, dtype=float32)))[source]#
Compute forces for contacts in Data.
- Parameters:
m – The model containing kinematic and dynamic information (device).
d – The data object containing the current state and output arrays (device).
contact_ids – IDs for each contact.
to_world_frame – If True, map force from contact to world frame.
force – Contact forces.
- get_state(m: Model, d: Data, state: array(ndim=2, dtype=float32), sig: int, active: array | None = None)[source]#
Copy concatenated state components specified by sig from Data into state.
The bits of the integer sig correspond to element fields of State.
- Parameters:
m – The model containing kinematic and dynamic information (device).
d – The data object containing the current state and output information (device).
state – Concatenation of state components.
sig – Bitflag specifying state components.
active – Per-world bitmask for getting state.
- mul_m(m: Model, d: Data, res: array(ndim=2, dtype=float32), vec: array(ndim=2, dtype=float32), skip: array | None = None, M: array | None = None)[source]#
Multiply vectors by inertia matrix; optionally skip per world.
- Parameters:
m – The model containing kinematic and dynamic information (device).
d – The data object containing the current state and output arrays (device).
res – Result: qM @ vec.
vec – Input vector to multiply by qM.
skip – Per-world bitmask to skip computing output.
M – Input matrix: M @ vec.
- set_state(m: Model, d: Data, state: array(ndim=2, dtype=float32), sig: int, active: array | None = None)[source]#
Copy concatenated state components specified by sig from state into Data.
The bits of the integer sig correspond to element fields of State.
- Parameters:
m – The model containing kinematic and dynamic information (device).
d – The data object containing the current state and output information (device).
state – Concatenation of state components.
sig – Bitflag specifying state components.
active – Per-world bitmask for setting state.
- xfrc_accumulate(m: Model, d: Data, qfrc: array(ndim=2, dtype=float32))[source]#
Map applied forces at each body via Jacobians to dof space and accumulate.
- Parameters:
m – The model containing kinematic and dynamic information (device).
d – The data object containing the current state and output arrays (device).
qfrc – Total applied force mapped to dof space.
- class BiasType[source]#
Type of actuator bias.
- NONE#
no bias
- AFFINE#
const + kp*length + kv*velocity
- MUSCLE#
muscle passive force computed by muscle_bias
- class BroadphaseFilter[source]#
Bitmask specifying which collision functions to run during broadphase.
- PLANE#
collision between bounding sphere and plane
- SPHERE#
collision between bounding spheres
- AABB#
collision between axis-aligned bounding boxes
- OBB#
collision between oriented bounding boxes
- class BroadphaseType[source]#
Type of broadphase algorithm.
- NXN#
Broad phase checking all pairs
- SAP_TILE#
Sweep and prune broad phase using tile sort
- SAP_SEGMENTED#
Sweep and prune broad phase using segment sort
- class Constraint[source]#
Constraint data.
- type#
constraint type (ConstraintType) (nworld, njmax)
- Type:
array(ndim=2, dtype=int32)
- id#
id of object of specific type (nworld, njmax)
- Type:
array(ndim=2, dtype=int32)
- J#
constraint Jacobian (nworld, njmax_pad, nv_pad)
- Type:
array(ndim=3, dtype=float32)
- pos#
constraint position (equality, contact) (nworld, njmax)
- Type:
array(ndim=2, dtype=float32)
- margin#
inclusion margin (contact) (nworld, njmax)
- Type:
array(ndim=2, dtype=float32)
- D#
constraint mass (nworld, njmax_pad)
- Type:
array(ndim=2, dtype=float32)
- vel#
velocity in constraint space: J*qvel (nworld, njmax)
- Type:
array(ndim=2, dtype=float32)
- aref#
reference pseudo-acceleration (nworld, njmax)
- Type:
array(ndim=2, dtype=float32)
- frictionloss#
frictionloss (friction) (nworld, njmax)
- Type:
array(ndim=2, dtype=float32)
- force#
constraint force in constraint space (nworld, njmax)
- Type:
array(ndim=2, dtype=float32)
- Jaref#
Jac*qacc - aref (nworld, njmax)
- Type:
array(ndim=2, dtype=float32)
- Ma#
M*qacc (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- grad#
gradient of master cost (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- cholesky_L_tmp#
temporary for Cholesky factor (nworld, nv, nv)
- Type:
array(ndim=3, dtype=float32)
- cholesky_y_tmp#
temporary for Cholesky solve (nworld, nv
- Type:
array(ndim=2, dtype=float32)
- grad_dot#
dot(grad, grad) (nworld,)
- Type:
array(ndim=1, dtype=float32)
- Mgrad#
M / grad (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- search#
linesearch vector (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- search_dot#
dot(search, search) (nworld,)
- Type:
array(ndim=1, dtype=float32)
- gauss#
Gauss Cost (nworld,)
- Type:
array(ndim=1, dtype=float32)
- cost#
constraint + Gauss cost (nworld,)
- Type:
array(ndim=1, dtype=float32)
- prev_cost#
cost from previous iter (nworld,)
- Type:
array(ndim=1, dtype=float32)
- state#
constraint state (nworld, njmax_pad)
- Type:
array(ndim=2, dtype=int32)
- mv#
qM @ search (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- jv#
efc_J @ search (nworld, njmax)
- Type:
array(ndim=2, dtype=float32)
- quad#
quadratic cost coefficients (nworld, njmax, 3)
- Type:
array(ndim=2, dtype=vec3f)
- quad_gauss#
quadratic cost Gauss coefficients (nworld, 3)
- Type:
array(ndim=1, dtype=vec3f)
- h#
Hessian (nworld, nv_pad, nv_pad)
- Type:
array(ndim=3, dtype=float32)
- alpha#
line search step size (nworld,)
- Type:
array(ndim=1, dtype=float32)
- prev_grad#
previous grad (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- prev_Mgrad#
previous Mgrad (nworld, nv)
- Type:
array(ndim=2, dtype=float32)
- beta#
Polak-Ribiere beta (nworld,)
- Type:
array(ndim=1, dtype=float32)
- done#
solver done (nworld,)
- Type:
array(ndim=1, dtype=warp._src.types.bool)
- class Contact[source]#
Contact data.
- dist#
distance between nearest points; neg: penetration (naconmax,)
- Type:
array(ndim=1, dtype=float32)
- pos#
position of contact point: midpoint between geoms (naconmax, 3)
- Type:
array(ndim=1, dtype=vec3f)
- frame#
normal is in [0-2], points from geom[0] to geom[1] (naconmax, 3, 3)
- Type:
array(ndim=1, dtype=mat33(f))
- includemargin#
include if dist<includemargin=margin-gap (naconmax,)
- Type:
array(ndim=1, dtype=float32)
- friction#
tangent1, 2, spin, roll1, 2 (naconmax, 5)
- Type:
array(ndim=1, dtype=vector(length=5, dtype=float32))
- solref#
constraint solver reference, normal direction (naconmax, 2)
- Type:
array(ndim=1, dtype=vec2f)
- solreffriction#
constraint solver reference, friction directions (naconmax, 2)
- Type:
array(ndim=1, dtype=vec2f)
- solimp#
constraint solver impedance (naconmax, 5)
- Type:
array(ndim=1, dtype=vector(length=5, dtype=float32))
- dim#
contact space dimensionality: 1, 3, 4 or 6 (naconmax,)
- Type:
array(ndim=1, dtype=int32)
- geom#
geom ids; -1 for flex (naconmax, 2)
- Type:
array(ndim=1, dtype=vec2i)
- efc_address#
address in efc; -1: not included (naconmax, nmaxpyramid)
- Type:
array(ndim=2, dtype=int32)
- worldid#
world id (naconmax,)
- Type:
array(ndim=1, dtype=int32)
- type#
ContactType (naconmax,)
- Type:
array(ndim=1, dtype=int32)
- geomcollisionid#
i-th contact generated for geom (naconmax,) helps uniquely identity contact when multiple contacts are generated for geom pair
- Type:
array(ndim=1, dtype=int32)
- class DisableBit[source]#
Disable default feature bitflags.
- CONSTRAINT#
entire constraint solver
- EQUALITY#
equality constraints
- FRICTIONLOSS#
joint and tendon frictionloss constraints
- LIMIT#
joint and tendon limit constraints
- CONTACT#
contact constraints
- SPRING#
passive spring forces
- DAMPER#
passive damper forces
- GRAVITY#
gravitational forces
- CLAMPCTRL#
clamp control to specified range
- WARMSTART#
warmstart constraint solver
- FILTERPARENT#
disable collisions between parent and child bodies
- ACTUATION#
apply actuation forces
- REFSAFE#
integrator safety: make ref[0]>=2*timestep
- SENSOR#
sensors
- EULERDAMP#
implicit damping for Euler integration
- NATIVECCD#
native convex collision detection (ignored in MJWarp)
- class DynType[source]#
Type of actuator dynamics.
- NONE#
no internal dynamics; ctrl specifies force
- INTEGRATOR#
integrator: da/dt = u
- FILTER#
linear filter: da/dt = (u-a) / tau
- FILTEREXACT#
linear filter: da/dt = (u-a) / tau, with exact integration
- MUSCLE#
piece-wise linear filter with two time constants
- class EnableBit[source]#
Enable optional feature bitflags.
- ENERGY#
energy computation
- INVDISCRETE#
discrete-time inverse dynamics
- class GainType[source]#
Type of actuator gain.
- FIXED#
fixed gain
- AFFINE#
const + kp*length + kv*velocity
- MUSCLE#
muscle FLV curve computed by muscle_gain
- class GeomType[source]#
Type of geometry.
- PLANE#
plane
- HFIELD#
heightfield
- SPHERE#
sphere
- CAPSULE#
capsule
- ELLIPSOID#
ellipsoid
- CYLINDER#
cylinder
- BOX#
box
- MESH#
mesh
- SDF#
sdf
- class IntegratorType[source]#
Integrator mode.
- EULER#
semi-implicit Euler
- RK4#
4th-order Runge Kutta
- IMPLICITFAST#
implicit in velocity, no rne derivative
- class JointType[source]#
Type of degree of freedom.
- FREE#
global position and orientation (quat) (7,)
- BALL#
orientation (quat) relative to parent (4,)
- SLIDE#
sliding distance along body-fixed axis (1,)
- HINGE#
rotation angle (rad) around body-fixed axis (1,)
- class Option[source]#
Physics options.
- timestep#
simulation timestep
- Type:
array(ndim=1, dtype=float32)
- impratio#
ratio of friction-to-normal contact impedance
- Type:
array(ndim=1, dtype=float32)
- tolerance#
main solver tolerance
- Type:
array(ndim=1, dtype=float32)
- ls_tolerance#
CG/Newton linesearch tolerance
- Type:
array(ndim=1, dtype=float32)
- ccd_tolerance#
convex collision detection tolerance
- Type:
array(ndim=1, dtype=float32)
- density#
density of medium
- Type:
array(ndim=1, dtype=float32)
- viscosity#
viscosity of medium
- Type:
array(ndim=1, dtype=float32)
- gravity#
gravitational acceleration
- Type:
array(ndim=1, dtype=vec3f)
- wind#
wind (for lift, drag, and viscosity)
- Type:
array(ndim=1, dtype=vec3f)
- magnetic#
global magnetic flux
- Type:
array(ndim=1, dtype=vec3f)
- integrator#
integration mode (IntegratorType)
- Type:
int
- cone#
type of friction cone (ConeType)
- Type:
int
- solver#
solver algorithm (SolverType)
- Type:
int
- iterations#
number of main solver iterations
- Type:
int
- ls_iterations#
maximum number of CG/Newton linesearch iterations
- Type:
int
- ccd_iterations#
number of iterations in convex collision detection
- Type:
int
- disableflags#
bit flags for disabling standard features
- Type:
int
- enableflags#
bit flags for enabling optional features
- Type:
int
- sdf_initpoints#
number of starting points for gradient descent
- Type:
int
- sdf_iterations#
max number of iterations for gradient descent
- Type:
int
- is_sparse#
whether to use sparse representations
- Type:
bool
- ls_parallel#
evaluate engine solver step sizes in parallel
- Type:
bool
- ls_parallel_min_step#
minimum step size for solver linesearch
- Type:
float
- has_fluid#
True if wind, density, or viscosity are non-zero at put_model time
- Type:
bool
- broadphase#
broadphase type (BroadphaseType)
- broadphase_filter#
broadphase filter bitflag (BroadphaseFilter)
- graph_conditional#
flag to use cuda graph conditional
- Type:
bool
- run_collision_detection#
if False, skips collision detection and allows user-populated contacts during the physics step (as opposed to DisableBit.CONTACT which explicitly zeros out the contacts at each step)
- Type:
bool
- contact_sensor_maxmatch#
max number of contacts considered by contact sensor matching criteria contacts matched after this value is exceded will be ignored
- Type:
int
- class SolverType[source]#
Constraint solver algorithm.
- CG#
Conjugate gradient (primal)
- NEWTON#
Newton (primal)
- class State[source]#
State component elements as integer bitflags.
Includes several convenient combinations of these flags.
- TIME#
time
- QPOS#
position
- QVEL#
velocity
- ACT#
actuator activation
- WARMSTART#
acceleration used for warmstart
- CTRL#
control
- QFRC_APPLIED#
applied generalized force
- XFRC_APPLIED#
applied Cartesian force/torque
- EQ_ACTIVE#
enable/disable constraints
- MOCAP_POS#
positions of mocap bodies
- MOCAP_QUAT#
orientations of mocap bodies
- NSTATE#
number of state elements
- PHYSICS#
QPOS | QVEL | ACT
- FULLPHYSICS#
TIME | PHYSICS | PLUGIN
- USER#
CTRL | QFRC_APPLIED | XFRC_APPLIED | EQ_ACTIVE | MOCAP_POS | MOCAP_QUAT | USERDATA
- INTEGRATION#
FULLPHYSICS | USER | WARMSTART