MJX API#
Public API for MJX.
- class Model[source]#
Static model of the scene that remains unchanged with each physics step.
- 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
- njnt#
number of joints
- 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
- nmesh#
number of meshes
- Type:
int
- nmeshvert#
number of vertices for all meshes
- Type:
int
- nmeshnormal#
number of normals in all meshes
- Type:
int
- nmeshtexcoord#
number of texcoords 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
- ntex#
number of textures
- Type:
int
- ntexdata#
size of texture 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
- nnumeric#
number of numeric custom fields
- Type:
int
- ntuple#
number of tuple custom fields
- Type:
int
- nkey#
number of keyframes
- Type:
int
- nmocap#
number of mocap bodies
- Type:
int
- nM#
number of non-zeros in sparse inertia matrix
- Type:
int
- nB#
number of non-zeros in B matrix
- Type:
int
- nC#
number of non-zeros in C matrix
- Type:
int
- nD#
number of non-zeros in D matrix
- Type:
int
- nJmom#
number of non-zeros in Jacobian momentum matrix
- Type:
int
- nJten#
number of non-zeros in sparse tendon Jacobian
- Type:
int
- ngravcomp#
number of bodies with nonzero gravcomp
- Type:
int
- nuserdata#
number of elements in userdata
- Type:
int
- nsensordata#
number of elements in sensor data vector
- Type:
int
- npluginstate#
number of plugin state values
- Type:
int
- nhistory#
number of history buffer elements
- Type:
int
- opt#
physics options
- stat#
model statistics
- qpos0#
qpos values at default pose
- Type:
jax.Array
- qpos_spring#
reference pose for springs
- Type:
jax.Array
- bind(obj: MjsBody | MjsFrame | MjsGeom | MjsJoint | MjsLight | MjsMaterial | MjsSite | MjsMesh | MjsSkin | MjsTexture | MjsText | MjsTuple | MjsCamera | MjsFlex | MjsHField | MjsKey | MjsNumeric | MjsPair | MjsExclude | MjsEquality | MjsTendon | MjsSensor | MjsActuator | MjsPlugin | Iterable[MjsBody | MjsFrame | MjsGeom | MjsJoint | MjsLight | MjsMaterial | MjsSite | MjsMesh | MjsSkin | MjsTexture | MjsText | MjsTuple | MjsCamera | MjsFlex | MjsHField | MjsKey | MjsNumeric | MjsPair | MjsExclude | MjsEquality | MjsTendon | MjsSensor | MjsActuator | MjsPlugin]) BindModel#
Bind a Mujoco spec to an MJX Model.
- class Data[source]#
Dynamic state that updates each step.
- time#
simulation time
- Type:
jax.Array
- qpos#
position
- Type:
jax.Array
- qvel#
velocity
- Type:
jax.Array
- act#
actuator activation
- Type:
jax.Array
- history#
actuator history buffer
- Type:
jax.Array
- qacc_warmstart#
warm start for solver
- Type:
jax.Array
- plugin_state#
plugin state values
- Type:
jax.Array
- ctrl#
control input
- Type:
jax.Array
- qfrc_applied#
applied generalized force
- Type:
jax.Array
- xfrc_applied#
applied Cartesian force/torque
- Type:
jax.Array
- eq_active#
enable/disable equality constraints
- Type:
jax.Array
- mocap_pos#
positions of mocap bodies
- Type:
jax.Array
- mocap_quat#
orientations of mocap bodies
- Type:
jax.Array
- qacc#
acceleration
- Type:
jax.Array
- act_dot#
time-derivative of actuator activation
- Type:
jax.Array
- userdata#
user data
- Type:
jax.Array
- sensordata#
sensor data output
- Type:
jax.Array
- xpos#
Cartesian position of body frame
- Type:
jax.Array
- xquat#
Cartesian orientation of body frame
- Type:
jax.Array
- xmat#
rotation matrix of body frame
- Type:
jax.Array
- xipos#
Cartesian position of body com
- Type:
jax.Array
- ximat#
rotation matrix of body inertia
- Type:
jax.Array
- xanchor#
Cartesian position of joint anchor
- Type:
jax.Array
- xaxis#
Cartesian joint axis
- Type:
jax.Array
- ten_length#
tendon lengths
- Type:
jax.Array
- geom_xpos#
Cartesian position of geoms
- Type:
jax.Array
- geom_xmat#
rotation matrix of geoms
- Type:
jax.Array
- site_xpos#
Cartesian position of sites
- Type:
jax.Array
- site_xmat#
rotation matrix of sites
- Type:
jax.Array
- cam_xpos#
camera positions
- Type:
jax.Array
- cam_xmat#
camera rotation matrices
- Type:
jax.Array
- subtree_com#
com of each subtree
- Type:
jax.Array
- cvel#
center of mass based velocity
- Type:
jax.Array
- cdof#
center of mass based jacobian
- Type:
jax.Array
- cdof_dot#
time-derivative of cdof
- Type:
jax.Array
- qfrc_bias#
C(qpos,qvel)
- Type:
jax.Array
- qfrc_gravcomp#
gravity compensation term
- Type:
jax.Array
- qfrc_fluid#
fluid drag and buoyancy forces
- Type:
jax.Array
- qfrc_passive#
passive force
- Type:
jax.Array
- qfrc_actuator#
actuator force
- Type:
jax.Array
- actuator_force#
actuator force in actuation space
- Type:
jax.Array
- actuator_length#
actuator lengths
- Type:
jax.Array
- qfrc_smooth#
smooth dynamics force
- Type:
jax.Array
- qacc_smooth#
acceleration without constraints
- Type:
jax.Array
- qfrc_constraint#
constraint force
- Type:
jax.Array
- qfrc_inverse#
net external force for inverse dynamics
- Type:
jax.Array
- bind(model: Model, obj: MjsBody | MjsFrame | MjsGeom | MjsJoint | MjsLight | MjsMaterial | MjsSite | MjsMesh | MjsSkin | MjsTexture | MjsText | MjsTuple | MjsCamera | MjsFlex | MjsHField | MjsKey | MjsNumeric | MjsPair | MjsExclude | MjsEquality | MjsTendon | MjsSensor | MjsActuator | MjsPlugin | Iterable[MjsBody | MjsFrame | MjsGeom | MjsJoint | MjsLight | MjsMaterial | MjsSite | MjsMesh | MjsSkin | MjsTexture | MjsText | MjsTuple | MjsCamera | MjsFlex | MjsHField | MjsKey | MjsNumeric | MjsPair | MjsExclude | MjsEquality | MjsTendon | MjsSensor | MjsActuator | MjsPlugin]) BindData#
Bind a Mujoco spec to an MJX Data.
- make_constraint(m: Model, d: Data) Data[source]#
Creates constraint jacobians and other supporting data.
- deriv_smooth_vel(m: Model, d: Data) Array | None[source]#
Analytical derivative of smooth forces w.r.t. velocities.
- fwd_acceleration(m: Model, d: Data) Data[source]#
Add up all non-constraint forces, compute qacc_smooth.
- create_render_context(mjm: MjModel, nworld: int, devices: Sequence[str] | None = None, **kwargs)[source]#
Creates a render context.
- Parameters:
mjm – the MuJoCo model
nworld – number of worlds to render. We must hardcode the nworld because Warp creates arrays of size nworld that are not exposed to JAX. Thus we cannot use JAX transforms like vmap with the render context.
devices – optional list of device names (e.g. [‘cuda:0’, ‘cuda:1’]). If provided, rendering workloads are sharded across these devices. By default, devices is None and the default device from wp.get_device(None) is used.
**kwargs – forwarded to the render context constructor.
- Returns:
Render context object that is JAX compatible.
- get_data(m: MjModel, d: Data, keepalive_refs: Dict[int, Any] | None = None) MjData | List[MjData][source]#
Gets mjx.Data from a device, resulting in mujoco.MjData or List[MjData].
- get_data_into(result: MjData | List[MjData], m: MjModel, d: Data, keepalive_refs: Dict[int, Any] | None = None)[source]#
Gets mjx.Data from a device into an existing mujoco.MjData or list.
- get_state(m: Model, d: Data, spec: int | mjtState) Array[source]#
Gets state from mjx.Data. This is equivalent to
mujoco.mj_getState.- Parameters:
m – model describing the simulation
d – data for the simulation
spec – int bitmask or mjtState enum specifying which state components to include
- Returns:
a flat array of state values
- make_data(m: Model | MjModel, device: Device | None = None, impl: str | Impl | None = None, _full_compat: bool = False, nconmax: int | None = None, naconmax: int | None = None, naccdmax: int | None = None, njmax: int | None = None, keepalive_refs: Dict[int, Any] | None = None) Data[source]#
Allocate and initialize Data.
- Parameters:
m – the model to use
device – which device to use - if unspecified picks the default device
impl – implementation to use (‘jax’, ‘warp’)
nconmax – maximum number of contacts to allocate for warp across all worlds Since the number of worlds is not pre-defined in JAX, we use the
nconmaxargument to set the upper bound for the number of contacts across all worlds. In MuJoCo Warp, the analgous field is callednaconmax.naconmax – maximum number of contacts to allocate for warp across all worlds Since the number of worlds is not pre-defined in JAX, we use the
naconmaxargument to set the upper bound for the number of contacts across all worlds, rather than thenconmaxargument from MuJoCo Warp.naccdmax – maximum number of contacts for GJK collision detection across all worlds. Since the number of worlds is not pre-defined in JAX, we use the
naccdmaxargument to set the upper bound for the number of contacts across all worlds, rather than thenccdmaxargument from MuJoCo Warp.njmax – maximum number of constraints to allocate for warp across all worlds
keepalive_refs – optional dict to store references to underlying MuJoCo objects, preventing them from being garbage collected. Required for CPP impl when passing a types.Model.
- Returns:
an initialized mjx.Data placed on device
- Raises:
ValueError – if the model’s impl does not match the make_data impl
NotImplementedError – if the impl is not implemented yet
DeprecationWarning – if nconmax is used
- put_data(m: MjModel, d: MjData, device: Device | None = None, impl: str | Impl | None = None, nconmax: int | None = None, naconmax: int | None = None, njmax: int | None = None, dummy_arg_for_batching: Array | None = None, keepalive_refs: Dict[int, Any] | None = None) Data[source]#
Puts mujoco.MjData onto a device, resulting in mjx.Data.
- Parameters:
m – the model to use
d – the data to put on device
device – which device to use - if unspecified picks the default device
impl – implementation to use (‘jax’, ‘warp’)
nconmax – maximum number of contacts to allocate for warp
naconmax – maximum number of contacts to allocate for warp across all worlds Since the number of worlds is not pre-defined in JAX, we use the
naconmaxargument to set the upper bound for the number of contacts across all worlds, rather than thenconmaxargument from MuJoCo Warp.njmax – maximum number of constraints to allocate for warp
dummy_arg_for_batching – dummy argument to use for batching in cpp implementation
keepalive_refs – optional dict to store references to underlying MuJoCo objects, preventing them from being garbage collected.
- Returns:
an mjx.Data placed on device DeprecationWarning: if nconmax is used
- put_model(m: MjModel, device: Device | None = None, impl: str | Impl | None = None, graph_mode: GraphMode | None = None, keepalive_refs: Dict[int, Any] | None = None) Model[source]#
Puts mujoco.MjModel onto a device, resulting in mjx.Model.
- Parameters:
m – the model to put onto device
device – which device to use - if unspecified picks the default device
impl – implementation to use
graph_mode – CUDA graph capture mode (for Warp only). Use GraphMode enum from warp._src.jax_experimental.ffi. GraphMode.WARP is the default mode.
keepalive_refs – optional dict to store references to underlying MuJoCo objects, preventing them from being garbage collected. Required for CPP impl to keep the model alive.
- Returns:
an mjx.Model placed on device
- Raises:
ValueError – if impl is not supported
RuntimeError – if impl is WARP and warp-lang is not installed
- set_state(m: Model, d: Data, state: Array, spec: int | mjtState) Data[source]#
Sets state in mjx.Data. This is equivalent to
mujoco.mj_setState.- Parameters:
m – model describing the simulation
d – data for the simulation
state – a flat array of state values
spec – int bitmask or mjtState enum specifying which state components to include
- Returns:
data with state set to provided values
- state_size(m: Model, spec: int | mjtState) int[source]#
Returns the size of a state vector for a given spec.
- Parameters:
m – model describing the simulation
spec – int bitmask or mjtState enum specifying which state components to include
- Returns:
size of the state vector
- ray(m: Model, d: Data, pnt: Array, vec: Array, geomgroup: Sequence[int] = (), flg_static: bool = True, bodyexclude: Sequence[int] | int = -1) Tuple[Array, Array][source]#
Returns the geom id and distance at which a ray intersects with a geom.
- Parameters:
m – MJX model
d – MJX data
pnt – ray origin point (3,)
vec – ray direction (3,)
geomgroup – group inclusion/exclusion mask, or empty to ignore
flg_static – if True, allows rays to intersect with static geoms
bodyexclude – ignore geoms on specified body id or sequence of body ids
- Returns:
Distance from ray origin to geom surface (or -1.0 for no intersection) and id of intersected geom (or -1 for no intersection)
- get_depth(rc: RenderContextPytree, cam_id: int, depth_data: Array, depth_scale: float) Array[source]#
Extract and normalize depth data for a camera.
- Parameters:
rc – RenderContextPytree.
cam_id – Camera index to extract.
depth_data – Raw depth output, shape (total_pixels,) as float32.
depth_scale – Scale factor for normalizing depth values.
- Returns:
Float32 depth array with shape (H, W), clamped to [0, 1].
- Raises:
RuntimeError – If Warp is not installed.
- get_rgb(rc: RenderContextPytree, cam_id: int, rgb_data: Array) Array[source]#
Unpack uint32 ABGR pixel data into float32 RGB.
- Parameters:
rc – RenderContextPytree.
cam_id – Camera index to extract.
rgb_data – Packed render output, shape (total_pixels,) as uint32.
- Returns:
Float32 RGB array with shape (H, W, 3), values in [0, 1].
- Raises:
RuntimeError – If Warp is not installed.
- com_pos(m: Model, d: Data) Data[source]#
Maps inertias and motion dofs to global frame centered at subtree-CoM.
- kinematics(m: Model, d: Data) Data[source]#
Converts position/velocity from generalized coordinates to maximal.
- rne(m: Model, d: Data, flg_acc: bool = False) Data[source]#
Computes inverse dynamics using the recursive Newton-Euler algorithm.
flg_acc=False removes inertial term.
- rne_postconstraint(m: Model, d: Data) Data[source]#
RNE with complete data: compute cacc, cfrc_ext, cfrc_int.
- solve(m: Model, d: Data) Data[source]#
Finds forces that satisfy constraints using conjugate gradient descent.
- apply_ft(m: Model, d: Data, force: Array, torque: Array, point: Array, body_id: Array) Array[source]#
Apply Cartesian force and torque.
- id2name(m: Model | MjModel, typ: mjtObj, i: int) str | None[source]#
Gets the name of an object with the specified mjtObj type and ids.
See mujoco.id2name for more info.
- Parameters:
m – mujoco.MjModel or mjx.Model
typ – mujoco.mjtObj type
i – the id
- Returns:
the name string, or None if not found
- is_sparse(m: MjModel | Model) bool[source]#
Return True if this model should create sparse mass matrices.
- Parameters:
m – a MuJoCo or MJX model
- Returns:
True if provided model should create sparse mass matrices
Modern TPUs have specialized hardware for rapidly operating over sparse matrices, whereas GPUs tend to be faster with dense matrices as long as they fit onto the device. As such, the default behavior in MJX (via
JacobianType.AUTO) is sparse ifnvis >= 60 or MJX detects a TPU as the default backend, otherwise dense.
- jac(m: Model, d: Data, point: Array, body_id: Array) Tuple[Array, Array][source]#
Compute pair of (NV, 3) Jacobians of global point attached to body.
- name2id(m: Model | MjModel, typ: mjtObj, name: str) int[source]#
Gets the id of an object with the specified mjtObj type and name.
See mujoco.mj_name2id for more info.
- Parameters:
m – mujoco.MjModel or mjx.Model
typ – mujoco.mjtObj type
name – the name of the object
- Returns:
the id, or -1 if not found
- benchmark(m: MjModel, nstep: int = 1000, batch_size: int = 1024, unroll_steps: int = 1, solver: str = 'newton', iterations: int = 1, ls_iterations: int = 4) Tuple[float, float, int][source]#
Benchmark a model.
- 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 CamLightType[source]#
Type of camera light.
- 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
- class ConstraintType[source]#
Type of constraint.
- EQUALITY#
equality constraint
- LIMIT_JOINT#
joint limit
- LIMIT_TENDON#
tendon limit
- CONTACT_FRICTIONLESS#
frictionless contact
- CONTACT_PYRAMIDAL#
frictional contact, pyramidal friction cone
- class Contact[source]#
Result of collision detection functions.
- dist#
distance between nearest points; neg: penetration
- Type:
jax.Array
- pos#
position of contact point: midpoint between geoms (3,)
- Type:
jax.Array
- frame#
normal is in [0-2] (9,)
- Type:
jax.Array
- includemargin#
include if dist<includemargin=margin-gap (1,)
- Type:
jax.Array
- friction#
tangent1, 2, spin, roll1, 2 (5,)
- Type:
jax.Array
- solref#
constraint solver reference, normal direction (mjNREF,)
- Type:
jax.Array
- solreffriction#
constraint solver reference, friction directions (mjNREF,)
- Type:
jax.Array
- solimp#
constraint solver impedance (mjNIMP,)
- Type:
jax.Array
- dim#
contact space dimensionality: 1, 3, 4, or 6
- Type:
numpy.ndarray
- geom1#
id of geom 1; deprecated, use geom[0]
- Type:
jax.Array
- geom2#
id of geom 2; deprecated, use geom[1]
- Type:
jax.Array
- geom#
geom ids (2,)
- Type:
jax.Array
- efc_address#
address in efc; -1: not included
- Type:
numpy.ndarray
- class ConvexMesh[source]#
Geom properties for convex meshes.
- vert#
vertices of the convex mesh
- Type:
jax.Array
- face#
faces of the convex mesh
- Type:
jax.Array
- face_normal#
normal vectors for the faces
- Type:
jax.Array
- edge#
edge indexes for all edges in the convex mesh
- Type:
jax.Array
- edge_face_normal#
indexes for face normals adjacent to edges in
edge- Type:
jax.Array
- 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
- ACTUATION#
apply actuation forces
- REFSAFE#
integrator safety: make ref[0]>=2*timestep
- SENSOR#
sensors
- 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.
- INVDISCRETE#
discrete-time inverse dynamics
- class EqType[source]#
Type of equality constraint.
- CONNECT#
connect two bodies at a point (ball joint)
- WELD#
fix relative position and orientation of two bodies
- JOINT#
couple the values of two scalar joints with cubic
- TENDON#
couple the lengths of two tendons with cubic
- 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#
height field
- SPHERE#
sphere
- CAPSULE#
capsule
- ELLIPSOID#
ellipsoid
- CYLINDER#
cylinder
- BOX#
box
- MESH#
mesh
- SDF#
signed distance field
- class IntegratorType[source]#
Integrator mode.
- EULER#
semi-implicit Euler
- RK4#
4th-order Runge Kutta
- IMPLICITFAST#
implicit in velocity, no rne derivative
- class JacobianType[source]#
Type of constraint Jacobian.
- DENSE#
dense
- SPARSE#
sparse
- AUTO#
sparse if nv>60 and device is TPU, dense otherwise
- 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 ObjType[source]#
Type of object.
- UNKNOWN#
unknown object type
- BODY#
body
- XBODY#
body, used to access regular frame instead of i-frame
- GEOM#
geom
- SITE#
site
- CAMERA#
camera
- class PyTreeNode[source]#
Base class for dataclasses that should act like a JAX pytree node.
This base class additionally avoids type checking errors when using PyType.
- class SensorType[source]#
Type of sensor.
- MAGNETOMETER#
magnetometer
- CAMPROJECTION#
camera projection
- RANGEFINDER#
rangefinder
- JOINTPOS#
joint position
- TENDONPOS#
scalar tendon position
- ACTUATORPOS#
actuator position
- BALLQUAT#
ball joint orientation
- FRAMEPOS#
frame position
- FRAMEXAXIS#
frame x-axis
- FRAMEYAXIS#
frame y-axis
- FRAMEZAXIS#
frame z-axis
- FRAMEQUAT#
frame orientation, represented as quaternion
- SUBTREECOM#
subtree centor of mass
- 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
- FRAMELINVEL#
3D linear velocity
- FRAMEANGVEL#
3D angular velocity
- SUBTREELINVEL#
subtree linear velocity
- SUBTREEANGMOM#
subtree angular momentum
- TOUCH#
scalar contact normal forces summed over the sensor zone
- CONTACT#
contacts which occurred during the simulation
- ACCELEROMETER#
accelerometer
- FORCE#
force
- TORQUE#
torque
- ACTUATORFRC#
scalar actuator force
- JOINTACTFRC#
scalar actuator force, measured at the joint
- TENDONACTFRC#
scalar actuator force, measured at the tendon
- FRAMELINACC#
3D linear acceleration
- FRAMEANGACC#
3D angular acceleration
- class SolverType[source]#
Constraint solver algorithm.
- CG#
Conjugate gradient (primal)
- NEWTON#
Newton (primal)
- class Statistic[source]#
Model statistics (in qpos0).
- meaninertia#
mean diagonal inertia
- Type:
jax.Array
- meanmass#
mean body mass (not used)
- Type:
jax.Array
- meansize#
mean body size (not used)
- Type:
jax.Array
- extent#
spatial extent (not used)
- Type:
jax.Array
- center#
center of model (not used)
- Type:
jax.Array