Source code for mujoco_warp._src.types

# Copyright 2025 The Newton Developers
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
#     http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
# ==============================================================================
import dataclasses
import enum
from typing import Callable

import mujoco
from mujoco_warp._src.util_pkg import check_version
import numpy as np
import warp as wp

MJ_MINVAL = mujoco.mjMINVAL
MJ_MAXVAL = mujoco.mjMAXVAL
MJ_MINIMP = mujoco.mjMINIMP  # minimum constraint impedance
MJ_MAXIMP = mujoco.mjMAXIMP  # maximum constraint impedance
MJ_MAXCONPAIR = mujoco.mjMAXCONPAIR
MJ_MINMU = mujoco.mjMINMU  # minimum friction
# True if MuJoCo >= 3.9.0 (new margin/gap semantics: includemargin = margin)
_NEW_GAP_SEMANTICS = check_version("mujoco>=3.9.0")
# maximum size (by number of edges) of an horizon in EPA algorithm
MJ_MAX_EPAHORIZON = 24
# maximum average number of trianglarfaces EPA can insert at each iteration
MJ_MAX_EPAFACES = 5

TILE_SIZE_JTDAJ_SPARSE = 16
TILE_SIZE_JTDAJ_DENSE = 16

# maximum number of plugin attributes
_NPLUGINATTR = 128


# TODO(team): add check that all wp.launch_tiled 'block_dim' settings are configurable
@dataclasses.dataclass
class BlockDim:
  """Block dimension 'block_dim' settings for wp.launch_tiled.

  TODO(team): experimental and may be removed
  """

  # collision_driver
  segmented_sort: int = 128
  # forward
  euler_dense: int = 32
  actuator_velocity: int = 32
  # ray
  ray: int = 64
  # sensor
  contact_sort: int = 64
  energy_vel_kinetic: int = 32
  # smooth
  cholesky_factorize: int = 32
  cholesky_solve: int = 32
  cholesky_factorize_solve: int = 32
  solve_LD_sparse_fused: int = 64
  # solver
  update_gradient_cholesky: int = 64
  update_gradient_cholesky_blocked: int = 32
  update_gradient_JTDAJ_sparse: int = 64
  update_gradient_JTDAJ_dense: int = 96
  linesearch_iterative: int = 32
  contact_jac_tiled: int = 32
  # derivative
  qderiv_actuator_dense: int = 32


