mjlab.actuator

Contents

mjlab.actuator#

Actuator implementations for motor control.

Actuator implementations for mjlab.

class mjlab.actuator.Actuator[source]#

Bases: ABC, Generic[ActuatorCfgT]

Base actuator interface.

__init__(cfg: ActuatorCfgT, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
abstractmethod compute(cmd: ActuatorCmd) Tensor[source]#

Compute low-level actuator control signal from high-level commands.

Parameters:

cmd – High-level actuator command.

Returns:

Control signal tensor of shape (num_envs, num_actuators).

property ctrl_ids: Tensor#

Local indices of control inputs within the entity.

abstractmethod edit_spec(spec: MjSpec, target_names: list[str]) None[source]#

Edit the MjSpec to add actuators.

This is called during entity construction, before the model is compiled.

Parameters:
  • spec – The entity’s MjSpec to edit.

  • target_names – Names of targets (joints, tendons, or sites) controlled by this actuator.

get_command(data: EntityData) ActuatorCmd[source]#

Extract command data for this actuator from entity data.

Parameters:

data – The entity data containing all state and target information.

Returns:

ActuatorCmd with appropriate data based on transmission type.

property global_ctrl_ids: Tensor#

Global indices of control inputs in the MuJoCo model.

initialize(mj_model: MjModel, model: mujoco_warp.Model, data: mujoco_warp.Data, device: str) None[source]#

Initialize the actuator after model compilation.

This is called after the MjSpec is compiled into an MjModel.

Parameters:
  • mj_model – The compiled MuJoCo model.

  • model – The compiled mjwarp model.

  • data – The mjwarp data arrays.

  • device – Device for tensor operations (e.g., “cuda”, “cpu”).

reset(env_ids: Tensor | slice | None = None) None[source]#

Reset actuator state for specified environments.

Base implementation does nothing. Override in subclasses that maintain internal state.

Parameters:

env_ids – Environment indices to reset. If None, reset all environments.

property target_ids: Tensor#

Local indices of targets controlled by this actuator.

property target_names: list[str]#

Names of targets controlled by this actuator.

property transmission_type: TransmissionType#

Transmission type of this actuator.

update(dt: float) None[source]#

Update actuator state after a simulation step.

Base implementation does nothing. Override in subclasses that need per-step updates.

Parameters:

dt – Time step in seconds.

class mjlab.actuator.ActuatorCfg[source]#

Bases: ABC

__init__(*, target_names_expr: tuple[str, ...], transmission_type: TransmissionType = TransmissionType.JOINT, armature: float = 0.0, frictionloss: float = 0.0) None#
armature: float = 0.0#

Reflected rotor inertia.

abstractmethod build(entity: Entity, target_ids: list[int], target_names: list[str]) Actuator[source]#

Build actuator instance.

Parameters:
  • entity – Entity this actuator belongs to.

  • target_ids – Local target indices (for indexing entity arrays).

  • target_names – Target names corresponding to target_ids.

Returns:

Actuator instance.

frictionloss: float = 0.0#

Friction loss force limit.

Applies a constant friction force opposing motion, independent of load or velocity. Also known as dry friction or load-independent friction.

transmission_type: TransmissionType = 'joint'#

Transmission type. Defaults to JOINT.

target_names_expr: tuple[str, ...]#

Targets that are part of this actuator group.

Can be a tuple of names or tuple of regex expressions. Interpreted based on transmission_type (joint/tendon/site).

class mjlab.actuator.ActuatorCmd[source]#

Bases: object

High-level actuator command with targets and current state.

Passed to actuator’s compute() method to generate low-level control signals. All tensors have shape (num_envs, num_targets).

__init__(position_target: Tensor, velocity_target: Tensor, effort_target: Tensor, pos: Tensor, vel: Tensor) None#
position_target: Tensor#

Desired positions (joint positions, tendon lengths, or site positions).

velocity_target: Tensor#

Desired velocities (joint velocities, tendon velocities, or site velocities).

effort_target: Tensor#

Feedforward effort (torques or forces).

pos: Tensor#

Current positions (joint positions, tendon lengths, or site positions).

vel: Tensor#

Current velocities (joint velocities, tendon velocities, or site velocities).

class mjlab.actuator.BuiltinMotorActuator[source]#

Bases: Actuator[BuiltinMotorActuatorCfg]

MuJoCo built-in motor actuator.

__init__(cfg: BuiltinMotorActuatorCfg, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
compute(cmd: ActuatorCmd) Tensor[source]#

Compute low-level actuator control signal from high-level commands.

Parameters:

cmd – High-level actuator command.

Returns:

Control signal tensor of shape (num_envs, num_actuators).

edit_spec(spec: MjSpec, target_names: list[str]) None[source]#

Edit the MjSpec to add actuators.

This is called during entity construction, before the model is compiled.

Parameters:
  • spec – The entity’s MjSpec to edit.

  • target_names – Names of targets (joints, tendons, or sites) controlled by this actuator.

class mjlab.actuator.BuiltinMotorActuatorCfg[source]#

Bases: ActuatorCfg

Configuration for MuJoCo built-in motor actuator.

Under the hood, this creates a <motor> actuator for each target and sets its effort limit and gear ratio accordingly. It also modifies the target’s properties, namely armature and frictionloss.

__init__(*, target_names_expr: tuple[str, ...], transmission_type: TransmissionType = TransmissionType.JOINT, armature: float = 0.0, frictionloss: float = 0.0, effort_limit: float, gear: float = 1.0) None#
build(entity: Entity, target_ids: list[int], target_names: list[str]) BuiltinMotorActuator[source]#

Build actuator instance.

Parameters:
  • entity – Entity this actuator belongs to.

  • target_ids – Local target indices (for indexing entity arrays).

  • target_names – Target names corresponding to target_ids.

Returns:

Actuator instance.

gear: float = 1.0#

Actuator gear ratio.

effort_limit: float#

Maximum actuator effort.

class mjlab.actuator.BuiltinMuscleActuator[source]#

Bases: Actuator[BuiltinMuscleActuatorCfg]

MuJoCo built-in muscle actuator.

__init__(cfg: BuiltinMuscleActuatorCfg, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
compute(cmd: ActuatorCmd) Tensor[source]#

Compute low-level actuator control signal from high-level commands.

Parameters:

cmd – High-level actuator command.

Returns:

Control signal tensor of shape (num_envs, num_actuators).

edit_spec(spec: MjSpec, target_names: list[str]) None[source]#

Edit the MjSpec to add actuators.

This is called during entity construction, before the model is compiled.

Parameters:
  • spec – The entity’s MjSpec to edit.

  • target_names – Names of targets (joints, tendons, or sites) controlled by this actuator.

class mjlab.actuator.BuiltinMuscleActuatorCfg[source]#

Bases: ActuatorCfg

Configuration for MuJoCo built-in muscle actuator.

__init__(*, target_names_expr: tuple[str, ...], transmission_type: TransmissionType = TransmissionType.JOINT, armature: float = 0.0, frictionloss: float = 0.0, length_range: tuple[float, float] = (0.0, 0.0), gear: float = 1.0, timeconst: tuple[float, float] = (0.01, 0.04), tausmooth: float = 0.0, range: tuple[float, float] = (0.75, 1.05), force: float = -1.0, scale: float = 200.0, lmin: float = 0.5, lmax: float = 1.6, vmax: float = 1.5, fpmax: float = 1.3, fvmax: float = 1.2) None#
build(entity: Entity, target_ids: list[int], target_names: list[str]) BuiltinMuscleActuator[source]#

Build actuator instance.

Parameters:
  • entity – Entity this actuator belongs to.

  • target_ids – Local target indices (for indexing entity arrays).

  • target_names – Target names corresponding to target_ids.

Returns:

Actuator instance.

force: float = -1.0#

Peak force (if -1, defaults to scale * FLV).

fpmax: float = 1.3#

Passive force at lmax.

fvmax: float = 1.2#

Active force at -vmax.

gear: float = 1.0#

Gear ratio.

length_range: tuple[float, float] = (0.0, 0.0)#

Length range for muscle actuator.

lmax: float = 1.6#

Maximum normalized muscle length.

lmin: float = 0.5#

Minimum normalized muscle length.

range: tuple[float, float] = (0.75, 1.05)#

Operating range of normalized muscle length.

scale: float = 200.0#

Force scaling factor.

tausmooth: float = 0.0#

Smoothing time constant.

timeconst: tuple[float, float] = (0.01, 0.04)#

Activation and deactivation time constants.

vmax: float = 1.5#

Maximum normalized muscle velocity.

class mjlab.actuator.BuiltinPositionActuator[source]#

Bases: Actuator[BuiltinPositionActuatorCfg]

MuJoCo built-in position actuator.

__init__(cfg: BuiltinPositionActuatorCfg, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
compute(cmd: ActuatorCmd) Tensor[source]#

Compute low-level actuator control signal from high-level commands.

Parameters:

cmd – High-level actuator command.

Returns:

Control signal tensor of shape (num_envs, num_actuators).

edit_spec(spec: MjSpec, target_names: list[str]) None[source]#

Edit the MjSpec to add actuators.

This is called during entity construction, before the model is compiled.

Parameters:
  • spec – The entity’s MjSpec to edit.

  • target_names – Names of targets (joints, tendons, or sites) controlled by this actuator.

class mjlab.actuator.BuiltinPositionActuatorCfg[source]#

Bases: ActuatorCfg

Configuration for MuJoCo built-in position actuator.

Under the hood, this creates a <position> actuator for each target and sets the stiffness, damping and effort limits accordingly. It also modifies the target’s properties, namely armature and frictionloss.

__init__(*, target_names_expr: tuple[str, ...], transmission_type: TransmissionType = TransmissionType.JOINT, armature: float = 0.0, frictionloss: float = 0.0, stiffness: float, damping: float, effort_limit: float | None = None) None#
build(entity: Entity, target_ids: list[int], target_names: list[str]) BuiltinPositionActuator[source]#

Build actuator instance.

Parameters:
  • entity – Entity this actuator belongs to.

  • target_ids – Local target indices (for indexing entity arrays).

  • target_names – Target names corresponding to target_ids.

Returns:

Actuator instance.

effort_limit: float | None = None#

Maximum actuator force/torque. If None, no limit is applied.

stiffness: float#

PD proportional gain.

damping: float#

PD derivative gain.

class mjlab.actuator.BuiltinVelocityActuator[source]#

Bases: Actuator[BuiltinVelocityActuatorCfg]

MuJoCo built-in velocity actuator.

__init__(cfg: BuiltinVelocityActuatorCfg, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
compute(cmd: ActuatorCmd) Tensor[source]#

Compute low-level actuator control signal from high-level commands.

Parameters:

cmd – High-level actuator command.

Returns:

Control signal tensor of shape (num_envs, num_actuators).

edit_spec(spec: MjSpec, target_names: list[str]) None[source]#

Edit the MjSpec to add actuators.

This is called during entity construction, before the model is compiled.

Parameters:
  • spec – The entity’s MjSpec to edit.

  • target_names – Names of targets (joints, tendons, or sites) controlled by this actuator.

class mjlab.actuator.BuiltinVelocityActuatorCfg[source]#

Bases: ActuatorCfg

Configuration for MuJoCo built-in velocity actuator.

Under the hood, this creates a <velocity> actuator for each target and sets the damping gain. It also modifies the target’s properties, namely armature and frictionloss.

__init__(*, target_names_expr: tuple[str, ...], transmission_type: TransmissionType = TransmissionType.JOINT, armature: float = 0.0, frictionloss: float = 0.0, damping: float, effort_limit: float | None = None) None#
build(entity: Entity, target_ids: list[int], target_names: list[str]) BuiltinVelocityActuator[source]#

Build actuator instance.

Parameters:
  • entity – Entity this actuator belongs to.

  • target_ids – Local target indices (for indexing entity arrays).

  • target_names – Target names corresponding to target_ids.

Returns:

Actuator instance.

effort_limit: float | None = None#

Maximum actuator force/torque. If None, no limit is applied.

damping: float#

Damping gain.

class mjlab.actuator.BuiltinActuatorGroup[source]#

Bases: object

Groups builtin actuators for batch processing.

Builtin actuators (position, velocity, motor) just pass through target values from entity data to control signals. This class pre-computes the mappings and enables direct writes without per-actuator overhead.

__init__(_index_groups: dict[tuple[type[BuiltinMotorActuator | BuiltinMuscleActuator | BuiltinPositionActuator | BuiltinVelocityActuator], TransmissionType], tuple[Tensor, Tensor]]) None#
apply_controls(data: EntityData) None[source]#

Write builtin actuator controls directly to simulation data.

Parameters:

data – Entity data containing targets and control arrays.

static process(actuators: list[Actuator]) tuple[BuiltinActuatorGroup, tuple[Actuator, ...]][source]#

Register builtin actuators and pre-compute their mappings.

Parameters:

actuators – List of initialized actuators to process.

Returns:

  • BuiltinActuatorGroup with pre-computed mappings.

  • List of custom (non-builtin) actuators.

Return type:

A tuple containing

class mjlab.actuator.DcMotorActuator[source]#

Bases: IdealPdActuator[DcMotorCfgT], Generic[DcMotorCfgT]

DC motor actuator with velocity-based saturation model.

This actuator extends IdealPdActuator with a realistic DC motor model that limits torque based on current joint velocity. The model implements a linear torque-speed curve where: - At zero velocity: can produce full saturation_effort (stall torque) - At max velocity: can produce zero torque - Between: torque limit varies linearly

The continuous torque limit (effort_limit) further constrains the output.

__init__(cfg: DcMotorCfgT, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
compute(cmd: ActuatorCmd) Tensor[source]#

Compute low-level actuator control signal from high-level commands.

Parameters:

cmd – High-level actuator command.

Returns:

Control signal tensor of shape (num_envs, num_actuators).

initialize(mj_model: MjModel, model: mujoco_warp.Model, data: mujoco_warp.Data, device: str) None[source]#

Initialize the actuator after model compilation.

This is called after the MjSpec is compiled into an MjModel.

Parameters:
  • mj_model – The compiled MuJoCo model.

  • model – The compiled mjwarp model.

  • data – The mjwarp data arrays.

  • device – Device for tensor operations (e.g., “cuda”, “cpu”).

class mjlab.actuator.DcMotorActuatorCfg[source]#

Bases: IdealPdActuatorCfg

Configuration for DC motor actuator with velocity-based saturation.

This actuator implements a DC motor torque-speed curve for more realistic actuator behavior. The motor produces maximum torque (saturation_effort) at zero velocity and reduces linearly to zero torque at maximum velocity.

Note: effort_limit should be explicitly set to a realistic value for proper motor modeling. Using the default (inf) will trigger a warning. Use IdealPdActuator if unlimited torque is desired.

__init__(*, target_names_expr: tuple[str, ...], transmission_type: TransmissionType = TransmissionType.JOINT, armature: float = 0.0, frictionloss: float = 0.0, stiffness: float, damping: float, effort_limit: float = inf, saturation_effort: float, velocity_limit: float) None#
build(entity: Entity, target_ids: list[int], target_names: list[str]) DcMotorActuator[source]#

Build actuator instance.

Parameters:
  • entity – Entity this actuator belongs to.

  • target_ids – Local target indices (for indexing entity arrays).

  • target_names – Target names corresponding to target_ids.

Returns:

Actuator instance.

saturation_effort: float#

Peak motor torque at zero velocity (stall torque).

velocity_limit: float#

Maximum motor velocity (no-load speed).

class mjlab.actuator.DelayedActuator[source]#

Bases: Actuator[DelayedActuatorCfg]

Generic wrapper that adds delay to any actuator.

Delays the specified command target(s) (position, velocity, and/or effort) before passing it to the underlying actuator’s compute method.

__init__(cfg: DelayedActuatorCfg, base_actuator: Actuator) None[source]#
property base_actuator: Actuator#

The underlying actuator being wrapped.

compute(cmd: ActuatorCmd) Tensor[source]#

Compute low-level actuator control signal from high-level commands.

Parameters:

cmd – High-level actuator command.

Returns:

Control signal tensor of shape (num_envs, num_actuators).

edit_spec(spec: MjSpec, target_names: list[str]) None[source]#

Edit the MjSpec to add actuators.

This is called during entity construction, before the model is compiled.

Parameters:
  • spec – The entity’s MjSpec to edit.

  • target_names – Names of targets (joints, tendons, or sites) controlled by this actuator.

initialize(mj_model: MjModel, model: mujoco_warp.Model, data: mujoco_warp.Data, device: str) None[source]#

Initialize the actuator after model compilation.

This is called after the MjSpec is compiled into an MjModel.

Parameters:
  • mj_model – The compiled MuJoCo model.

  • model – The compiled mjwarp model.

  • data – The mjwarp data arrays.

  • device – Device for tensor operations (e.g., “cuda”, “cpu”).

reset(env_ids: Tensor | slice | None = None) None[source]#

Reset actuator state for specified environments.

Base implementation does nothing. Override in subclasses that maintain internal state.

Parameters:

env_ids – Environment indices to reset. If None, reset all environments.

set_lags(lags: Tensor, env_ids: Tensor | slice | None = None) None[source]#

Set delay lag values for specified environments.

Parameters:
  • lags – Lag values in physics timesteps. Shape: (num_env_ids,) or scalar.

  • env_ids – Environment indices to set. If None, sets all environments.

update(dt: float) None[source]#

Update actuator state after a simulation step.

Base implementation does nothing. Override in subclasses that need per-step updates.

Parameters:

dt – Time step in seconds.

class mjlab.actuator.DelayedActuatorCfg[source]#

Bases: ActuatorCfg

Configuration for delayed actuator wrapper.

Wraps any actuator config to add delay functionality. Delays are quantized to physics timesteps (not control timesteps). For example, with 500Hz physics and 50Hz control (decimation=10), a lag of 2 represents a 4ms delay (2 physics steps).

__init__(*, transmission_type: TransmissionType = TransmissionType.JOINT, armature: float = 0.0, frictionloss: float = 0.0, base_cfg: ActuatorCfg, delay_target: Literal['position', 'velocity', 'effort'] | tuple[Literal['position', 'velocity', 'effort'], ...] = 'position', delay_min_lag: int = 0, delay_max_lag: int = 0, delay_hold_prob: float = 0.0, delay_update_period: int = 0, delay_per_env_phase: bool = True) None#
build(entity: Entity, target_ids: list[int], target_names: list[str]) DelayedActuator[source]#

Build actuator instance.

Parameters:
  • entity – Entity this actuator belongs to.

  • target_ids – Local target indices (for indexing entity arrays).

  • target_names – Target names corresponding to target_ids.

Returns:

Actuator instance.

delay_hold_prob: float = 0.0#

Probability of keeping previous lag when updating.

delay_max_lag: int = 0#

Maximum delay lag in physics timesteps.

delay_min_lag: int = 0#

Minimum delay lag in physics timesteps.

delay_per_env_phase: bool = True#

Whether each environment has a different phase offset.

delay_target: Literal['position', 'velocity', 'effort'] | tuple[Literal['position', 'velocity', 'effort'], ...] = 'position'#

Which command target(s) to delay.

Can be a single string like ‘position’, or a tuple of strings like (‘position’, ‘velocity’, ‘effort’) to delay multiple targets together.

delay_update_period: int = 0#

Period for updating delays in physics timesteps (0 = every step).

target_names_expr: tuple[str, ...] = ()#

Targets that are part of this actuator group.

Can be a tuple of names or tuple of regex expressions. Interpreted based on transmission_type (joint/tendon/site).

base_cfg: ActuatorCfg#

Configuration for the underlying actuator.

class mjlab.actuator.LearnedMlpActuator[source]#

Bases: DcMotorActuator[LearnedMlpActuatorCfg]

MLP-based learned actuator with joint history.

This actuator uses a trained neural network to map from joint commands and state history to torque outputs. The network captures complex actuator dynamics that are difficult to model analytically.

The actuator maintains circular buffers of joint position errors and velocities, which are used as inputs to the MLP. The network outputs are then scaled and clipped using the DC motor limits from the parent class.

__init__(cfg: LearnedMlpActuatorCfg, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
compute(cmd: ActuatorCmd) Tensor[source]#

Compute actuator torques using the learned MLP model.

Parameters:

cmd – High-level actuator command containing targets and current state.

Returns:

Computed torque tensor of shape (num_envs, num_joints).

initialize(mj_model: MjModel, model: mujoco_warp.Model, data: mujoco_warp.Data, device: str) None[source]#

Initialize the actuator after model compilation.

This is called after the MjSpec is compiled into an MjModel.

Parameters:
  • mj_model – The compiled MuJoCo model.

  • model – The compiled mjwarp model.

  • data – The mjwarp data arrays.

  • device – Device for tensor operations (e.g., “cuda”, “cpu”).

reset(env_ids: Tensor | slice | None = None) None[source]#

Reset history buffers for specified environments.

Parameters:

env_ids – Environment indices to reset. If None, reset all environments.

class mjlab.actuator.LearnedMlpActuatorCfg[source]#

Bases: DcMotorActuatorCfg

Configuration for MLP-based learned actuator model.

This actuator learns the mapping from joint commands and state history to actual torque output. It’s useful for capturing actuator dynamics that are difficult to model analytically, such as delays, non-linearities, and friction effects.

The network is trained offline using data from the real system and loaded as a TorchScript file. The model uses a sliding window of historical joint position errors and velocities as inputs.

__init__(*, target_names_expr: tuple[str, ...], transmission_type: TransmissionType = TransmissionType.JOINT, armature: float = 0.0, frictionloss: float = 0.0, stiffness: float = 0.0, damping: float = 0.0, effort_limit: float = inf, saturation_effort: float, velocity_limit: float, network_file: str, pos_scale: float, vel_scale: float, torque_scale: float, input_order: Literal['pos_vel', 'vel_pos'] = 'pos_vel', history_length: int = 3) None#
build(entity: Entity, target_ids: list[int], target_names: list[str]) LearnedMlpActuator[source]#

Build actuator instance.

Parameters:
  • entity – Entity this actuator belongs to.

  • target_ids – Local target indices (for indexing entity arrays).

  • target_names – Target names corresponding to target_ids.

Returns:

Actuator instance.

damping: float = 0.0#

PD damping (derivative gain).

history_length: int = 3#

Number of timesteps of history to use as network inputs.

For example, history_length=3 uses the current timestep plus the previous 2 timesteps (total of 3 frames).

input_order: Literal['pos_vel', 'vel_pos'] = 'pos_vel'#

Order of inputs to the network.

  • “pos_vel”: position errors followed by velocities

  • “vel_pos”: velocities followed by position errors

stiffness: float = 0.0#

PD stiffness (proportional gain).

network_file: str#

Path to the TorchScript file containing the trained MLP model.

pos_scale: float#

Scaling factor for joint position error inputs to the network.

vel_scale: float#

Scaling factor for joint velocity inputs to the network.

torque_scale: float#

Scaling factor for torque outputs from the network.

class mjlab.actuator.IdealPdActuator[source]#

Bases: Actuator, Generic[IdealPdCfgT]

Ideal PD control actuator.

__init__(cfg: IdealPdCfgT, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
compute(cmd: ActuatorCmd) Tensor[source]#

Compute low-level actuator control signal from high-level commands.

Parameters:

cmd – High-level actuator command.

Returns:

Control signal tensor of shape (num_envs, num_actuators).

edit_spec(spec: MjSpec, target_names: list[str]) None[source]#

Edit the MjSpec to add actuators.

This is called during entity construction, before the model is compiled.

Parameters:
  • spec – The entity’s MjSpec to edit.

  • target_names – Names of targets (joints, tendons, or sites) controlled by this actuator.

initialize(mj_model: MjModel, model: mujoco_warp.Model, data: mujoco_warp.Data, device: str) None[source]#

Initialize the actuator after model compilation.

This is called after the MjSpec is compiled into an MjModel.

Parameters:
  • mj_model – The compiled MuJoCo model.

  • model – The compiled mjwarp model.

  • data – The mjwarp data arrays.

  • device – Device for tensor operations (e.g., “cuda”, “cpu”).

set_effort_limit(env_ids: Tensor | slice, effort_limit: Tensor) None[source]#

Set effort limits for specified environments.

Parameters:
  • env_ids – Environment indices to update.

  • effort_limit – New effort limits. Shape: (num_envs, num_actuators) or (num_envs,).

set_gains(env_ids: Tensor | slice, kp: Tensor | None = None, kd: Tensor | None = None) None[source]#

Set PD gains for specified environments.

Parameters:
  • env_ids – Environment indices to update.

  • kp – New proportional gains. Shape: (num_envs, num_actuators) or (num_envs,).

  • kd – New derivative gains. Shape: (num_envs, num_actuators) or (num_envs,).

class mjlab.actuator.IdealPdActuatorCfg[source]#

Bases: ActuatorCfg

Configuration for ideal PD actuator.

__init__(*, target_names_expr: tuple[str, ...], transmission_type: TransmissionType = TransmissionType.JOINT, armature: float = 0.0, frictionloss: float = 0.0, stiffness: float, damping: float, effort_limit: float = inf) None#
build(entity: Entity, target_ids: list[int], target_names: list[str]) IdealPdActuator[source]#

Build actuator instance.

Parameters:
  • entity – Entity this actuator belongs to.

  • target_ids – Local target indices (for indexing entity arrays).

  • target_names – Target names corresponding to target_ids.

Returns:

Actuator instance.

effort_limit: float = inf#

Maximum force/torque limit.

stiffness: float#

PD stiffness (proportional gain).

damping: float#

PD damping (derivative gain).

class mjlab.actuator.XmlMotorActuator[source]#

Bases: XmlActuator[XmlMotorActuatorCfg]

Wrapper for XML-defined <motor> actuators.

compute(cmd: ActuatorCmd) Tensor[source]#

Compute low-level actuator control signal from high-level commands.

Parameters:

cmd – High-level actuator command.

Returns:

Control signal tensor of shape (num_envs, num_actuators).

class mjlab.actuator.XmlMotorActuatorCfg[source]#

Bases: ActuatorCfg

Wrap existing XML-defined <motor> actuators.

__init__(*, target_names_expr: tuple[str, ...], transmission_type: TransmissionType = TransmissionType.JOINT, armature: float = 0.0, frictionloss: float = 0.0) None#
build(entity: Entity, target_ids: list[int], target_names: list[str]) XmlMotorActuator[source]#

Build actuator instance.

Parameters:
  • entity – Entity this actuator belongs to.

  • target_ids – Local target indices (for indexing entity arrays).

  • target_names – Target names corresponding to target_ids.

Returns:

Actuator instance.

class mjlab.actuator.XmlMuscleActuator[source]#

Bases: XmlActuator[XmlMuscleActuatorCfg]

Wrapper for XML-defined <muscle> actuators.

compute(cmd: ActuatorCmd) Tensor[source]#

Compute low-level actuator control signal from high-level commands.

Parameters:

cmd – High-level actuator command.

Returns:

Control signal tensor of shape (num_envs, num_actuators).

class mjlab.actuator.XmlMuscleActuatorCfg[source]#

Bases: ActuatorCfg

Wrap existing XML-defined <muscle> actuators.

__init__(*, target_names_expr: tuple[str, ...], transmission_type: TransmissionType = TransmissionType.JOINT, armature: float = 0.0, frictionloss: float = 0.0) None#
build(entity: Entity, target_ids: list[int], target_names: list[str]) XmlMuscleActuator[source]#

Build actuator instance.

Parameters:
  • entity – Entity this actuator belongs to.

  • target_ids – Local target indices (for indexing entity arrays).

  • target_names – Target names corresponding to target_ids.

Returns:

Actuator instance.

class mjlab.actuator.XmlPositionActuator[source]#

Bases: XmlActuator[XmlPositionActuatorCfg]

Wrapper for XML-defined <position> actuators.

compute(cmd: ActuatorCmd) Tensor[source]#

Compute low-level actuator control signal from high-level commands.

Parameters:

cmd – High-level actuator command.

Returns:

Control signal tensor of shape (num_envs, num_actuators).

class mjlab.actuator.XmlPositionActuatorCfg[source]#

Bases: ActuatorCfg

Wrap existing XML-defined <position> actuators.

__init__(*, target_names_expr: tuple[str, ...], transmission_type: TransmissionType = TransmissionType.JOINT, armature: float = 0.0, frictionloss: float = 0.0) None#
build(entity: Entity, target_ids: list[int], target_names: list[str]) XmlPositionActuator[source]#

Build actuator instance.

Parameters:
  • entity – Entity this actuator belongs to.

  • target_ids – Local target indices (for indexing entity arrays).

  • target_names – Target names corresponding to target_ids.

Returns:

Actuator instance.

class mjlab.actuator.XmlVelocityActuator[source]#

Bases: XmlActuator[XmlVelocityActuatorCfg]

Wrapper for XML-defined <velocity> actuators.

compute(cmd: ActuatorCmd) Tensor[source]#

Compute low-level actuator control signal from high-level commands.

Parameters:

cmd – High-level actuator command.

Returns:

Control signal tensor of shape (num_envs, num_actuators).

class mjlab.actuator.XmlVelocityActuatorCfg[source]#

Bases: ActuatorCfg

Wrap existing XML-defined <velocity> actuators.

__init__(*, target_names_expr: tuple[str, ...], transmission_type: TransmissionType = TransmissionType.JOINT, armature: float = 0.0, frictionloss: float = 0.0) None#
build(entity: Entity, target_ids: list[int], target_names: list[str]) XmlVelocityActuator[source]#

Build actuator instance.

Parameters:
  • entity – Entity this actuator belongs to.

  • target_ids – Local target indices (for indexing entity arrays).

  • target_names – Target names corresponding to target_ids.

Returns:

Actuator instance.