mjlab.entity#
Entity models and data structures.
Classes:
Data container for an entity. |
|
An entity represents a physical object in the simulation. |
|
EntityArticulationInfoCfg(actuators: 'tuple[actuator.ActuatorCfg, ...]' = <factory>, soft_joint_pos_limit_factor: 'float' = 1.0) |
|
EntityCfg(init_state: 'InitialStateCfg' = <factory>, spec_fn: 'Callable[[], mujoco.MjSpec]' = <factory>, articulation: 'EntityArticulationInfoCfg | None' = None, lights: 'tuple[spec_cfg.LightCfg, ...]' = <factory>, cameras: 'tuple[spec_cfg.CameraCfg, ...]' = <factory>, textures: 'tuple[spec_cfg.TextureCfg, ...]' = <factory>, materials: 'tuple[spec_cfg.MaterialCfg, ...]' = <factory>, collisions: 'tuple[spec_cfg.CollisionCfg, ...]' = <factory>) |
|
Maps entity elements to global indices and addresses in the simulation. |
- class mjlab.entity.EntityData[source]#
Bases:
objectData container for an entity.
Note: Write methods (write_*) modify state directly. Read properties (e.g., root_link_pose_w) require sim.forward() to be current. If you write then read, call sim.forward() in between. Event order matters when mixing reads and writes. All inputs/outputs use world frame.
Attributes:
Root link pose in simulation world frame.
Root link velocity in simulation world frame.
Root center-of-mass pose in simulation world frame.
Root center-of-mass velocity in world frame.
Body link pose in simulation world frame.
Body link velocity in simulation world frame.
Body center-of-mass pose in simulation world frame.
Body center-of-mass velocity in simulation world frame.
Body external wrench in world frame.
Geom pose in simulation world frame.
Geom velocity in simulation world frame.
Site pose in simulation world frame.
Site velocity in simulation world frame.
Joint positions.
Joint positions with encoder bias applied.
Joint velocities.
Joint accelerations.
Tendon lengths.
Tendon velocities.
Joint torques.
Scalar actuation force in actuation space.
Generalized forces applied to the DoFs.
Root link position in world frame.
Root link quaternion in world frame.
Root link linear velocity in world frame.
Root link angular velocity in world frame.
Root COM position in world frame.
Root COM quaternion in world frame.
Root COM linear velocity in world frame.
Root COM angular velocity in world frame.
Body link positions in world frame.
Body link quaternions in world frame.
Body link linear velocities in world frame.
Body link angular velocities in world frame.
Body COM positions in world frame.
Body COM quaternions in world frame.
Body COM linear velocities in world frame.
Body COM angular velocities in world frame.
Body external forces in world frame.
Body external torques in world frame.
Geom positions in world frame.
Geom quaternions in world frame.
Geom linear velocities in world frame.
Geom angular velocities in world frame.
Site positions in world frame.
Site quaternions in world frame.
Site linear velocities in world frame.
Site angular velocities in world frame.
Gravity vector projected into body frame.
Heading angle in world frame.
Root link linear velocity in body frame.
Root link angular velocity in body frame.
Root COM linear velocity in body frame.
Root COM angular velocity in body frame.
Methods:
write_root_state(root_state[, env_ids])write_root_pose(pose[, env_ids])write_root_velocity(velocity[, env_ids])write_joint_state(position, velocity[, ...])write_joint_position(position[, joint_ids, ...])write_joint_velocity(velocity[, joint_ids, ...])write_external_wrench(force, torque[, ...])write_ctrl(ctrl[, ctrl_ids, env_ids])write_mocap_pose(pose[, env_ids])clear_state([env_ids])__init__(indexing, data, model, device, ...)- indexing: EntityIndexing#
- data: mjwarp.Data#
- model: mjwarp.Model#
- default_root_state: torch.Tensor#
- default_joint_pos: torch.Tensor#
- default_joint_vel: torch.Tensor#
- default_joint_pos_limits: torch.Tensor#
- joint_pos_limits: torch.Tensor#
- soft_joint_pos_limits: torch.Tensor#
- gravity_vec_w: torch.Tensor#
- forward_vec_b: torch.Tensor#
- joint_pos_target: torch.Tensor#
- joint_vel_target: torch.Tensor#
- joint_effort_target: torch.Tensor#
- tendon_len_target: torch.Tensor#
- tendon_vel_target: torch.Tensor#
- tendon_effort_target: torch.Tensor#
- site_effort_target: torch.Tensor#
- encoder_bias: torch.Tensor#
- POS_DIM = 3#
- QUAT_DIM = 4#
- LIN_VEL_DIM = 3#
- ANG_VEL_DIM = 3#
- ROOT_POSE_DIM = 7#
- ROOT_VEL_DIM = 6#
- ROOT_STATE_DIM = 13#
- write_joint_state(position: Tensor, velocity: Tensor, joint_ids: Tensor | slice | None = None, env_ids: Tensor | slice | None = None) None[source]#
- write_joint_position(position: Tensor, joint_ids: Tensor | slice | None = None, env_ids: Tensor | slice | None = None) None[source]#
- write_joint_velocity(velocity: Tensor, joint_ids: Tensor | slice | None = None, env_ids: Tensor | slice | None = None) None[source]#
- write_external_wrench(force: Tensor | None, torque: Tensor | None, body_ids: Sequence[int] | slice | None = None, env_ids: Tensor | slice | None = None) None[source]#
- write_ctrl(ctrl: Tensor, ctrl_ids: Tensor | slice | None = None, env_ids: Tensor | slice | None = None) None[source]#
- property root_link_pose_w: Tensor#
Root link pose in simulation world frame. Shape (num_envs, 7).
- property root_link_vel_w: Tensor#
Root link velocity in simulation world frame. Shape (num_envs, 6).
- property root_com_pose_w: Tensor#
Root center-of-mass pose in simulation world frame. Shape (num_envs, 7).
- property root_com_vel_w: Tensor#
Root center-of-mass velocity in world frame. Shape (num_envs, 6).
- property body_link_pose_w: Tensor#
Body link pose in simulation world frame. Shape (num_envs, num_bodies, 7).
- property body_link_vel_w: Tensor#
Body link velocity in simulation world frame. Shape (num_envs, num_bodies, 6).
- property body_com_pose_w: Tensor#
Body center-of-mass pose in simulation world frame. Shape (num_envs, num_bodies, 7).
- property body_com_vel_w: Tensor#
Body center-of-mass velocity in simulation world frame. Shape (num_envs, num_bodies, 6).
- property body_external_wrench: Tensor#
Body external wrench in world frame. Shape (num_envs, num_bodies, 6).
- property geom_pose_w: Tensor#
Geom pose in simulation world frame. Shape (num_envs, num_geoms, 7).
- property geom_vel_w: Tensor#
Geom velocity in simulation world frame. Shape (num_envs, num_geoms, 6).
- property site_pose_w: Tensor#
Site pose in simulation world frame. Shape (num_envs, num_sites, 7).
- property site_vel_w: Tensor#
Site velocity in simulation world frame. Shape (num_envs, num_sites, 6).
- property joint_pos: Tensor#
Joint positions. Shape (num_envs, num_joints).
- property joint_pos_biased: Tensor#
Joint positions with encoder bias applied. Shape (num_envs, num_joints).
- property joint_vel: Tensor#
Joint velocities. Shape (num_envs, nv).
- property joint_acc: Tensor#
Joint accelerations. Shape (num_envs, nv).
- property tendon_len: Tensor#
Tendon lengths. Shape (num_envs, num_tendons).
- property tendon_vel: Tensor#
Tendon velocities. Shape (num_envs, num_tendons).
- property joint_torques: Tensor#
Joint torques. Shape (num_envs, nv).
- property actuator_force: Tensor#
Scalar actuation force in actuation space. Shape (num_envs, nu).
- property generalized_force: Tensor#
Generalized forces applied to the DoFs. Shape (num_envs, nv).
- property root_link_pos_w: Tensor#
Root link position in world frame. Shape (num_envs, 3).
- property root_link_quat_w: Tensor#
Root link quaternion in world frame. Shape (num_envs, 4).
- property root_link_lin_vel_w: Tensor#
Root link linear velocity in world frame. Shape (num_envs, 3).
- property root_link_ang_vel_w: Tensor#
Root link angular velocity in world frame. Shape (num_envs, 3).
- property root_com_pos_w: Tensor#
Root COM position in world frame. Shape (num_envs, 3).
- property root_com_quat_w: Tensor#
Root COM quaternion in world frame. Shape (num_envs, 4).
- property root_com_lin_vel_w: Tensor#
Root COM linear velocity in world frame. Shape (num_envs, 3).
- property root_com_ang_vel_w: Tensor#
Root COM angular velocity in world frame. Shape (num_envs, 3).
- property body_link_pos_w: Tensor#
Body link positions in world frame. Shape (num_envs, num_bodies, 3).
- property body_link_quat_w: Tensor#
Body link quaternions in world frame. Shape (num_envs, num_bodies, 4).
- property body_link_lin_vel_w: Tensor#
Body link linear velocities in world frame. Shape (num_envs, num_bodies, 3).
- property body_link_ang_vel_w: Tensor#
Body link angular velocities in world frame. Shape (num_envs, num_bodies, 3).
- property body_com_pos_w: Tensor#
Body COM positions in world frame. Shape (num_envs, num_bodies, 3).
- property body_com_quat_w: Tensor#
Body COM quaternions in world frame. Shape (num_envs, num_bodies, 4).
- property body_com_lin_vel_w: Tensor#
Body COM linear velocities in world frame. Shape (num_envs, num_bodies, 3).
- property body_com_ang_vel_w: Tensor#
Body COM angular velocities in world frame. Shape (num_envs, num_bodies, 3).
- property body_external_force: Tensor#
Body external forces in world frame. Shape (num_envs, num_bodies, 3).
- property body_external_torque: Tensor#
Body external torques in world frame. Shape (num_envs, num_bodies, 3).
- property geom_pos_w: Tensor#
Geom positions in world frame. Shape (num_envs, num_geoms, 3).
- property geom_quat_w: Tensor#
Geom quaternions in world frame. Shape (num_envs, num_geoms, 4).
- property geom_lin_vel_w: Tensor#
Geom linear velocities in world frame. Shape (num_envs, num_geoms, 3).
- property geom_ang_vel_w: Tensor#
Geom angular velocities in world frame. Shape (num_envs, num_geoms, 3).
- property site_pos_w: Tensor#
Site positions in world frame. Shape (num_envs, num_sites, 3).
- property site_quat_w: Tensor#
Site quaternions in world frame. Shape (num_envs, num_sites, 4).
- property site_lin_vel_w: Tensor#
Site linear velocities in world frame. Shape (num_envs, num_sites, 3).
- property site_ang_vel_w: Tensor#
Site angular velocities in world frame. Shape (num_envs, num_sites, 3).
- property projected_gravity_b: Tensor#
Gravity vector projected into body frame. Shape (num_envs, 3).
- property heading_w: Tensor#
Heading angle in world frame. Shape (num_envs,).
- property root_link_lin_vel_b: Tensor#
Root link linear velocity in body frame. Shape (num_envs, 3).
- property root_link_ang_vel_b: Tensor#
Root link angular velocity in body frame. Shape (num_envs, 3).
- property root_com_lin_vel_b: Tensor#
Root COM linear velocity in body frame. Shape (num_envs, 3).
- property root_com_ang_vel_b: Tensor#
Root COM angular velocity in body frame. Shape (num_envs, 3).
- __init__(indexing: EntityIndexing, data: mjwarp.Data, model: mjwarp.Model, device: str, default_root_state: torch.Tensor, default_joint_pos: torch.Tensor, default_joint_vel: torch.Tensor, default_joint_pos_limits: torch.Tensor, joint_pos_limits: torch.Tensor, soft_joint_pos_limits: torch.Tensor, gravity_vec_w: torch.Tensor, forward_vec_b: torch.Tensor, is_fixed_base: bool, is_articulated: bool, is_actuated: bool, joint_pos_target: torch.Tensor, joint_vel_target: torch.Tensor, joint_effort_target: torch.Tensor, tendon_len_target: torch.Tensor, tendon_vel_target: torch.Tensor, tendon_effort_target: torch.Tensor, site_effort_target: torch.Tensor, encoder_bias: torch.Tensor) None#
- class mjlab.entity.Entity[source]#
Bases:
objectAn entity represents a physical object in the simulation.
Entity Type Matrix#
MuJoCo entities can be categorized along two dimensions:
Base Type:
Fixed Base: Entity is welded to the world (no freejoint)
Floating Base: Entity has 6 DOF movement (has freejoint)
Articulation:
Non-articulated: No joints other than freejoint
Articulated: Has joints in kinematic tree (may or may not be actuated)
Fixed non-articulated entities can optionally be mocap bodies, whereby their position and orientation can be set directly each timestep rather than being determined by physics. This property can be useful for creating props with adjustable position and orientation.
Supported Combinations:#
Type | Example | is_fixed_base | is_articulated | is_actuated ||---------------------------|———————|---------------|—————-|-------------| | Fixed Non-articulated | Table, wall | True | False | False | | Fixed Articulated | Robot arm, door | True | True | True/False | | Floating Non-articulated | Box, ball, mug | False | False | False | | Floating Articulated | Humanoid, quadruped | False | True | True/False |
Methods:
__init__(cfg)find_bodies(name_keys[, preserve_order])find_joints(name_keys[, joint_subset, ...])find_actuators(name_keys[, actuator_subset, ...])find_tendons(name_keys[, tendon_subset, ...])find_joints_by_actuator_names(actuator_name_keys)find_geoms(name_keys[, geom_subset, ...])find_sites(name_keys[, site_subset, ...])compile()Compile the underlying MjSpec into an MjModel.
write_xml(xml_path)Write the MjSpec to disk.
to_zip(path)Write the MjSpec to a zip file.
initialize(mj_model, model, data, device)update(dt)reset([env_ids])clear_state([env_ids])write_ctrl_to_sim(ctrl[, ctrl_ids])Write control inputs to the simulation.
write_root_state_to_sim(root_state[, env_ids])Set the root state into the simulation.
write_root_link_pose_to_sim(root_pose[, env_ids])Set the root pose into the simulation.
write_root_link_velocity_to_sim(root_velocity)Set the root velocity into the simulation.
write_joint_state_to_sim(position, velocity)Set the joint state into the simulation.
write_joint_position_to_sim(position[, ...])Set the joint positions into the simulation.
write_joint_velocity_to_sim(velocity[, ...])Set the joint velocities into the simulation.
set_joint_position_target(position[, ...])Set joint position targets.
set_joint_velocity_target(velocity[, ...])Set joint velocity targets.
set_joint_effort_target(effort[, joint_ids, ...])Set joint effort targets.
set_tendon_len_target(length[, tendon_ids, ...])Set tendon length targets.
set_tendon_vel_target(velocity[, ...])Set tendon velocity targets.
set_tendon_effort_target(effort[, ...])Set tendon effort targets.
set_site_effort_target(effort[, site_ids, ...])Set site effort targets.
write_external_wrench_to_sim(forces, torques)Apply external wrenches to bodies in the simulation.
write_mocap_pose_to_sim(mocap_pose[, env_ids])Set the pose of a mocap body into the simulation.
Attributes:
Entity is welded to the world.
Entity is articulated (has fixed or actuated joints).
Entity has actuated joints.
Entity has actuators using tendon transmission.
Entity has actuators using site transmission.
Entity root body is a mocap body (only for fixed-base entities).
- property spec: MjSpec#
- property data: EntityData#
- property root_body: MjsBody#
- find_bodies(name_keys: str | Sequence[str], preserve_order: bool = False) tuple[list[int], list[str]][source]#
- find_joints(name_keys: str | Sequence[str], joint_subset: Sequence[str] | None = None, preserve_order: bool = False) tuple[list[int], list[str]][source]#
- find_actuators(name_keys: str | Sequence[str], actuator_subset: Sequence[str] | None = None, preserve_order: bool = False) tuple[list[int], list[str]][source]#
- find_tendons(name_keys: str | Sequence[str], tendon_subset: Sequence[str] | None = None, preserve_order: bool = False) tuple[list[int], list[str]][source]#
- find_joints_by_actuator_names(actuator_name_keys: str | Sequence[str]) tuple[list[int], list[str]][source]#
- find_geoms(name_keys: str | Sequence[str], geom_subset: Sequence[str] | None = None, preserve_order: bool = False) tuple[list[int], list[str]][source]#
- find_sites(name_keys: str | Sequence[str], site_subset: Sequence[str] | None = None, preserve_order: bool = False) tuple[list[int], list[str]][source]#
- initialize(mj_model: MjModel, model: mujoco_warp.Model, data: mujoco_warp.Data, device: str) None[source]#
- write_ctrl_to_sim(ctrl: Tensor, ctrl_ids: Tensor | slice | None = None) None[source]#
Write control inputs to the simulation.
- Parameters:
ctrl – A tensor of control inputs.
ctrl_ids – A tensor of control indices.
- write_root_state_to_sim(root_state: Tensor, env_ids: Tensor | slice | None = None) None[source]#
Set the root state into the simulation.
The root state consists of position (3), orientation as a (w, x, y, z) quaternion (4), linear velocity (3), and angular velocity (3), for a total of 13 values. All of the quantities are in the world frame.
- Parameters:
root_state – Tensor of shape (N, 13) where N is the number of environments.
env_ids – Optional tensor or slice specifying which environments to set. If None, all environments are set.
- write_root_link_pose_to_sim(root_pose: Tensor, env_ids: Tensor | slice | None = None)[source]#
Set the root pose into the simulation. Like write_root_state_to_sim() but only sets position and orientation.
- Parameters:
root_pose – Tensor of shape (N, 7) where N is the number of environments.
env_ids – Optional tensor or slice specifying which environments to set. If None, all environments are set.
- write_root_link_velocity_to_sim(root_velocity: Tensor, env_ids: Tensor | slice | None = None)[source]#
Set the root velocity into the simulation. Like write_root_state_to_sim() but only sets linear and angular velocity.
- Parameters:
root_velocity – Tensor of shape (N, 6) where N is the number of environments. Contains linear velocity (3) and angular velocity (3), both in world frame.
env_ids – Optional tensor or slice specifying which environments to set. If None, all environments are set.
- write_joint_state_to_sim(position: Tensor, velocity: Tensor, joint_ids: Tensor | slice | None = None, env_ids: Tensor | slice | None = None)[source]#
Set the joint state into the simulation.
The joint state consists of joint positions and velocities. It does not include the root state.
- Parameters:
position – Tensor of shape (N, num_joints) where N is the number of environments.
velocity – Tensor of shape (N, num_joints) where N is the number of environments.
joint_ids – Optional tensor or slice specifying which joints to set. If None, all joints are set.
env_ids – Optional tensor or slice specifying which environments to set. If None, all environments are set.
- write_joint_position_to_sim(position: Tensor, joint_ids: Tensor | slice | None = None, env_ids: Tensor | slice | None = None)[source]#
Set the joint positions into the simulation. Like write_joint_state_to_sim() but only sets joint positions.
- Parameters:
position – Tensor of shape (N, num_joints) where N is the number of environments.
joint_ids – Optional tensor or slice specifying which joints to set. If None, all joints are set.
env_ids – Optional tensor or slice specifying which environments to set. If None, all environments are set.
- write_joint_velocity_to_sim(velocity: Tensor, joint_ids: Tensor | slice | None = None, env_ids: Tensor | slice | None = None)[source]#
Set the joint velocities into the simulation. Like write_joint_state_to_sim() but only sets joint velocities.
- Parameters:
velocity – Tensor of shape (N, num_joints) where N is the number of environments.
joint_ids – Optional tensor or slice specifying which joints to set. If None, all joints are set.
env_ids – Optional tensor or slice specifying which environments to set. If None, all environments are set.
- set_joint_position_target(position: Tensor, joint_ids: Tensor | slice | None = None, env_ids: Tensor | slice | None = None) None[source]#
Set joint position targets.
- Parameters:
position – Target joint poisitions with shape (N, num_joints).
joint_ids – Optional joint indices to set. If None, set all joints.
env_ids – Optional environment indices. If None, set all environments.
- set_joint_velocity_target(velocity: Tensor, joint_ids: Tensor | slice | None = None, env_ids: Tensor | slice | None = None) None[source]#
Set joint velocity targets.
- Parameters:
velocity – Target joint velocities with shape (N, num_joints).
joint_ids – Optional joint indices to set. If None, set all joints.
env_ids – Optional environment indices. If None, set all environments.
- set_joint_effort_target(effort: Tensor, joint_ids: Tensor | slice | None = None, env_ids: Tensor | slice | None = None) None[source]#
Set joint effort targets.
- Parameters:
effort – Target joint efforts with shape (N, num_joints).
joint_ids – Optional joint indices to set. If None, set all joints.
env_ids – Optional environment indices. If None, set all environments.
- set_tendon_len_target(length: Tensor, tendon_ids: Tensor | slice | None = None, env_ids: Tensor | slice | None = None) None[source]#
Set tendon length targets.
- Parameters:
length – Target tendon lengths with shape (N, num_tendons).
tendon_ids – Optional tendon indices to set. If None, set all tendons.
env_ids – Optional environment indices. If None, set all environments.
- set_tendon_vel_target(velocity: Tensor, tendon_ids: Tensor | slice | None = None, env_ids: Tensor | slice | None = None) None[source]#
Set tendon velocity targets.
- Parameters:
velocity – Target tendon velocities with shape (N, num_tendons).
tendon_ids – Optional tendon indices to set. If None, set all tendons.
env_ids – Optional environment indices. If None, set all environments.
- set_tendon_effort_target(effort: Tensor, tendon_ids: Tensor | slice | None = None, env_ids: Tensor | slice | None = None) None[source]#
Set tendon effort targets.
- Parameters:
effort – Target tendon efforts with shape (N, num_tendons).
tendon_ids – Optional tendon indices to set. If None, set all tendons.
env_ids – Optional environment indices. If None, set all environments.
- set_site_effort_target(effort: Tensor, site_ids: Tensor | slice | None = None, env_ids: Tensor | slice | None = None) None[source]#
Set site effort targets.
- Parameters:
effort – Target site efforts with shape (N, num_sites).
site_ids – Optional site indices to set. If None, set all sites.
env_ids – Optional environment indices. If None, set all environments.
- write_external_wrench_to_sim(forces: Tensor, torques: Tensor, env_ids: Tensor | slice | None = None, body_ids: Sequence[int] | slice | None = None) None[source]#
Apply external wrenches to bodies in the simulation.
Underneath the hood, this sets the xfrc_applied field in the MuJoCo data structure. The wrenches are specified in the world frame and persist until the next call to this function or until the simulation is reset.
- Parameters:
forces – Tensor of shape (N, num_bodies, 3) where N is the number of environments.
torques – Tensor of shape (N, num_bodies, 3) where N is the number of environments.
env_ids – Optional tensor or slice specifying which environments to set. If None, all environments are set.
body_ids – Optional list of body indices or slice specifying which bodies to apply the wrenches to. If None, wrenches are applied to all bodies.
- write_mocap_pose_to_sim(mocap_pose: Tensor, env_ids: Tensor | slice | None = None) None[source]#
Set the pose of a mocap body into the simulation.
- Parameters:
mocap_pose – Tensor of shape (N, 7) where N is the number of environments. Format: [pos_x, pos_y, pos_z, quat_w, quat_x, quat_y, quat_z]
env_ids – Optional tensor or slice specifying which environments to set. If None, all environments are set.
- class mjlab.entity.EntityArticulationInfoCfg[source]#
Bases:
objectEntityArticulationInfoCfg(actuators: ‘tuple[actuator.ActuatorCfg, …]’ = <factory>, soft_joint_pos_limit_factor: ‘float’ = 1.0)
Attributes:
Methods:
__init__([actuators, ...])- actuators: tuple[ActuatorCfg, ...]#
- class mjlab.entity.EntityCfg[source]#
Bases:
objectEntityCfg(init_state: ‘InitialStateCfg’ = <factory>, spec_fn: ‘Callable[[], mujoco.MjSpec]’ = <factory>, articulation: ‘EntityArticulationInfoCfg | None’ = None, lights: ‘tuple[spec_cfg.LightCfg, …]’ = <factory>, cameras: ‘tuple[spec_cfg.CameraCfg, …]’ = <factory>, textures: ‘tuple[spec_cfg.TextureCfg, …]’ = <factory>, materials: ‘tuple[spec_cfg.MaterialCfg, …]’ = <factory>, collisions: ‘tuple[spec_cfg.CollisionCfg, …]’ = <factory>)
Classes:
InitialStateCfg(pos: 'tuple[float, float, float]' = (0.0, 0.0, 0.0), rot: 'tuple[float, float, float, float]' = (1.0, 0.0, 0.0, 0.0), lin_vel: 'tuple[float, float, float]' = (0.0, 0.0, 0.0), ang_vel: 'tuple[float, float, float]' = (0.0, 0.0, 0.0), joint_pos: 'dict[str, float] | None' = <factory>, joint_vel: 'dict[str, float]' = <factory>)
Attributes:
Methods:
- class InitialStateCfg[source]#
Bases:
objectInitialStateCfg(pos: ‘tuple[float, float, float]’ = (0.0, 0.0, 0.0), rot: ‘tuple[float, float, float, float]’ = (1.0, 0.0, 0.0, 0.0), lin_vel: ‘tuple[float, float, float]’ = (0.0, 0.0, 0.0), ang_vel: ‘tuple[float, float, float]’ = (0.0, 0.0, 0.0), joint_pos: ‘dict[str, float] | None’ = <factory>, joint_vel: ‘dict[str, float]’ = <factory>)
Attributes:
Methods:
__init__([pos, rot, lin_vel, ang_vel, ...])- __init__(pos: tuple[float, float, float] = (0.0, 0.0, 0.0), rot: tuple[float, float, float, float] = (1.0, 0.0, 0.0, 0.0), lin_vel: tuple[float, float, float] = (0.0, 0.0, 0.0), ang_vel: tuple[float, float, float] = (0.0, 0.0, 0.0), joint_pos: dict[str, float] | None = <factory>, joint_vel: dict[str, float] = <factory>) None#
- init_state: InitialStateCfg#
- spec_fn: Callable[[], mujoco.MjSpec]#
- articulation: EntityArticulationInfoCfg | None = None#
- build() Entity[source]#
Build entity instance from this config.
Override in subclasses to return custom Entity types.
- __init__(init_state: InitialStateCfg = <factory>, spec_fn: Callable[[], mujoco.MjSpec] = <factory>, articulation: EntityArticulationInfoCfg | None = None, lights: tuple[spec_cfg.LightCfg, ...] = <factory>, cameras: tuple[spec_cfg.CameraCfg, ...] = <factory>, textures: tuple[spec_cfg.TextureCfg, ...] = <factory>, materials: tuple[spec_cfg.MaterialCfg, ...] = <factory>, collisions: tuple[spec_cfg.CollisionCfg, ...] = <factory>) None#
- class mjlab.entity.EntityIndexing[source]#
Bases:
objectMaps entity elements to global indices and addresses in the simulation.
Attributes:
Methods:
__init__(bodies, joints, geoms, sites, ...)- body_ids: Tensor#
- geom_ids: Tensor#
- site_ids: Tensor#
- tendon_ids: Tensor#
- ctrl_ids: Tensor#
- joint_ids: Tensor#
- joint_q_adr: Tensor#
- joint_v_adr: Tensor#
- free_joint_q_adr: Tensor#
- free_joint_v_adr: Tensor#
- __init__(bodies: tuple[MjsBody, ...], joints: tuple[MjsJoint, ...], geoms: tuple[MjsGeom, ...], sites: tuple[MjsSite, ...], tendons: tuple[MjsTendon, ...], actuators: tuple[MjsActuator, ...] | None, body_ids: Tensor, geom_ids: Tensor, site_ids: Tensor, tendon_ids: Tensor, ctrl_ids: Tensor, joint_ids: Tensor, mocap_id: int | None, joint_q_adr: Tensor, joint_v_adr: Tensor, free_joint_q_adr: Tensor, free_joint_v_adr: Tensor) None#