[docs] class BroadphaseType(enum.IntEnum): """Type of broadphase algorithm. Attributes: 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 """ NXN = 0 SAP_TILE = 1 SAP_SEGMENTED = 2
[docs] class BroadphaseFilter(enum.IntFlag): """Bitmask specifying which collision functions to run during broadphase. Attributes: 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 """ PLANE = 1 SPHERE = 2 AABB = 4 OBB = 8
class CamLightType(enum.IntEnum): """Type of camera light. Attributes: FIXED: pos and rot fixed in body TRACK: pos tracks body, rot fixed in global TRACKCOM: pos tracks subtree com, rot fixed in body TARGETBODY: pos fixed in body, rot tracks target body TARGETBODYCOM: pos fixed in body, rot tracks target subtree com """ FIXED = mujoco.mjtCamLight.mjCAMLIGHT_FIXED TRACK = mujoco.mjtCamLight.mjCAMLIGHT_TRACK TRACKCOM = mujoco.mjtCamLight.mjCAMLIGHT_TRACKCOM TARGETBODY = mujoco.mjtCamLight.mjCAMLIGHT_TARGETBODY TARGETBODYCOM = mujoco.mjtCamLight.mjCAMLIGHT_TARGETBODYCOM class ProjectionType(enum.IntEnum): """Type of camera projection. Attributes: PERSPECTIVE: perspective projection ORTHOGRAPHIC: orthographic projection """ # TODO(team): remove after mjwarp depends on mujoco > 3.4.0 in pyproject.toml if hasattr(mujoco, "mjtProjection"): PERSPECTIVE = mujoco.mjtProjection.mjPROJ_PERSPECTIVE ORTHOGRAPHIC = mujoco.mjtProjection.mjPROJ_ORTHOGRAPHIC else: PERSPECTIVE = 0 ORTHOGRAPHIC = 1 class Stage(enum.IntEnum): """Computation stage. Attributes: POS: position-dependent VEL: velocity-dependent ACC: acceleration/force-dependent """ POS = mujoco.mjtStage.mjSTAGE_POS VEL = mujoco.mjtStage.mjSTAGE_VEL ACC = mujoco.mjtStage.mjSTAGE_ACC class DataType(enum.IntFlag): """Sensor data types. Attributes: REAL: real values, no constraints POSITIVE: positive values, 0 or negative: inactive """ REAL = mujoco.mjtDataType.mjDATATYPE_REAL POSITIVE = mujoco.mjtDataType.mjDATATYPE_POSITIVE # unsupported: AXIS, QUATERNION
[docs] class DisableBit(enum.IntFlag): """Disable default feature bitflags. Attributes: 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) ISLAND: constraint islands """ CONSTRAINT = mujoco.mjtDisableBit.mjDSBL_CONSTRAINT EQUALITY = mujoco.mjtDisableBit.mjDSBL_EQUALITY FRICTIONLOSS = mujoco.mjtDisableBit.mjDSBL_FRICTIONLOSS LIMIT = mujoco.mjtDisableBit.mjDSBL_LIMIT CONTACT = mujoco.mjtDisableBit.mjDSBL_CONTACT SPRING = mujoco.mjtDisableBit.mjDSBL_SPRING DAMPER = mujoco.mjtDisableBit.mjDSBL_DAMPER GRAVITY = mujoco.mjtDisableBit.mjDSBL_GRAVITY CLAMPCTRL = mujoco.mjtDisableBit.mjDSBL_CLAMPCTRL WARMSTART = mujoco.mjtDisableBit.mjDSBL_WARMSTART FILTERPARENT = mujoco.mjtDisableBit.mjDSBL_FILTERPARENT ACTUATION = mujoco.mjtDisableBit.mjDSBL_ACTUATION REFSAFE = mujoco.mjtDisableBit.mjDSBL_REFSAFE SENSOR = mujoco.mjtDisableBit.mjDSBL_SENSOR EULERDAMP = mujoco.mjtDisableBit.mjDSBL_EULERDAMP NATIVECCD = mujoco.mjtDisableBit.mjDSBL_NATIVECCD ISLAND = mujoco.mjtDisableBit.mjDSBL_ISLAND MULTICCD = mujoco.mjtDisableBit.mjDSBL_MULTICCD
# unsupported: MIDPHASE, AUTORESET
[docs] class EnableBit(enum.IntFlag): """Enable optional feature bitflags. Attributes: ENERGY: energy computation INVDISCRETE: discrete-time inverse dynamics MULTICCD: multiple contacts with CCD """ ENERGY = mujoco.mjtEnableBit.mjENBL_ENERGY INVDISCRETE = mujoco.mjtEnableBit.mjENBL_INVDISCRETE
# unsupported: OVERRIDE, FWDINV, ISLAND
[docs] class TrnType(enum.IntEnum): """Type of actuator transmission. Attributes: JOINT: force on joint JOINTINPARENT: force on joint, expressed in parent frame SLIDERCRANK: force via slider-crank linkage TENDON: force on tendon BODY: adhesion force on body's geoms SITE: force on site """ JOINT = mujoco.mjtTrn.mjTRN_JOINT JOINTINPARENT = mujoco.mjtTrn.mjTRN_JOINTINPARENT SLIDERCRANK = mujoco.mjtTrn.mjTRN_SLIDERCRANK TENDON = mujoco.mjtTrn.mjTRN_TENDON BODY = mujoco.mjtTrn.mjTRN_BODY SITE = mujoco.mjtTrn.mjTRN_SITE
[docs] class DynType(enum.IntEnum): """Type of actuator dynamics. Attributes: 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 USER: user-defined dynamics via act_dyn_callback DCMOTOR: DC motor dynamics """ NONE = mujoco.mjtDyn.mjDYN_NONE INTEGRATOR = mujoco.mjtDyn.mjDYN_INTEGRATOR FILTER = mujoco.mjtDyn.mjDYN_FILTER FILTEREXACT = mujoco.mjtDyn.mjDYN_FILTEREXACT MUSCLE = mujoco.mjtDyn.mjDYN_MUSCLE USER = mujoco.mjtDyn.mjDYN_USER DCMOTOR = mujoco.mjtDyn.mjDYN_DCMOTOR
[docs] class GainType(enum.IntEnum): """Type of actuator gain. Attributes: FIXED: fixed gain AFFINE: const + kp*length + kv*velocity MUSCLE: muscle FLV curve computed by muscle_gain USER: user-defined gain via act_gain_callback DCMOTOR: DC motor gain """ FIXED = mujoco.mjtGain.mjGAIN_FIXED AFFINE = mujoco.mjtGain.mjGAIN_AFFINE MUSCLE = mujoco.mjtGain.mjGAIN_MUSCLE USER = mujoco.mjtGain.mjGAIN_USER DCMOTOR = mujoco.mjtGain.mjGAIN_DCMOTOR
[docs] class BiasType(enum.IntEnum): """Type of actuator bias. Attributes: NONE: no bias AFFINE: const + kp*length + kv*velocity MUSCLE: muscle passive force computed by muscle_bias USER: user-defined bias via act_bias_callback DCMOTOR: DC motor back-EMF bias """ NONE = mujoco.mjtBias.mjBIAS_NONE AFFINE = mujoco.mjtBias.mjBIAS_AFFINE MUSCLE = mujoco.mjtBias.mjBIAS_MUSCLE USER = mujoco.mjtBias.mjBIAS_USER DCMOTOR = mujoco.mjtBias.mjBIAS_DCMOTOR
[docs] class JointType(enum.IntEnum): """Type of degree of freedom. Attributes: 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,) """ FREE = mujoco.mjtJoint.mjJNT_FREE BALL = mujoco.mjtJoint.mjJNT_BALL SLIDE = mujoco.mjtJoint.mjJNT_SLIDE HINGE = mujoco.mjtJoint.mjJNT_HINGE
[docs] class ConeType(enum.IntEnum): """Type of friction cone. Attributes: PYRAMIDAL: pyramidal ELLIPTIC: elliptic """ PYRAMIDAL = mujoco.mjtCone.mjCONE_PYRAMIDAL ELLIPTIC = mujoco.mjtCone.mjCONE_ELLIPTIC
[docs] class IntegratorType(enum.IntEnum): """Integrator mode. Attributes: EULER: semi-implicit Euler RK4: 4th-order Runge Kutta IMPLICITFAST: implicit in velocity, no rne derivative """ EULER = mujoco.mjtIntegrator.mjINT_EULER RK4 = mujoco.mjtIntegrator.mjINT_RK4 IMPLICITFAST = mujoco.mjtIntegrator.mjINT_IMPLICITFAST
# unsupported: IMPLICIT
[docs] class GeomType(enum.IntEnum): """Type of geometry. Attributes: PLANE: plane HFIELD: heightfield SPHERE: sphere CAPSULE: capsule ELLIPSOID: ellipsoid CYLINDER: cylinder BOX: box MESH: mesh SDF: sdf FLEX: flex """ PLANE = mujoco.mjtGeom.mjGEOM_PLANE HFIELD = mujoco.mjtGeom.mjGEOM_HFIELD SPHERE = mujoco.mjtGeom.mjGEOM_SPHERE CAPSULE = mujoco.mjtGeom.mjGEOM_CAPSULE ELLIPSOID = mujoco.mjtGeom.mjGEOM_ELLIPSOID CYLINDER = mujoco.mjtGeom.mjGEOM_CYLINDER BOX = mujoco.mjtGeom.mjGEOM_BOX MESH = mujoco.mjtGeom.mjGEOM_MESH SDF = mujoco.mjtGeom.mjGEOM_SDF FLEX = mujoco.mjtGeom.mjGEOM_FLEX
# unsupported: NGEOMTYPES, ARROW*, LINE, SKIN, LABEL, NONE class CollisionType(enum.IntEnum): """Type of narrowphase collision. Attributes: PRIMITIVE: primitive collision CONVEX: convex collision (CCD) SDF: sdf collision """ PRIMITIVE = 0 CONVEX = 1 SDF = 2
[docs] class SolverType(enum.IntEnum): """Constraint solver algorithm. Attributes: CG: Conjugate gradient (primal) NEWTON: Newton (primal) """ CG = mujoco.mjtSolver.mjSOL_CG NEWTON = mujoco.mjtSolver.mjSOL_NEWTON
# unsupported: PGS class ConstraintState(enum.IntEnum): """State of constraint. Attributes: SATISFIED: constraint satisfied, zero cost (limit, contact) QUADRATIC: quadratic cost (equality, friction, limit, contact) LINEARNEG: linear cost, negative side (friction) LINEARPOS: linear cost, positive side (friction) CONE: square distance to cone cost (elliptic contact) """ SATISFIED = mujoco.mjtConstraintState.mjCNSTRSTATE_SATISFIED QUADRATIC = mujoco.mjtConstraintState.mjCNSTRSTATE_QUADRATIC LINEARNEG = mujoco.mjtConstraintState.mjCNSTRSTATE_LINEARNEG LINEARPOS = mujoco.mjtConstraintState.mjCNSTRSTATE_LINEARPOS CONE = mujoco.mjtConstraintState.mjCNSTRSTATE_CONE class ConstraintType(enum.IntEnum): """Type of constraint. Attributes: EQUALITY: equality constraint FRICTION_DOF: dof friction FRICTION_TENDON: tendon friction LIMIT_JOINT: joint limit LIMIT_TENDON: tendon limit CONTACT_FRICTIONLESS: frictionless contact CONTACT_PYRAMIDAL: frictional contact, pyramidal friction cone CONTACT_ELLIPTIC: frictional contact, elliptic friction cone """ EQUALITY = mujoco.mjtConstraint.mjCNSTR_EQUALITY FRICTION_DOF = mujoco.mjtConstraint.mjCNSTR_FRICTION_DOF FRICTION_TENDON = mujoco.mjtConstraint.mjCNSTR_FRICTION_TENDON LIMIT_JOINT = mujoco.mjtConstraint.mjCNSTR_LIMIT_JOINT LIMIT_TENDON = mujoco.mjtConstraint.mjCNSTR_LIMIT_TENDON CONTACT_FRICTIONLESS = mujoco.mjtConstraint.mjCNSTR_CONTACT_FRICTIONLESS CONTACT_PYRAMIDAL = mujoco.mjtConstraint.mjCNSTR_CONTACT_PYRAMIDAL CONTACT_ELLIPTIC = mujoco.mjtConstraint.mjCNSTR_CONTACT_ELLIPTIC class SensorType(enum.IntEnum): """Type of sensor. Attributes: MAGNETOMETER: magnetometer CAMPROJECTION: camera projection RANGEFINDER: scalar distance to nearest geom or site along z-axis JOINTPOS: joint position TENDONPOS: scalar tendon position ACTUATORPOS: actuator position BALLQUAT: ball joint orientation JOINTLIMITPOS: joint limit distance-margin TENDONLIMITPOS: tendon limit distance-margin FRAMEPOS: frame position FRAMEXAXIS: frame x-axis FRAMEYAXIS: frame y-axis FRAMEZAXIS: frame z-axis FRAMEQUAT: frame orientation, represented as quaternion SUBTREECOM: subtree center of mass GEOMDIST: signed distance between two geoms GEOMNORMAL: normal direction between two geoms GEOMFROMTO: segment between two geoms INSIDESITE: 1 if object is inside site, 0 otherwise E_POTENTIAL: potential energy E_KINETIC: kinetic energy CLOCK: simulation time VELOCIMETER: 3D linear velocity, in local frame GYRO: 3D angular velocity, in local frame JOINTVEL: joint velocity TENDONVEL: scalar tendon velocity ACTUATORVEL: actuator velocity BALLANGVEL: ball joint angular velocity JOINTLIMITVEL: joint limit velocity TENDONLIMITVEL: tendon limit velocity FRAMELINVEL: 3D linear velocity FRAMEANGVEL: 3D angular velocity SUBTREELINVEL: subtree linear velocity SUBTREEANGMOM: subtree angular momentum TOUCH: scalar contact normal forces summed over sensor zone CONTACT: contacts which occurred during the simulation ACCELEROMETER: accelerometer FORCE: force TORQUE: torque ACTUATORFRC: scalar actuator force, measured at the joint TENDONACTFRC: scalar actuator force, measured at the tendon JOINTACTFRC: scalar actuator force, measured at the joint JOINTLIMITFRC: joint limit force TENDONLIMITFRC: tendon limit force FRAMELINACC: 3D linear acceleration FRAMEANGACC: 3D angular acceleration TACTILE: tactile sensor USER: user-defined sensor via sensor_callback """ MAGNETOMETER = mujoco.mjtSensor.mjSENS_MAGNETOMETER CAMPROJECTION = mujoco.mjtSensor.mjSENS_CAMPROJECTION RANGEFINDER = mujoco.mjtSensor.mjSENS_RANGEFINDER JOINTPOS = mujoco.mjtSensor.mjSENS_JOINTPOS TENDONPOS = mujoco.mjtSensor.mjSENS_TENDONPOS ACTUATORPOS = mujoco.mjtSensor.mjSENS_ACTUATORPOS BALLQUAT = mujoco.mjtSensor.mjSENS_BALLQUAT JOINTLIMITPOS = mujoco.mjtSensor.mjSENS_JOINTLIMITPOS TENDONLIMITPOS = mujoco.mjtSensor.mjSENS_TENDONLIMITPOS FRAMEPOS = mujoco.mjtSensor.mjSENS_FRAMEPOS FRAMEXAXIS = mujoco.mjtSensor.mjSENS_FRAMEXAXIS FRAMEYAXIS = mujoco.mjtSensor.mjSENS_FRAMEYAXIS FRAMEZAXIS = mujoco.mjtSensor.mjSENS_FRAMEZAXIS FRAMEQUAT = mujoco.mjtSensor.mjSENS_FRAMEQUAT SUBTREECOM = mujoco.mjtSensor.mjSENS_SUBTREECOM GEOMDIST = mujoco.mjtSensor.mjSENS_GEOMDIST GEOMNORMAL = mujoco.mjtSensor.mjSENS_GEOMNORMAL GEOMFROMTO = mujoco.mjtSensor.mjSENS_GEOMFROMTO INSIDESITE = mujoco.mjtSensor.mjSENS_INSIDESITE E_POTENTIAL = mujoco.mjtSensor.mjSENS_E_POTENTIAL E_KINETIC = mujoco.mjtSensor.mjSENS_E_KINETIC CLOCK = mujoco.mjtSensor.mjSENS_CLOCK VELOCIMETER = mujoco.mjtSensor.mjSENS_VELOCIMETER GYRO = mujoco.mjtSensor.mjSENS_GYRO JOINTVEL = mujoco.mjtSensor.mjSENS_JOINTVEL TENDONVEL = mujoco.mjtSensor.mjSENS_TENDONVEL ACTUATORVEL = mujoco.mjtSensor.mjSENS_ACTUATORVEL BALLANGVEL = mujoco.mjtSensor.mjSENS_BALLANGVEL JOINTLIMITVEL = mujoco.mjtSensor.mjSENS_JOINTLIMITVEL TENDONLIMITVEL = mujoco.mjtSensor.mjSENS_TENDONLIMITVEL FRAMELINVEL = mujoco.mjtSensor.mjSENS_FRAMELINVEL FRAMEANGVEL = mujoco.mjtSensor.mjSENS_FRAMEANGVEL SUBTREELINVEL = mujoco.mjtSensor.mjSENS_SUBTREELINVEL SUBTREEANGMOM = mujoco.mjtSensor.mjSENS_SUBTREEANGMOM TOUCH = mujoco.mjtSensor.mjSENS_TOUCH CONTACT = mujoco.mjtSensor.mjSENS_CONTACT ACCELEROMETER = mujoco.mjtSensor.mjSENS_ACCELEROMETER FORCE = mujoco.mjtSensor.mjSENS_FORCE TORQUE = mujoco.mjtSensor.mjSENS_TORQUE ACTUATORFRC = mujoco.mjtSensor.mjSENS_ACTUATORFRC TENDONACTFRC = mujoco.mjtSensor.mjSENS_TENDONACTFRC JOINTACTFRC = mujoco.mjtSensor.mjSENS_JOINTACTFRC JOINTLIMITFRC = mujoco.mjtSensor.mjSENS_JOINTLIMITFRC TENDONLIMITFRC = mujoco.mjtSensor.mjSENS_TENDONLIMITFRC FRAMELINACC = mujoco.mjtSensor.mjSENS_FRAMELINACC FRAMEANGACC = mujoco.mjtSensor.mjSENS_FRAMEANGACC TACTILE = mujoco.mjtSensor.mjSENS_TACTILE USER = mujoco.mjtSensor.mjSENS_USER
[docs] class ObjType(enum.IntEnum): """Type of object. Attributes: UNKNOWN: unknown object type BODY: body XBODY: body, used to access regular frame instead of i-frame GEOM: geom FLEX: flex SITE: site CAMERA: camera """ UNKNOWN = mujoco.mjtObj.mjOBJ_UNKNOWN BODY = mujoco.mjtObj.mjOBJ_BODY XBODY = mujoco.mjtObj.mjOBJ_XBODY GEOM = mujoco.mjtObj.mjOBJ_GEOM FLEX = mujoco.mjtObj.mjOBJ_FLEX SITE = mujoco.mjtObj.mjOBJ_SITE CAMERA = mujoco.mjtObj.mjOBJ_CAMERA
class EqType(enum.IntEnum): """Type of equality constraint. Attributes: CONNECT: connect two bodies at a point (ball joint) JOINT: couple the values of two scalar joints with cubic WELD: fix relative position and orientation of two bodies TENDON: couple the lengths of two tendons with cubic FLEX: couple the edge lengths of a flex """ CONNECT = mujoco.mjtEq.mjEQ_CONNECT WELD = mujoco.mjtEq.mjEQ_WELD JOINT = mujoco.mjtEq.mjEQ_JOINT TENDON = mujoco.mjtEq.mjEQ_TENDON FLEX = mujoco.mjtEq.mjEQ_FLEX # unsupported: DISTANCE class WrapType(enum.IntEnum): """Type of tendon wrapping object. Attributes: JOINT: constant moment arm PULLEY: pulley used to split tendon SITE: pass through site SPHERE: wrap around sphere CYLINDER: wrap around (infinite) cylinder """ JOINT = mujoco.mjtWrap.mjWRAP_JOINT PULLEY = mujoco.mjtWrap.mjWRAP_PULLEY SITE = mujoco.mjtWrap.mjWRAP_SITE SPHERE = mujoco.mjtWrap.mjWRAP_SPHERE CYLINDER = mujoco.mjtWrap.mjWRAP_CYLINDER
[docs] class State(enum.IntEnum): """State component elements as integer bitflags. Includes several convenient combinations of these flags. Attributes: 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 """ TIME = mujoco.mjtState.mjSTATE_TIME QPOS = mujoco.mjtState.mjSTATE_QPOS QVEL = mujoco.mjtState.mjSTATE_QVEL ACT = mujoco.mjtState.mjSTATE_ACT WARMSTART = mujoco.mjtState.mjSTATE_WARMSTART CTRL = mujoco.mjtState.mjSTATE_CTRL QFRC_APPLIED = mujoco.mjtState.mjSTATE_QFRC_APPLIED XFRC_APPLIED = mujoco.mjtState.mjSTATE_XFRC_APPLIED EQ_ACTIVE = mujoco.mjtState.mjSTATE_EQ_ACTIVE MOCAP_POS = mujoco.mjtState.mjSTATE_MOCAP_POS MOCAP_QUAT = mujoco.mjtState.mjSTATE_MOCAP_QUAT NSTATE = mujoco.mjtState.mjNSTATE PHYSICS = mujoco.mjtState.mjSTATE_PHYSICS FULLPHYSICS = mujoco.mjtState.mjSTATE_FULLPHYSICS USER = mujoco.mjtState.mjSTATE_USER INTEGRATION = mujoco.mjtState.mjSTATE_INTEGRATION
# unsupported: USERDATA, PLUGIN class vec5f(wp.types.vector(length=5, dtype=float)): pass class vec6f(wp.types.vector(length=6, dtype=float)): pass class vec6i(wp.types.vector(length=6, dtype=int)): pass class vec8f(wp.types.vector(length=8, dtype=float)): pass class vec8i(wp.types.vector(length=8, dtype=int)): pass class vec10f(wp.types.vector(length=10, dtype=float)): pass class vec11f(wp.types.vector(length=11, dtype=float)): pass class vec_pluginattr(wp.types.vector(length=_NPLUGINATTR, dtype=float)): pass class mat23f(wp.types.matrix(shape=(2, 3), dtype=float)): pass class mat43f(wp.types.matrix(shape=(4, 3), dtype=float)): pass class mat63f(wp.types.matrix(shape=(6, 3), dtype=float)): pass vec5 = vec5f vec6 = vec6f vec8 = vec8f vec10 = vec10f vec11 = vec11f vec128 = vec_pluginattr mat23 = mat23f mat43 = mat43f mat63 = mat63f def array(*args) -> wp.array: """A wrapper around wp.array that adds extra metadata to ease type introspection. Format is array(dim_1, dim_2, ..., dtype). dim may be a constant int, or reference a size from Model or Data (e.g. "nq" or "nworld"). dim may also be "*", which means any nonzero size. """ shape, dtype = args[:-1], args[-1] arr = wp.array(ndim=len(shape), dtype=dtype) arr.shape = shape return arr
[docs] @dataclasses.dataclass class Option: """Physics options. Attributes: timestep: simulation timestep tolerance: main solver tolerance ls_tolerance: CG/Newton linesearch tolerance ccd_tolerance: convex collision detection tolerance gravity: gravitational acceleration wind: wind (for lift, drag, and viscosity) magnetic: global magnetic flux density: density of medium viscosity: viscosity of medium integrator: integration mode (IntegratorType) cone: type of friction cone (ConeType) solver: solver algorithm (SolverType) iterations: number of main solver iterations ls_iterations: maximum number of CG/Newton linesearch iterations ccd_iterations: number of iterations in convex collision detection disableflags: bit flags for disabling standard features enableflags: bit flags for enabling optional features sdf_initpoints: number of starting points for gradient descent sdf_iterations: max number of iterations for gradient descent warp only fields: impratio_invsqrt: ratio of friction-to-normal contact impedance (stored as inverse square root) ls_parallel: evaluate engine solver step sizes in parallel ls_parallel_min_step: minimum step size for solver linesearch broadphase: broadphase type (BroadphaseType) broadphase_filter: broadphase filter bitflag (BroadphaseFilter) graph_conditional: flag to use cuda graph conditional 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) contact_sensor_maxmatch: max number of contacts considered by contact sensor matching criteria contacts matched after this value is exceded will be ignored """ timestep: wp.array[float] tolerance: wp.array[float] ls_tolerance: wp.array[float] ccd_tolerance: wp.array[float] gravity: wp.array[wp.vec3] wind: wp.array[wp.vec3] magnetic: wp.array[wp.vec3] density: wp.array[float] viscosity: wp.array[float] integrator: int cone: int solver: int iterations: int ls_iterations: int ccd_iterations: int disableflags: int enableflags: int sdf_initpoints: int sdf_iterations: int # warp only fields: impratio_invsqrt: wp.array[float] ls_parallel: bool ls_parallel_min_step: float broadphase: BroadphaseType broadphase_filter: BroadphaseFilter graph_conditional: bool run_collision_detection: bool contact_sensor_maxmatch: int
[docs] @dataclasses.dataclass class Statistic: """Model statistics (in qpos0). Attributes: meaninertia: mean diagonal inertia (per-world) """ meaninertia: wp.array[float]
@dataclasses.dataclass class TileSet: """Tiling configuration for decomposable block diagonal matrix. For non-square, non-block-diagonal tiles, use two tilesets. Attributes: adr: address of each tile in the set size: size of all the tiles in this set """ adr: wp.array[int] size: int def __eq__(self, other) -> bool: if self.__class__ is not other.__class__: return NotImplemented return self.size == other.size and np.array_equal(np.asarray(self.adr.numpy()), np.asarray(other.adr.numpy())) def __hash__(self) -> int: adr = np.asarray(self.adr.numpy()) return hash((self.size, adr.dtype.str, adr.shape, adr.tobytes()))
[docs] @dataclasses.dataclass class Callback: """Callbacks for custom physics behavior. Attributes: passive: custom passive forces, writes to ``Data.qfrc_passive`` control: custom control laws, writes to ``Data.ctrl`` act_dyn: custom actuator dynamics, writes to ``Data.act_dot`` act_gain: custom actuator gains, writes to ``Data.actuator_force`` act_bias: custom actuator biases, writes to ``Data.actuator_force`` sensor: custom sensors, writes to ``Data.sensordata`` contactfilter: custom contact filtering, writes to ``Data.contact`` """ passive: Callable | None = None control: Callable | None = None act_dyn: Callable | None = None act_gain: Callable | None = None act_bias: Callable | None = None sensor: Callable | None = None contactfilter: Callable | None = None
[docs] @dataclasses.dataclass class Model: """Model definition and parameters. Attributes: nq: number of generalized coordinates nv: number of degrees of freedom nu: number of actuators/controls na: number of activation states nbody: number of bodies noct: number of total octree cells in all meshes njnt: number of joints ntree: number of kinematic trees nM: number of non-zeros in sparse inertia matrix nC: number of non-zeros in sparse body-dof matrix ngeom: number of geoms nsite: number of sites ncam: number of cameras nlight: number of lights nflex: number of flexes nflexvert: number of vertices in all flexes nflexedge: number of edges in all flexes nflexelem: number of elements in all flexes nflexelemdata: number of element vertex ids in all flexes nflexstiffness: number of stiffness parameters in all flexes nflexbending: number of bending parameters in all flexes nflexelemedge: number of element edge ids in all flexes nflexshelldata: number of shell fragment vertex ids in all flexes nJfe: number of non-zeros in sparse flexedge Jacobian nmesh: number of meshes nmeshvert: number of vertices for all meshes nmeshnormal: number of normals in all meshes nmeshface: number of faces for all meshes nmeshgraph: number of ints in mesh auxiliary data nmeshpoly: number of polygons in all meshes nmeshpolyvert: number of vertices in all polygons nmeshpolymap: number of polygons in vertex map nhfield: number of heightfields nhfielddata: size of elevation data nmat: number of materials npair: number of predefined geom pairs nexclude: number of excluded geom pairs neq: number of equality constraints ntendon: number of tendons nJten: number of non-zeros in sparse tendon Jacobian nwrap: number of wrap objects in all tendon paths nsensor: number of sensors nmocap: number of mocap bodies nplugin: number of plugin instances nJmom: number of non-zeros in actuator_moment ngravcomp: number of bodies with nonzero gravcomp nsensordata: number of elements in sensor data vector opt: physics options stat: model statistics qpos0: qpos values at default pose (*, nq) qpos_spring: reference pose for springs (*, nq) body_parentid: id of body's parent (nbody,) body_rootid: id of root above body (nbody,) body_weldid: id of body that this body is welded to (nbody,) body_mocapid: id of mocap data; -1: none (nbody,) body_jntnum: number of joints for this body (nbody,) body_jntadr: start addr of joints; -1: no joints (nbody,) body_dofnum: number of motion degrees of freedom (nbody,) body_dofadr: start addr of dofs; -1: no dofs (nbody,) body_treeid: id of body's tree; -1: static (nbody,) body_geomnum: number of geoms (nbody,) body_geomadr: start addr of geoms; -1: no geoms (nbody,) body_pos: position offset rel. to parent body (*, nbody, 3) body_quat: orientation offset rel. to parent body (*, nbody, 4) body_ipos: local position of center of mass (*, nbody, 3) body_iquat: local orientation of inertia ellipsoid (*, nbody, 4) body_mass: mass (*, nbody,) body_subtreemass: mass of subtree starting at this body (*, nbody,) body_inertia: diagonal inertia in ipos/iquat frame (*, nbody, 3) body_invweight0: mean inv inert in qpos0 (trn, rot) (*, nbody, 2) body_gravcomp: antigravity force, units of body weight (*, nbody) body_contype: OR over all geom contypes (nbody,) body_conaffinity: OR over all geom conaffinities (nbody,) oct_child: octree children (noct, 8) oct_aabb: octree axis-aligned bounding boxes (noct, 2, 3) oct_coeff: octree interpolation coefficients (noct, 8) jnt_type: type of joint (JointType) (njnt,) jnt_qposadr: start addr in 'qpos' for joint's data (njnt,) jnt_dofadr: start addr in 'qvel' for joint's data (njnt,) jnt_bodyid: id of joint's body (njnt,) jnt_limited: does joint have limits (njnt,) jnt_actfrclimited: does joint have actuator force limits (njnt,) jnt_actgravcomp: is gravcomp force applied via actuators (njnt,) jnt_solref: constraint solver reference: limit (*, njnt, mjNREF) jnt_solimp: constraint solver impedance: limit (*, njnt, mjNIMP) jnt_pos: local anchor position (*, njnt, 3) jnt_axis: local joint axis (*, njnt, 3) jnt_stiffness: stiffness coefficient (*, njnt) jnt_stiffnesspoly: high-order stiffness coefficients (*, njnt, 2) jnt_range: joint limits (*, njnt, 2) jnt_actfrcrange: range of total actuator force (*, njnt, 2) jnt_margin: min distance for limit detection (*, njnt) dof_bodyid: id of dof's body (nv,) dof_jntid: id of dof's joint (nv,) dof_parentid: id of dof's parent; -1: none (nv,) dof_treeid: id of dof's tree (nv,) dof_Madr: dof address in M-diagonal (nv,) dof_solref: constraint solver reference: frictionloss (*, nv, NREF) dof_solimp: constraint solver impedance: frictionloss (*, nv, NIMP) dof_frictionloss: dof friction loss (*, nv) dof_armature: dof armature inertia/mass (*, nv) dof_damping: damping coefficient (*, nv) dof_dampingpoly: high-order damping coefficients (*, nv, 2) dof_invweight0: diag. inverse inertia in qpos0 (*, nv) tree_bodynum: number of bodies in tree (incl. root) (ntree,) tree_dofadr: start address of tree's dofs (ntree,) tree_dofnum: number of dofs in tree (ntree,) geom_type: geometric type (GeomType) (ngeom,) geom_contype: geom contact type (ngeom,) geom_conaffinity: geom contact affinity (ngeom,) geom_condim: contact dimensionality (1, 3, 4, 6) (ngeom,) geom_bodyid: id of geom's body (ngeom,) geom_dataid: id of geom's mesh/hfield; -1: none (*, ngeom) geom_matid: material id for rendering (*, ngeom,) geom_group: geom group inclusion/exclusion mask (ngeom,) geom_priority: geom contact priority (ngeom,) geom_solmix: mixing coef for solref/imp in geom pair (*, ngeom,) geom_solref: constraint solver reference: contact (*, ngeom, mjNREF) geom_solimp: constraint solver impedance: contact (*, ngeom, mjNIMP) geom_size: geom-specific size parameters (*, ngeom, 3) geom_aabb: bounding box, (center, size) (*, ngeom, 2, 3) geom_rbound: radius of bounding sphere (*, ngeom,) geom_pos: local position offset rel. to body (*, ngeom, 3) geom_quat: local orientation offset rel. to body (*, ngeom, 4) geom_friction: friction for (slide, spin, roll) (*, ngeom, 3) geom_margin: detect contact if dist<margin (*, ngeom,) geom_gap: additional contact detection buffer (*, ngeom,) geom_fluid: fluid interaction parameters (ngeom, mjNFLUID) geom_rgba: rgba when material is omitted (*, ngeom, 4) site_type: geom type for rendering (GeomType) (nsite,) site_bodyid: id of site's body (nsite,) site_size: geom size for rendering (nsite, 3) site_pos: local position offset rel. to body (*, nsite, 3) site_quat: local orientation offset rel. to body (*, nsite, 4) cam_mode: camera tracking mode (CamLightType) (ncam,) cam_bodyid: id of camera's body (ncam,) cam_targetbodyid: id of targeted body; -1: none (ncam,) cam_pos: position rel. to body frame (*, ncam, 3) cam_quat: orientation rel. to body frame (*, ncam, 4) cam_poscom0: global position rel. to sub-com in qpos0 (*, ncam, 3) cam_pos0: global position rel. to body in qpos0 (*, ncam, 3) cam_mat0: global orientation in qpos0 (*, ncam, 3, 3) cam_projection: projection type (ProjectionType) (ncam,) cam_fovy: y field-of-view (ortho ? len : deg) (*, ncam) cam_resolution: resolution: pixels [width, height] (ncam, 2) cam_sensorsize: sensor size: length [width, height] (ncam, 2) cam_intrinsic: [focal length; principal point] (*, ncam, 4) light_mode: light tracking mode (CamLightType) (nlight,) light_bodyid: id of light's body (nlight,) light_targetbodyid: id of targeted body; -1: none (nlight,) light_type: spot, directional, etc. (mjtLightType) (*, nlight) light_castshadow: does light cast shadows (*, nlight) light_active: is light active (*, nlight) light_pos: position rel. to body frame (*, nlight, 3) light_dir: direction rel. to body frame (*, nlight, 3) light_poscom0: global position rel. to sub-com in qpos0 (*, nlight, 3) light_pos0: global position rel. to body in qpos0 (*, nlight, 3) light_dir0: global direction in qpos0 (*, nlight, 3) flex_contype: flex contact type (nflex,) flex_conaffinity: flex contact affinity (nflex,) flex_condim: contact dimensionality (1, 3, 4, 6) (nflex,) flex_priority: geom contact priority (nflex,) flex_solmix: mixing coef for solref/imp in geom pair (nflex,) flex_solref: constraint solver reference: contact (nflex, mjNREF) flex_solimp: constraint solver impedance: contact (nflex, mjNIMP) flex_friction: friction for (slide, spin, roll) (nflex, 3) flex_margin: detect contact if dist<margin (nflex,) flex_gap: include in solver if dist<margin-gap (nflex,) flex_dim: 1: lines, 2: triangles, 3: tetrahedra (nflex,) flex_vertadr: first vertex address (nflex,) flex_vertnum: number of vertices (nflex,) flex_edgeadr: first edge address (nflex,) flex_edgenum: number of edges (nflex,) flex_elemadr: first element address (nflex,) flex_elemnum: number of elements (nflex,) flex_elemdataadr: first element vertex id address (nflex,) flex_stiffnessadr: stiffness matrix address (nflex,) flex_elemedgeadr: first element edge id address (nflex,) flex_bendingadr: first bending data address (nflex,) flex_shellnum: number of shells (nflex,) flex_shelldataadr: first shell data address (nflex,) flex_vertbodyid: vertex body ids (nflexvert,) flex_edge: edge vertex ids (2 per edge) (nflexedge, 2) flex_edgeflap: adjacent vertex ids (dim=2 only) (nflexedge, 2) flex_elem: element vertex ids (dim+1 per elem) (nflexelemdata,) flex_elemedge: element edge ids (nflexelemedge,) flex_shell: shell fragment vertex ids (dim per frag) (nflexshelldata,) flex_vert: vertex local positions (nflexvert, 3) flexedge_length0: edge lengths in qpos0 (nflexedge,) flexedge_invweight0: inv. inertia for the edge (nflexedge,) flex_radius: radius around primitive element (nflex,) flex_stiffness: finite element stiffness matrix (nflexstiffness,) flex_bending: bending stiffness (nflexbending,) flex_damping: Rayleigh's damping coefficient (nflex,) flex_centered: flex vertices are centered at body origin (nflex,) flexedge_J_rownnz: number of nonzeros in Jacobian row (nflexedge,) flexedge_J_rowadr: row start address in colind array (nflexedge,) flexedge_J_colind: column indices in sparse Jacobian (nJfe,) mesh_vertadr: first vertex address (nmesh,) mesh_vertnum: number of vertices (nmesh,) mesh_faceadr: first face address (nmesh,) mesh_octadr: octree address for each mesh (nmesh,) mesh_normaladr: first normal address (nmesh,) mesh_normalnum: number of normals (nmesh,) mesh_graphadr: graph data address; -1: no graph (nmesh,) mesh_vert: vertex positions for all meshes (nmeshvert, 3) mesh_normal: normals for all meshes (nmeshnormal, 3) mesh_face: face indices for all meshes (nface, 3) mesh_graph: convex graph data (nmeshgraph,) mesh_quat: rotation applied to asset vertices (nmesh, 4) mesh_polynum: number of polygons per mesh (nmesh,) mesh_polyadr: first polygon address per mesh (nmesh,) mesh_polynormal: all polygon normals (nmeshpoly, 3) mesh_polyvertadr: polygon vertex start address (nmeshpoly,) mesh_polyvertnum: number of vertices per polygon (nmeshpoly,) mesh_polyvert: all polygon vertices (nmeshpolyvert,) mesh_polymapadr: first polygon address per vertex (nmeshvert,) mesh_polymapnum: number of polygons per vertex (nmeshvert,) mesh_polymap: vertex to polygon map (nmeshpolymap,) hfield_size: (x, y, z_top, z_bottom) (nhfield, 4) hfield_nrow: number of rows in grid (nhfield,) hfield_ncol: number of columns in grid (nhfield,) hfield_adr: start address in hfield_data (nhfield,) hfield_data: elevation data (nhfielddata,) mat_texid: texture id for rendering (*, nmat, mjNTEXROLE) mat_texrepeat: texture repeat for rendering (*, nmat, 2) mat_rgba: rgba (*, nmat, 4) pair_dim: contact dimensionality (npair,) pair_geom1: id of geom1 (npair,) pair_geom2: id of geom2 (npair,) pair_solref: solver reference: contact normal (*, npair, mjNREF) pair_solreffriction: solver reference: contact friction (*, npair, mjNREF) pair_solimp: solver impedance: contact (*, npair, mjNIMP) pair_margin: detect contact if dist<margin (*, npair,) pair_gap: additional contact detection buffer (*, npair,) pair_friction: tangent1, 2, spin, roll1, 2 (*, npair, 5) exclude_signature: body1 << 16 + body2 (nexclude,) eq_type: constraint type (EqType) (neq,) eq_obj1id: id of object 1 (neq,) eq_obj2id: id of object 2 (neq,) eq_objtype: type of both objects (ObjType) (neq,) eq_active0: initial enable/disable constraint state (neq,) eq_solref: constraint solver reference (*, neq, mjNREF) eq_solimp: constraint solver impedance (*, neq, mjNIMP) eq_data: numeric data for constraint (*, neq, mjNEQDATA) tendon_adr: address of first object in tendon's path (ntendon,) tendon_num: number of objects in tendon's path (ntendon,) ten_J_rownnz: number of non-zeros in each tendon row (ntendon,) ten_J_rowadr: row start address for sparse ten_J (ntendon,) ten_J_colind: column indices in sparse ten_J (nJten,) tendon_limited: does tendon have length limits (ntendon,) tendon_actfrclimited: does ten have actuator force limit (ntendon,) tendon_solref_lim: constraint solver reference: limit (*, ntendon, mjNREF) tendon_solimp_lim: constraint solver impedance: limit (*, ntendon, mjNIMP) tendon_solref_fri: constraint solver reference: friction (*, ntendon, mjNREF) tendon_solimp_fri: constraint solver impedance: friction (*, ntendon, mjNIMP) tendon_range: tendon length limits (*, ntendon, 2) tendon_actfrcrange: range of total actuator force (*, ntendon, 2) tendon_margin: min distance for limit detection (*, ntendon) tendon_stiffness: stiffness coefficient (*, ntendon) tendon_stiffnesspoly: high-order stiffness coefficients (*, ntendon, 2) tendon_damping: damping coefficient (*, ntendon) tendon_dampingpoly: high-order damping coefficients (*, ntendon, 2) tendon_armature: inertia associated with tendon velocity (*, ntendon) tendon_frictionloss: loss due to friction (*, ntendon) tendon_lengthspring: spring resting length range (*, ntendon, 2) tendon_length0: tendon length in qpos0 (*, ntendon) tendon_invweight0: inv. weight in qpos0 (*, ntendon) wrap_type: wrap object type (WrapType) (nwrap,) wrap_objid: object id: geom, site, joint (nwrap,) wrap_prm: divisor, joint coef, or site id (nwrap,) actuator_trntype: transmission type (TrnType) (nu,) actuator_dyntype: dynamics type (DynType) (nu,) actuator_gaintype: gain type (GainType) (nu,) actuator_biastype: bias type (BiasType) (nu,) actuator_trnid: transmission id: joint, tendon, site (nu, 2) actuator_actadr: first activation address; -1: stateless (nu,) actuator_actnum: number of activation variables (nu,) actuator_ctrllimited: is control limited (nu,) actuator_forcelimited: is force limited (nu,) actuator_actlimited: is activation limited (nu,) actuator_dynprm: dynamics parameters (*, nu, mjNDYN) actuator_gainprm: gain parameters (*, nu, mjNGAIN) actuator_biasprm: bias parameters (*, nu, mjNBIAS) actuator_actearly: step activation before force (nu,) actuator_ctrlrange: range of controls (*, nu, 2) actuator_forcerange: range of forces (*, nu, 2) actuator_actrange: range of activations (*, nu, 2) actuator_gear: scale length and transmitted force (*, nu, 6) actuator_cranklength: crank length for slider-crank (*, nu) actuator_acc0: acceleration from unit force in qpos0 (*, nu) actuator_lengthrange: feasible actuator length range (*, nu, 2) sensor_type: sensor type (SensorType) (nsensor,) sensor_datatype: numeric data type (DataType) (nsensor,) sensor_objtype: type of sensorized object (ObjType) (nsensor,) sensor_objid: id of sensorized object (nsensor,) sensor_reftype: type of reference frame (ObjType) (nsensor,) sensor_refid: id of reference frame; -1: global frame (nsensor,) sensor_intprm: sensor parameters (nsensor, mjNSENS) sensor_dim: number of scalar outputs (nsensor,) sensor_adr: address in sensor array (nsensor,) sensor_cutoff: cutoff for real and positive; 0: ignore (nsensor,) plugin: globally registered plugin slot number (nplugin,) plugin_attr: config attributes of geom plugin (nplugin, _NPLUGINATTR) M_rownnz: number of non-zeros in each row of qM (nv,) M_rowadr: index of each row in qM (nv,) M_colind: column indices of non-zeros in qM (nM,) mapM2M: index mapping from M (legacy) to M (CSR) (nC) flex_vertflexid: flex id for each flex vertex (nflexvert,) warp only fields: callback: custom physics callbacks nbranch: number of branches (leaf-to-root paths) nv_pad: number of degrees of freedom + padding nacttrnbody: number of actuators with body transmission nsensorcollision: number of unique collisions for geom distance sensors nsensortaxel: number of taxels in all tactile sensors nsensorcontact: number of contact sensors nrangefinder: number of rangefinder sensors nmaxcondim: maximum condim across geoms, pairs, and flexes nmaxpyramid: maximum number of pyramid directions nmaxpolygon: maximum number of verts per polygon nmaxmeshdeg: maximum number of polygons per vert is_sparse: whether to use sparse representations has_fluid: True if wind, density, or viscosity are non-zero at put_model time has_sdf_geom: whether the model contains SDF geoms block_dim: block dim options body_tree: list of body ids by tree level body_branches: flattened body ids for all branches body_branch_start: start index in body_branches for each branch (nbranch + 1,) mocap_bodyid: id of body for mocap (nmocap,) body_fluid_ellipsoid: does body use ellipsoid fluid (nbody,) jnt_limited_slide_hinge_adr: limited/slide/hinge jntadr jnt_limited_ball_adr: limited/ball jntadr body_isdofancestor: precomputed mask of which DOFs affect each body dof_tri_row: dof lower triangle row (used in solver) dof_tri_col: dof lower triangle col (used in solver) nxn_geom_pair: collision pair geom ids [-2, ngeom-1] nxn_geom_pair_filtered: valid collision pair geom ids [-1, ngeom - 1] nxn_pairid: contact pair id, -1 if not predefined, -2 if skipped collision id, else -1 nxn_pairid_filtered: active subset of nxn_pairid geom_pair_type_count: count of max number of each potential collision geom_plugin_index: geom index in plugin array (ngeom,) eq_connect_adr: eq_* addresses of type `CONNECT` eq_wld_adr: eq_* addresses of type `WELD` eq_jnt_adr: eq_* addresses of type `JOINT` eq_ten_adr: eq_* addresses of type `TENDON` eq_flex_adr: eq * addresses of type `FLEX tendon_jnt_adr: joint tendon address tendon_site_pair_adr: site pair tendon address tendon_geom_adr: geom tendon address tendon_limited_adr: addresses for limited tendons max_ten_J_rownnz: maximum number of non-zeros in a tendon row ten_wrapadr_site: wrap object starting address for sites ten_wrapnum_site: number of site wrap objects per tendon wrap_jnt_adr: addresses for joint tendon wrap object wrap_site_adr: addresses for site tendon wrap object wrap_site_pair_adr: first address for site wrap pair wrap_geom_adr: addresses for geom tendon wrap object wrap_pulley_scale: pulley scaling (nwrap,) actuator_trntype_body_adr: addresses for actuators with body transmission sensor_pos_adr: addresses for position sensors sensor_limitpos_adr: address for limit position sensors sensor_vel_adr: addresses for velocity sensors (excluding limit velocity sensors) sensor_limitvel_adr: address for limit velocity sensors sensor_acc_adr: addresses for acceleration sensors sensor_rangefinder_adr: addresses for rangefinder sensors rangefinder_sensor_adr: map sensor id to rangefinder id (excluding touch sensors) (excluding limit force sensors) sensor_collision_start_adr: address for sensor's first item in collision collision_sensor_adr: map sensor id to collision id (nsensor,) sensor_touch_adr: addresses for touch sensors sensor_limitfrc_adr: address for limit force sensors sensor_e_potential: evaluate energy_pos sensor_e_kinetic: evaluate energy_vel sensor_tendonactfrc_adr: address for tendonactfrc sensor sensor_subtree_vel: evaluate subtree_vel sensor_contact_adr: addresses for contact sensors (nsensorcontact,) sensor_adr_to_contact_adr: map sensor adr to contact adr (nsensor,) sensor_rne_postconstraint: evaluate rne_postconstraint sensor_rangefinder_bodyid: bodyid for rangefinder (nrangefinder,) taxel_vertadr: tactile sensor vertex address (nsensortaxel,) taxel_sensorid: address for tactile sensors qM_tiles: tiling configuration qLD_updates: tuple of index triples for sparse factorization qLD_all_updates: tuple of all levels concatenated qLD_level_offsets: tuple of start offsets for each level qM_fullm_i: sparse mass matrix addressing qM_fullm_j: sparse mass matrix addressing qM_mulm_rowadr: sparse matmul row pointers qM_mulm_col: sparse matmul column indices qM_mulm_madr: sparse matmul matrix addresses """ nq: int nv: int nu: int na: int nbody: int noct: int njnt: int ntree: int nM: int nC: int ngeom: int nsite: int ncam: int nlight: int nflex: int nflexvert: int nflexedge: int nflexelem: int nflexelemdata: int nflexstiffness: int nflexbending: int nflexelemedge: int nflexshelldata: int nJfe: int nmesh: int nmeshvert: int nmeshnormal: int nmeshface: int nmeshgraph: int nmeshpoly: int nmeshpolyvert: int nmeshpolymap: int nhfield: int nhfielddata: int nmat: int npair: int nexclude: int neq: int ntendon: int nJten: int nwrap: int nsensor: int nmocap: int nplugin: int nJmom: int ngravcomp: int nsensordata: int opt: Option stat: Statistic qpos0: wp.array2d[float] qpos_spring: wp.array2d[float] body_parentid: wp.array[int] body_rootid: wp.array[int] body_weldid: wp.array[int] body_mocapid: wp.array[int] body_jntnum: wp.array[int] body_jntadr: wp.array[int] body_dofnum: wp.array[int] body_dofadr: wp.array[int] body_treeid: wp.array[int] body_geomnum: wp.array[int] body_geomadr: wp.array[int] body_pos: wp.array2d[wp.vec3] body_quat: wp.array2d[wp.quat] body_ipos: wp.array2d[wp.vec3] body_iquat: wp.array2d[wp.quat] body_mass: wp.array2d[float] body_subtreemass: wp.array2d[float] body_inertia: wp.array2d[wp.vec3] body_invweight0: wp.array2d[wp.vec2] body_gravcomp: wp.array2d[float] body_contype: wp.array[int] body_conaffinity: wp.array[int] oct_child: wp.array[vec8i] oct_aabb: wp.array2d[wp.vec3] oct_coeff: wp.array[vec8] jnt_type: wp.array[int] jnt_qposadr: wp.array[int] jnt_dofadr: wp.array[int] jnt_bodyid: wp.array[int] jnt_limited: wp.array[int] jnt_actfrclimited: wp.array[bool] jnt_actgravcomp: wp.array[int] jnt_solref: wp.array2d[wp.vec2] jnt_solimp: wp.array2d[vec5] jnt_pos: wp.array2d[wp.vec3] jnt_axis: wp.array2d[wp.vec3] jnt_stiffness: wp.array2d[float] jnt_stiffnesspoly: wp.array2d[wp.vec2] jnt_range: wp.array2d[wp.vec2] jnt_actfrcrange: wp.array2d[wp.vec2] jnt_margin: wp.array2d[float] dof_bodyid: wp.array[int] dof_jntid: wp.array[int] dof_parentid: wp.array[int] dof_treeid: wp.array[int] dof_Madr: wp.array[int] dof_solref: wp.array2d[wp.vec2] dof_solimp: wp.array2d[vec5] dof_frictionloss: wp.array2d[float] dof_armature: wp.array2d[float] dof_damping: wp.array2d[float] dof_dampingpoly: wp.array2d[wp.vec2] dof_invweight0: wp.array2d[float] tree_bodynum: wp.array[int] tree_dofadr: wp.array[int] tree_dofnum: wp.array[int] geom_type: wp.array[int] geom_contype: wp.array[int] geom_conaffinity: wp.array[int] geom_condim: wp.array[int] geom_bodyid: wp.array[int] geom_dataid: wp.array2d[int] geom_matid: wp.array2d[int] geom_group: wp.array[int] geom_priority: wp.array[int] geom_solmix: wp.array2d[float] geom_solref: wp.array2d[wp.vec2] geom_solimp: wp.array2d[vec5] geom_size: wp.array2d[wp.vec3] geom_aabb: wp.array3d[wp.vec3] geom_rbound: wp.array2d[float] geom_pos: wp.array2d[wp.vec3] geom_quat: wp.array2d[wp.quat] geom_friction: wp.array2d[wp.vec3] geom_margin: wp.array2d[float] geom_gap: wp.array2d[float] geom_fluid: wp.array2d[float] geom_rgba: wp.array2d[wp.vec4] site_type: wp.array[int] site_bodyid: wp.array[int] site_size: wp.array[wp.vec3] site_pos: wp.array2d[wp.vec3] site_quat: wp.array2d[wp.quat] cam_mode: wp.array[int] cam_bodyid: wp.array[int] cam_targetbodyid: wp.array[int] cam_pos: wp.array2d[wp.vec3] cam_quat: wp.array2d[wp.quat] cam_poscom0: wp.array2d[wp.vec3] cam_pos0: wp.array2d[wp.vec3] cam_mat0: wp.array2d[wp.mat33] cam_projection: wp.array[int] cam_fovy: wp.array2d[float] cam_resolution: wp.array[wp.vec2i] cam_sensorsize: wp.array[wp.vec2] cam_intrinsic: wp.array2d[wp.vec4] light_mode: wp.array[int] light_bodyid: wp.array[int] light_targetbodyid: wp.array[int] light_type: wp.array2d[int] light_castshadow: wp.array2d[bool] light_active: wp.array2d[bool] light_pos: wp.array2d[wp.vec3] light_dir: wp.array2d[wp.vec3] light_poscom0: wp.array2d[wp.vec3] light_pos0: wp.array2d[wp.vec3] light_dir0: wp.array2d[wp.vec3] flex_contype: wp.array[int] flex_conaffinity: wp.array[int] flex_condim: wp.array[int] flex_priority: wp.array[int] flex_solmix: wp.array[float] flex_solref: wp.array[wp.vec2] flex_solimp: wp.array[vec5] flex_friction: wp.array[wp.vec3] flex_margin: wp.array[float] flex_gap: wp.array[float] flex_dim: wp.array[int] flex_vertadr: wp.array[int] flex_vertnum: wp.array[int] flex_edgeadr: wp.array[int] flex_edgenum: wp.array[int] flex_elemadr: wp.array[int] flex_elemnum: wp.array[int] flex_elemdataadr: wp.array[int] flex_stiffnessadr: wp.array[int] flex_elemedgeadr: wp.array[int] flex_bendingadr: wp.array[int] flex_shellnum: wp.array[int] flex_shelldataadr: wp.array[int] flex_vertbodyid: wp.array[int] flex_edge: wp.array[wp.vec2i] flex_edgeflap: wp.array[wp.vec2i] flex_elem: wp.array[int] flex_elemedge: wp.array[int] flex_shell: wp.array[int] flex_vert: wp.array[wp.vec3] flexedge_length0: wp.array[float] flexedge_invweight0: wp.array[float] flex_radius: wp.array[float] flex_stiffness: wp.array[float] flex_bending: wp.array[float] flex_damping: wp.array[float] flex_centered: wp.array[bool] flexedge_J_rownnz: wp.array[int] flexedge_J_rowadr: wp.array[int] flexedge_J_colind: wp.array[int] mesh_vertadr: wp.array[int] mesh_vertnum: wp.array[int] mesh_faceadr: wp.array[int] mesh_octadr: wp.array[int] mesh_normaladr: wp.array[int] mesh_normalnum: wp.array[int] mesh_graphadr: wp.array[int] mesh_vert: wp.array[wp.vec3] mesh_normal: wp.array[wp.vec3] mesh_face: wp.array[wp.vec3i] mesh_graph: wp.array[int] mesh_quat: wp.array[wp.quat] mesh_polynum: wp.array[int] mesh_polyadr: wp.array[int] mesh_polynormal: wp.array[wp.vec3] mesh_polyvertadr: wp.array[int] mesh_polyvertnum: wp.array[int] mesh_polyvert: wp.array[int] mesh_polymapadr: wp.array[int] mesh_polymapnum: wp.array[int] mesh_polymap: wp.array[int] hfield_size: wp.array[wp.vec4] hfield_nrow: wp.array[int] hfield_ncol: wp.array[int] hfield_adr: wp.array[int] hfield_data: wp.array[float] mat_texid: wp.array3d[int] mat_texrepeat: wp.array2d[wp.vec2] mat_rgba: wp.array2d[wp.vec4] pair_dim: wp.array[int] pair_geom1: wp.array[int] pair_geom2: wp.array[int] pair_solref: wp.array2d[wp.vec2] pair_solreffriction: wp.array2d[wp.vec2] pair_solimp: wp.array2d[vec5] pair_margin: wp.array2d[float] pair_gap: wp.array2d[float] pair_friction: wp.array2d[vec5] exclude_signature: wp.array[int] eq_type: wp.array[int] eq_obj1id: wp.array[int] eq_obj2id: wp.array[int] eq_objtype: wp.array[int] eq_active0: wp.array[bool] eq_solref: wp.array2d[wp.vec2] eq_solimp: wp.array2d[vec5] eq_data: wp.array2d[vec11] tendon_adr: wp.array[int] tendon_num: wp.array[int] ten_J_rownnz: wp.array[int] ten_J_rowadr: wp.array[int] ten_J_colind: wp.array[int] tendon_limited: wp.array[int] tendon_actfrclimited: wp.array[bool] tendon_solref_lim: wp.array2d[wp.vec2] tendon_solimp_lim: wp.array2d[vec5] tendon_solref_fri: wp.array2d[wp.vec2] tendon_solimp_fri: wp.array2d[vec5] tendon_range: wp.array2d[wp.vec2] tendon_actfrcrange: wp.array2d[wp.vec2] tendon_margin: wp.array2d[float] tendon_stiffness: wp.array2d[float] tendon_stiffnesspoly: wp.array2d[wp.vec2] tendon_damping: wp.array2d[float] tendon_dampingpoly: wp.array2d[wp.vec2] tendon_armature: wp.array2d[float] tendon_frictionloss: wp.array2d[float] tendon_lengthspring: wp.array2d[wp.vec2] tendon_length0: wp.array2d[float] tendon_invweight0: wp.array2d[float] wrap_type: wp.array[int] wrap_objid: wp.array[int] wrap_prm: wp.array[float] actuator_trntype: wp.array[int] actuator_dyntype: wp.array[int] actuator_gaintype: wp.array[int] actuator_biastype: wp.array[int] actuator_trnid: wp.array[wp.vec2i] actuator_actadr: wp.array[int] actuator_actnum: wp.array[int] actuator_ctrllimited: wp.array[bool] actuator_forcelimited: wp.array[bool] actuator_actlimited: wp.array[bool] actuator_dynprm: wp.array2d[vec10f] actuator_gainprm: wp.array2d[vec10f] actuator_biasprm: wp.array2d[vec10f] actuator_actearly: wp.array[bool] actuator_ctrlrange: wp.array2d[wp.vec2] actuator_forcerange: wp.array2d[wp.vec2] actuator_actrange: wp.array2d[wp.vec2] actuator_gear: wp.array2d[wp.spatial_vector] actuator_cranklength: wp.array2d[float] actuator_acc0: wp.array2d[float] actuator_lengthrange: wp.array2d[wp.vec2] sensor_type: wp.array[int] sensor_datatype: wp.array[int] sensor_objtype: wp.array[int] sensor_objid: wp.array[int] sensor_reftype: wp.array[int] sensor_refid: wp.array[int] sensor_intprm: wp.array2d[int] sensor_dim: wp.array[int] sensor_adr: wp.array[int] sensor_cutoff: wp.array[float] plugin: wp.array[int] plugin_attr: wp.array[vec_pluginattr] M_rownnz: wp.array[int] M_rowadr: wp.array[int] M_colind: wp.array[int] mapM2M: wp.array[int] flex_vertflexid: wp.array[int] # warp only fields: callback: Callback nbranch: int nv_pad: int nacttrnbody: int nsensorcollision: int nsensortaxel: int nsensorcontact: int nrangefinder: int nmaxcondim: int nmaxpyramid: int nmaxpolygon: int nmaxmeshdeg: int is_sparse: bool has_fluid: bool has_sdf_geom: bool block_dim: BlockDim body_tree: tuple[wp.array[int], ...] body_branches: wp.array[int] body_branch_start: wp.array[int] mocap_bodyid: wp.array[int] body_fluid_ellipsoid: wp.array[bool] jnt_limited_slide_hinge_adr: wp.array[int] jnt_limited_ball_adr: wp.array[int] body_isdofancestor: wp.array2d[int] dof_tri_row: wp.array[int] dof_tri_col: wp.array[int] nxn_geom_pair: wp.array[wp.vec2i] nxn_geom_pair_filtered: wp.array[wp.vec2i] nxn_pairid: wp.array[wp.vec2i] nxn_pairid_filtered: wp.array[wp.vec2i] geom_pair_type_count: tuple[int, ...] geom_plugin_index: wp.array[int] eq_connect_adr: wp.array[int] eq_wld_adr: wp.array[int] eq_jnt_adr: wp.array[int] eq_ten_adr: wp.array[int] eq_flex_adr: wp.array[int] tendon_jnt_adr: wp.array[int] tendon_site_pair_adr: wp.array[int] tendon_geom_adr: wp.array[int] tendon_limited_adr: wp.array[int] max_ten_J_rownnz: int ten_wrapadr_site: wp.array[int] ten_wrapnum_site: wp.array[int] wrap_jnt_adr: wp.array[int] wrap_site_adr: wp.array[int] wrap_site_pair_adr: wp.array[int] wrap_geom_adr: wp.array[int] wrap_pulley_scale: wp.array[float] actuator_trntype_body_adr: wp.array[int] sensor_pos_adr: wp.array[int] sensor_limitpos_adr: wp.array[int] sensor_vel_adr: wp.array[int] sensor_limitvel_adr: wp.array[int] sensor_acc_adr: wp.array[int] sensor_rangefinder_adr: wp.array[int] rangefinder_sensor_adr: wp.array[int] sensor_collision_start_adr: wp.array[int] collision_sensor_adr: wp.array[int] sensor_touch_adr: wp.array[int] sensor_limitfrc_adr: wp.array[int] sensor_e_potential: bool sensor_e_kinetic: bool sensor_tendonactfrc_adr: wp.array[int] sensor_subtree_vel: bool sensor_contact_adr: wp.array[int] sensor_adr_to_contact_adr: wp.array[int] sensor_rne_postconstraint: bool sensor_rangefinder_bodyid: wp.array[int] taxel_vertadr: wp.array[int] taxel_sensorid: wp.array[int] qM_tiles: tuple[TileSet, ...] qLD_updates: tuple[wp.array[wp.vec3i], ...] qLD_all_updates: wp.array[wp.vec3i] qLD_level_offsets: wp.array[int] qM_fullm_i: wp.array[int] qM_fullm_j: wp.array[int] # Gather-based sparse mul_m indices (thread per DOF, no atomics) qM_mulm_rowadr: wp.array[int] # start address for each row [nv+1] qM_mulm_col: wp.array[int] # column index to gather from qM_mulm_madr: wp.array[int] # matrix address to read
class ContactType(enum.IntFlag): """Type of contact. CONSTRAINT: contact for constraint solver. SENSOR: contact for collision sensor (GEOMDIST, GEOMNORMAL, GEOMFROMTO). """ CONSTRAINT = 1 SENSOR = 2
[docs] @dataclasses.dataclass class Contact: """Contact data. Attributes: dist: distance between nearest points; neg: penetration (naconmax,) pos: position of contact point: midpoint between geoms (naconmax, 3) frame: normal is in [0-2], points from geom[0] to geom[1] (naconmax, 3, 3) includemargin: include if dist<includemargin=margin (naconmax,) friction: tangent1, 2, spin, roll1, 2 (naconmax, 5) solref: constraint solver reference, normal direction (naconmax, 2) solreffriction: constraint solver reference, friction directions (naconmax, 2) solimp: constraint solver impedance (naconmax, 5) dim: contact space dimensionality: 1, 3, 4 or 6 (naconmax,) geom: geom ids; -1 for flex (naconmax, 2) efc_address: address in efc; -1: not included (naconmax, nmaxpyramid) worldid: world id (naconmax,) type: ContactType (naconmax,) geomcollisionid: i-th contact generated for geom (naconmax,) helps uniquely identity contact when multiple contacts are generated for geom pair """ dist: wp.array[float] pos: wp.array[wp.vec3] frame: wp.array[wp.mat33] includemargin: wp.array[float] friction: wp.array[vec5] solref: wp.array[wp.vec2] solreffriction: wp.array[wp.vec2] solimp: wp.array[vec5] dim: wp.array[int] geom: wp.array[wp.vec2i] flex: wp.array[wp.vec2i] vert: wp.array[wp.vec2i] efc_address: wp.array2d[int] worldid: wp.array[int] type: wp.array[int] geomcollisionid: wp.array[int]
[docs] @dataclasses.dataclass class Constraint: """Constraint data. Attributes: type: constraint type (ConstraintType) (nworld, njmax) id: id of object of specific type (nworld, njmax) J_rownnz: number of non-zeros in J row (nworld, 0) dense (nworld, njmax) sparse J_rowadr: row start address in colind array (nworld, 0) dense (nworld, njmax) sparse J_colind: column indices in J (nworld, 0, 0) dense (nworld, 1, njmax * nv) sparse J: constraint Jacobian (nworld, njmax_pad, nv_pad) dense (nworld, 1, njmax * nv) sparse pos: constraint position (equality, contact) (nworld, njmax) margin: inclusion margin (contact) (nworld, njmax) D: constraint mass (nworld, njmax_pad) vel: velocity in constraint space: J*qvel (nworld, njmax) aref: reference pseudo-acceleration (nworld, njmax) frictionloss: frictionloss (friction) (nworld, njmax) force: constraint force in constraint space (nworld, njmax) state: constraint state (nworld, njmax_pad) warp only fields: Ma: M*qacc (nworld, nv) Jqvel: J*qvel (nworld, njmax) """ type: wp.array2d[int] id: wp.array2d[int] J_rownnz: wp.array2d[int] J_rowadr: wp.array2d[int] J_colind: wp.array3d[int] J: wp.array3d[float] pos: wp.array2d[float] margin: wp.array2d[float] D: wp.array2d[float] vel: wp.array2d[float] aref: wp.array2d[float] frictionloss: wp.array2d[float] force: wp.array2d[float] state: wp.array2d[int] Ma: wp.array2d[float] Jqvel: wp.array2d[float]
[docs] @dataclasses.dataclass class Data: """Dynamic state that updates each step. Attributes: solver_niter: number of solver iterations (nworld,) ne: number of equality constraints (nworld,) nf: number of friction constraints (nworld,) nl: number of limit constraints (nworld,) nefc: number of constraints (nworld,) nisland: number of constraint islands (nworld,) time: simulation time (nworld,) energy: potential, kinetic energy (nworld, 2) qpos: position (nworld, nq) qvel: velocity (nworld, nv) act: actuator activation (nworld, na) qacc_warmstart: acceleration used for warmstart (nworld, nv) ctrl: control (nworld, nu) qfrc_applied: applied generalized force (nworld, nv) xfrc_applied: applied Cartesian force/torque (nworld, nbody, 6) eq_active: enable/disable constraints (nworld, neq) mocap_pos: position of mocap bodies (nworld, nmocap, 3) mocap_quat: orientation of mocap bodies (nworld, nmocap, 4) qacc: acceleration (nworld, nv) act_dot: time-derivative of actuator activation (nworld, na) sensordata: sensor data array (nworld, nsensordata,) xpos: Cartesian position of body frame (nworld, nbody, 3) xquat: Cartesian orientation of body frame (nworld, nbody, 4) xmat: Cartesian orientation of body frame (nworld, nbody, 3, 3) xipos: Cartesian position of body com (nworld, nbody, 3) ximat: Cartesian orientation of body inertia (nworld, nbody, 3, 3) xanchor: Cartesian position of joint anchor (nworld, njnt, 3) xaxis: Cartesian joint axis (nworld, njnt, 3) geom_xpos: Cartesian geom position (nworld, ngeom, 3) geom_xmat: Cartesian geom orientation (nworld, ngeom, 3, 3) site_xpos: Cartesian site position (nworld, nsite, 3) site_xmat: Cartesian site orientation (nworld, nsite, 3, 3) cam_xpos: Cartesian camera position (nworld, ncam, 3) cam_xmat: Cartesian camera orientation (nworld, ncam, 3, 3) light_xpos: Cartesian light position (nworld, nlight, 3) light_xdir: Cartesian light direction (nworld, nlight, 3) subtree_com: center of mass of each subtree (nworld, nbody, 3) cdof: com-based motion axis of each dof (rot:lin) (nworld, nv, 6) cinert: com-based body inertia and mass (nworld, nbody, 10) flexvert_xpos: cartesian flex vertex positions (nworld, nflexvert, 3) flexedge_J: edge length Jacobian (nworld, nJfe) flexedge_length: flex edge lengths (nworld, nflexedge, 1) ten_wrapadr: start address of tendon's path (nworld, ntendon) ten_wrapnum: number of wrap points in path (nworld, ntendon) ten_J: tendon Jacobian (nworld, nJten) ten_length: tendon lengths (nworld, ntendon) wrap_obj: geomid; -1: site; -2: pulley (nworld, nwrap, 2) wrap_xpos: Cartesian 3D points in all paths (nworld, nwrap, 6) actuator_length: actuator lengths (nworld, nu) moment_rownnz: number of non-zeros in actuator_moment row (nworld, nu) moment_rowadr: row start address in actuator_moment (nworld, nu) moment_colind: column indices in sparse actuator_moment (nworld, nJmom) actuator_moment: actuator moments (nworld, nJmom) crb: com-based composite inertia and mass (nworld, nbody, 10) qM: total inertia (nworld, nv, nv) if dense (nworld, 1, nM) if sparse qLD: L'*D*L factorization of M (nworld, nv, nv) if dense (nworld, 1, nC) if sparse qLDiagInv: 1/diag(D) (nworld, nv) flexedge_velocity: flex edge velocities (nworld, nflexedge) ten_velocity: tendon velocities (nworld, ntendon) actuator_velocity: actuator velocities (nworld, nu) cvel: com-based velocity (rot:lin) (nworld, nbody, 6) cdof_dot: time-derivative of cdof (rot:lin) (nworld, nv, 6) qfrc_bias: C(qpos,qvel) (nworld, nv) qfrc_spring: passive spring force (nworld, nv) qfrc_damper: passive damper force (nworld, nv) qfrc_gravcomp: passive gravity compensation force (nworld, nv) qfrc_fluid: passive fluid force (nworld, nv) qfrc_passive: total passive force (nworld, nv) subtree_linvel: linear velocity of subtree com (nworld, nbody, 3) subtree_angmom: angular momentum about subtree com (nworld, nbody, 3) actuator_force: actuator force in actuation space (nworld, nu) qfrc_actuator: actuator force (nworld, nv) qfrc_smooth: net unconstrained force (nworld, nv) qacc_smooth: unconstrained acceleration (nworld, nv) qfrc_constraint: constraint force (nworld, nv) qfrc_inverse: net external force; should equal: (nworld, nv) qfrc_applied + J.T @ xfrc_applied + qfrc_actuator cacc: com-based acceleration (nworld, nbody, 6) cfrc_int: com-based interaction force with parent (nworld, nbody, 6) cfrc_ext: com-based external force on body (nworld, nbody, 6) contact: contact data efc: constraint data tree_island: island ID per tree (-1 if unconstrained) (nworld, ntree) warp only fields: nworld: number of worlds naconmax: maximum number of contacts (shared across all worlds) naccdmax: maximum number of contacts for CCD (all worlds) njmax: maximum number of constraints per world njmax_pad: njmax rounded up to the nearest multiple of TILE_SIZE_JTDAJ njmax_nnz: number of non-zeros in constraint Jacobian nacon: number of detected contacts (across all worlds) (1,) ncollision: collision count from broadphase (1,) """ solver_niter: wp.array[int] ne: wp.array[int] nf: wp.array[int] nl: wp.array[int] nefc: wp.array[int] nisland: wp.array[int] time: wp.array[float] energy: wp.array[wp.vec2] qpos: wp.array2d[float] qvel: wp.array2d[float] act: wp.array2d[float] qacc_warmstart: wp.array2d[float] ctrl: wp.array2d[float] qfrc_applied: wp.array2d[float] xfrc_applied: wp.array2d[wp.spatial_vector] eq_active: wp.array2d[bool] mocap_pos: wp.array2d[wp.vec3] mocap_quat: wp.array2d[wp.quat] qacc: wp.array2d[float] act_dot: wp.array2d[float] sensordata: wp.array2d[float] xpos: wp.array2d[wp.vec3] xquat: wp.array2d[wp.quat] xmat: wp.array2d[wp.mat33] xipos: wp.array2d[wp.vec3] ximat: wp.array2d[wp.mat33] xanchor: wp.array2d[wp.vec3] xaxis: wp.array2d[wp.vec3] geom_xpos: wp.array2d[wp.vec3] geom_xmat: wp.array2d[wp.mat33] site_xpos: wp.array2d[wp.vec3] site_xmat: wp.array2d[wp.mat33] cam_xpos: wp.array2d[wp.vec3] cam_xmat: wp.array2d[wp.mat33] light_xpos: wp.array2d[wp.vec3] light_xdir: wp.array2d[wp.vec3] subtree_com: wp.array2d[wp.vec3] cdof: wp.array2d[wp.spatial_vector] cinert: wp.array2d[vec10] flexvert_xpos: wp.array2d[wp.vec3] flexedge_J: wp.array2d[float] flexedge_length: wp.array2d[float] ten_wrapadr: wp.array2d[int] ten_wrapnum: wp.array2d[int] ten_J: wp.array2d[float] ten_length: wp.array2d[float] wrap_obj: wp.array2d[wp.vec2i] wrap_xpos: wp.array2d[wp.spatial_vector] actuator_length: wp.array2d[float] moment_rownnz: wp.array2d[int] moment_rowadr: wp.array2d[int] moment_colind: wp.array2d[int] actuator_moment: wp.array2d[float] crb: wp.array2d[vec10] qM: wp.array3d[float] qLD: wp.array3d[float] qLDiagInv: wp.array2d[float] flexedge_velocity: wp.array2d[float] ten_velocity: wp.array2d[float] actuator_velocity: wp.array2d[float] cvel: wp.array2d[wp.spatial_vector] cdof_dot: wp.array2d[wp.spatial_vector] qfrc_bias: wp.array2d[float] qfrc_spring: wp.array2d[float] qfrc_damper: wp.array2d[float] qfrc_gravcomp: wp.array2d[float] qfrc_fluid: wp.array2d[float] qfrc_passive: wp.array2d[float] subtree_linvel: wp.array2d[wp.vec3] subtree_angmom: wp.array2d[wp.vec3] actuator_force: wp.array2d[float] qfrc_actuator: wp.array2d[float] qfrc_smooth: wp.array2d[float] qacc_smooth: wp.array2d[float] qfrc_constraint: wp.array2d[float] qfrc_inverse: wp.array2d[float] cacc: wp.array2d[wp.spatial_vector] cfrc_int: wp.array2d[wp.spatial_vector] cfrc_ext: wp.array2d[wp.spatial_vector] contact: Contact efc: Constraint tree_island: wp.array2d[int] # warp only fields: nworld: int naconmax: int naccdmax: int njmax: int njmax_pad: int njmax_nnz: int nacon: wp.array[int] ncollision: wp.array[int]
[docs] @dataclasses.dataclass class RenderContext: """Context for rendering. Attributes: nrender: number of actively rendering cameras cam_res: camera resolution for actively rendering cameras cam_id_map: camera id map use_textures: whether to use textures use_shadows: whether to use shadows use_precomputed_rays: whether to use precomputed rays bvh_ngeom: number of geometries in the BVH enabled_geom_ids: enabled geometry ids mesh_registry: mesh BVH id to warp mesh mapping mesh_bvh_id: mesh BVH ids mesh_bounds_size: mesh bounds size mesh_texcoord: mesh texture coordinates mesh_texcoord_offsets: mesh texture coordinate offsets mesh_facetexcoord: mesh face texture coordinates textures: textures textures_registry: texture registry hfield_registry: hfield BVH id to warp mesh mapping hfield_bvh_id: hfield BVH ids hfield_bounds_size: hfield bounds half-extents flex_mesh_registry: per-flex mesh BVH registry (prevents garbage collection) flex_rgba: flex rgba flex_bvh_id: per-flex BVH ids flex_group_root: per-flex group roots (nworld x n_flex_bvh) flex_render_smooth: whether to render flex meshes smoothly flex_dim: flex dimension per flex (1D/2D/3D) bvh: scene BVH bvh_id: scene BVH id lower: lower bounds upper: upper bounds group: groups group_root: group roots ray: rays rgb_data: RGB data rgb_adr: RGB addresses depth_data: depth data depth_adr: depth addresses render_rgb: per-camera RGB render flags render_depth: per-camera depth render flags seg_data: segmentation data (per-pixel object ID/type pairs) seg_adr: segmentation addresses render_seg: per-camera segmentation render flags znear: near plane distance total_rays: total number of rays render_skybox: whether to shade missed rays with the MuJoCo skybox texture skybox_tex_id: index into textures of the skybox (MuJoCo tex_type == SKYBOX), -1 if none skybox_face_width: pixel width of one skybox cube face (0 if no skybox) """ nrender: int cam_res: wp.array[wp.vec2i] cam_id_map: wp.array[int] use_textures: bool use_shadows: bool background_color: wp.uint32 use_precomputed_rays: bool render_skybox: bool skybox_tex_id: int skybox_face_width: int bvh_ngeom: int enabled_geom_ids: wp.array[int] mesh_registry: dict mesh_bvh_id: wp.array[wp.uint64] mesh_bounds_size: wp.array[wp.vec3] mesh_texcoord: wp.array[wp.vec2] mesh_texcoord_offsets: wp.array[int] mesh_facetexcoord: wp.array[wp.vec3i] textures: wp.array[wp.Texture2D] textures_registry: list[wp.Texture2D] hfield_registry: dict hfield_bvh_id: wp.array[wp.uint64] hfield_bounds_size: wp.array[wp.vec3] flex_mesh_registry: dict flex_rgba: wp.array[wp.vec4] flex_bvh_id: wp.array[wp.uint64] flex_group_root: wp.array2d[int] flex_render_smooth: bool bvh_nflexgeom: int flex_dim_np: wp.array[int] flex_geom_flexid: wp.array[int] flex_geom_edgeid: wp.array[int] bvh: wp.Bvh bvh_id: wp.uint64 lower: wp.array[wp.vec3] upper: wp.array[wp.vec3] group: wp.array[int] group_root: wp.array[int] ray: wp.array[wp.vec3] rgb_data: wp.array[wp.uint32] rgb_adr: wp.array[int] depth_data: wp.array[wp.float32] depth_adr: wp.array[int] render_rgb: wp.array[bool] render_depth: wp.array[bool] seg_data: wp.array[wp.vec2i] seg_adr: wp.array[int] render_seg: wp.array[bool] znear: float total_rays: int