mjlab.actuator#
Actuator implementations for motor control.
Actuator implementations for mjlab.
Classes:
Base actuator interface. |
|
ActuatorCfg(*, target_names_expr: 'tuple[str, ...]', transmission_type: 'TransmissionType' = <TransmissionType.JOINT: 'joint'>, armature: 'float' = 0.0, frictionloss: 'float' = 0.0) |
|
High-level actuator command with targets and current state. |
|
MuJoCo built-in motor actuator. |
|
Configuration for MuJoCo built-in motor actuator. |
|
MuJoCo built-in muscle actuator. |
|
Configuration for MuJoCo built-in muscle actuator. |
|
MuJoCo built-in position actuator. |
|
Configuration for MuJoCo built-in position actuator. |
|
MuJoCo built-in velocity actuator. |
|
Configuration for MuJoCo built-in velocity actuator. |
|
Groups builtin actuators for batch processing. |
|
DC motor actuator with velocity-based saturation model. |
|
Configuration for DC motor actuator with velocity-based saturation. |
|
Generic wrapper that adds delay to any actuator. |
|
Configuration for delayed actuator wrapper. |
|
MLP-based learned actuator with joint history. |
|
Configuration for MLP-based learned actuator model. |
|
Ideal PD control actuator. |
|
Configuration for ideal PD actuator. |
|
Wrapper for XML-defined <motor> actuators. |
|
Wrap existing XML-defined <motor> actuators. |
|
Wrapper for XML-defined <muscle> actuators. |
|
Wrap existing XML-defined <muscle> actuators. |
|
Wrapper for XML-defined <position> actuators. |
|
Wrap existing XML-defined <position> actuators. |
|
Wrapper for XML-defined <velocity> actuators. |
|
Wrap existing XML-defined <velocity> actuators. |
- class mjlab.actuator.Actuator[source]#
Bases:
ABC,Generic[ActuatorCfgT]Base actuator interface.
Methods:
__init__(cfg, entity, target_ids, target_names)edit_spec(spec, target_names)Edit the MjSpec to add actuators.
initialize(mj_model, model, data, device)Initialize the actuator after model compilation.
get_command(data)Extract command data for this actuator from entity data.
compute(cmd)Compute low-level actuator control signal from high-level commands.
reset([env_ids])Reset actuator state for specified environments.
update(dt)Update actuator state after a simulation step.
Attributes:
Local indices of targets controlled by this actuator.
Names of targets controlled by this actuator.
Transmission type of this actuator.
Global indices of control inputs for this actuator.
- __init__(cfg: ActuatorCfgT, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
- property target_ids: Tensor#
Local indices of targets controlled by this actuator.
- property transmission_type: TransmissionType#
Transmission type of this actuator.
- property ctrl_ids: Tensor#
Global indices of control inputs for this actuator.
- 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.
- 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”).
- 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.
- 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).
- class mjlab.actuator.ActuatorCfg[source]#
Bases:
ABCActuatorCfg(*, target_names_expr: ‘tuple[str, …]’, transmission_type: ‘TransmissionType’ = <TransmissionType.JOINT: ‘joint’>, armature: ‘float’ = 0.0, frictionloss: ‘float’ = 0.0)
Attributes:
Targets that are part of this actuator group.
Transmission type.
Reflected rotor inertia.
Friction loss force limit.
Methods:
build(entity, target_ids, target_names)Build actuator instance.
__init__(*, target_names_expr[, ...])- 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).
- transmission_type: TransmissionType = 'joint'#
Transmission type. Defaults to JOINT.
- 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.
- 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.
- class mjlab.actuator.ActuatorCmd[source]#
Bases:
objectHigh-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).
Attributes:
Desired positions (joint positions, tendon lengths, or site positions).
Desired velocities (joint velocities, tendon velocities, or site velocities).
Feedforward effort (torques or forces).
Current positions (joint positions, tendon lengths, or site positions).
Current velocities (joint velocities, tendon velocities, or site velocities).
Methods:
__init__(position_target, velocity_target, ...)- 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.
Methods:
__init__(cfg, entity, target_ids, target_names)edit_spec(spec, target_names)Edit the MjSpec to add actuators.
compute(cmd)Compute low-level actuator control signal from high-level commands.
- __init__(cfg: BuiltinMotorActuatorCfg, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
- 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.
- 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.BuiltinMotorActuatorCfg[source]#
Bases:
ActuatorCfgConfiguration 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.
Attributes:
Maximum actuator effort.
Actuator gear ratio.
Methods:
build(entity, target_ids, target_names)Build actuator instance.
__init__(*, target_names_expr[, ...])- 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.
- class mjlab.actuator.BuiltinMuscleActuator[source]#
Bases:
Actuator[BuiltinMuscleActuatorCfg]MuJoCo built-in muscle actuator.
Methods:
__init__(cfg, entity, target_ids, target_names)edit_spec(spec, target_names)Edit the MjSpec to add actuators.
compute(cmd)Compute low-level actuator control signal from high-level commands.
- __init__(cfg: BuiltinMuscleActuatorCfg, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
- 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.
- 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.BuiltinMuscleActuatorCfg[source]#
Bases:
ActuatorCfgConfiguration for MuJoCo built-in muscle actuator.
Attributes:
Length range for muscle actuator.
Gear ratio.
Activation and deactivation time constants.
Smoothing time constant.
Operating range of normalized muscle length.
Peak force (if -1, defaults to scale * FLV).
Force scaling factor.
Minimum normalized muscle length.
Maximum normalized muscle length.
Maximum normalized muscle velocity.
Passive force at lmax.
Active force at -vmax.
Methods:
__init__(*, target_names_expr[, ...])build(entity, target_ids, target_names)Build actuator instance.
- __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#
- 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).
- 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.
- class mjlab.actuator.BuiltinPositionActuator[source]#
Bases:
Actuator[BuiltinPositionActuatorCfg]MuJoCo built-in position actuator.
Methods:
__init__(cfg, entity, target_ids, target_names)edit_spec(spec, target_names)Edit the MjSpec to add actuators.
compute(cmd)Compute low-level actuator control signal from high-level commands.
- __init__(cfg: BuiltinPositionActuatorCfg, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
- 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.
- 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.BuiltinPositionActuatorCfg[source]#
Bases:
ActuatorCfgConfiguration 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.
Attributes:
PD proportional gain.
PD derivative gain.
Maximum actuator force/torque.
Methods:
build(entity, target_ids, target_names)Build actuator instance.
__init__(*, target_names_expr[, ...])- 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.
- class mjlab.actuator.BuiltinVelocityActuator[source]#
Bases:
Actuator[BuiltinVelocityActuatorCfg]MuJoCo built-in velocity actuator.
Methods:
__init__(cfg, entity, target_ids, target_names)edit_spec(spec, target_names)Edit the MjSpec to add actuators.
compute(cmd)Compute low-level actuator control signal from high-level commands.
- __init__(cfg: BuiltinVelocityActuatorCfg, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
- 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.
- 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.BuiltinVelocityActuatorCfg[source]#
Bases:
ActuatorCfgConfiguration 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.
Attributes:
Damping gain.
Maximum actuator force/torque.
Methods:
build(entity, target_ids, target_names)Build actuator instance.
__init__(*, target_names_expr[, ...])- 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.
- class mjlab.actuator.BuiltinActuatorGroup[source]#
Bases:
objectGroups 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.
Methods:
process(actuators)Register builtin actuators and pre-compute their mappings.
apply_controls(data)Write builtin actuator controls directly to simulation data.
__init__(_index_groups)- 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
- apply_controls(data: EntityData) None[source]#
Write builtin actuator controls directly to simulation data.
- Parameters:
data – Entity data containing targets and control arrays.
- 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.
Methods:
__init__(cfg, entity, target_ids, target_names)initialize(mj_model, model, data, device)Initialize the actuator after model compilation.
compute(cmd)Compute low-level actuator control signal from high-level commands.
- __init__(cfg: DcMotorCfgT, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
- 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”).
- 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.DcMotorActuatorCfg[source]#
Bases:
IdealPdActuatorCfgConfiguration 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.
Attributes:
Peak motor torque at zero velocity (stall torque).
Maximum motor velocity (no-load speed).
Methods:
build(entity, target_ids, target_names)Build actuator instance.
__init__(*, target_names_expr[, ...])- 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.
- 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.
Methods:
__init__(cfg, base_actuator)edit_spec(spec, target_names)Edit the MjSpec to add actuators.
initialize(mj_model, model, data, device)Initialize the actuator after model compilation.
compute(cmd)Compute low-level actuator control signal from high-level commands.
reset([env_ids])Reset actuator state for specified environments.
set_lags(lags[, env_ids])Set delay lag values for specified environments.
update(dt)Update actuator state after a simulation step.
Attributes:
The underlying actuator being wrapped.
- __init__(cfg: DelayedActuatorCfg, base_actuator: Actuator) None[source]#
- 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”).
- 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).
- 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.
- class mjlab.actuator.DelayedActuatorCfg[source]#
Bases:
ActuatorCfgConfiguration 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).
Attributes:
Targets that are part of this actuator group.
Configuration for the underlying actuator.
Which command target(s) to delay.
Minimum delay lag in physics timesteps.
Maximum delay lag in physics timesteps.
Probability of keeping previous lag when updating.
Period for updating delays in physics timesteps (0 = every step).
Whether each environment has a different phase offset.
Methods:
build(entity, target_ids, target_names)Build actuator instance.
__init__(*[, transmission_type, armature, ...])- 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.
- 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.
- 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.
- __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#
- 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.
Methods:
__init__(cfg, entity, target_ids, target_names)initialize(mj_model, model, data, device)Initialize the actuator after model compilation.
reset([env_ids])Reset history buffers for specified environments.
compute(cmd)Compute actuator torques using the learned MLP model.
- __init__(cfg: LearnedMlpActuatorCfg, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
- 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.
- 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).
- class mjlab.actuator.LearnedMlpActuatorCfg[source]#
Bases:
DcMotorActuatorCfgConfiguration 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.
Attributes:
Path to the TorchScript file containing the trained MLP model.
Scaling factor for joint position error inputs to the network.
Scaling factor for joint velocity inputs to the network.
Scaling factor for torque outputs from the network.
Order of inputs to the network.
Number of timesteps of history to use as network inputs.
PD stiffness (proportional gain).
PD damping (derivative gain).
Methods:
build(entity, target_ids, target_names)Build actuator instance.
__init__(*, target_names_expr[, ...])- 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
- 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).
- 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.
- __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#
- class mjlab.actuator.IdealPdActuator[source]#
Bases:
Actuator,Generic[IdealPdCfgT]Ideal PD control actuator.
Methods:
__init__(cfg, entity, target_ids, target_names)edit_spec(spec, target_names)Edit the MjSpec to add actuators.
initialize(mj_model, model, data, device)Initialize the actuator after model compilation.
compute(cmd)Compute low-level actuator control signal from high-level commands.
set_gains(env_ids[, kp, kd])Set PD gains for specified environments.
set_effort_limit(env_ids, effort_limit)Set effort limits for specified environments.
- __init__(cfg: IdealPdCfgT, entity: Entity, target_ids: list[int], target_names: list[str]) None[source]#
- 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”).
- 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).
- 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:
ActuatorCfgConfiguration for ideal PD actuator.
Attributes:
PD stiffness (proportional gain).
PD damping (derivative gain).
Maximum force/torque limit.
Methods:
build(entity, target_ids, target_names)Build actuator instance.
__init__(*, target_names_expr[, ...])- 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.
- class mjlab.actuator.XmlMotorActuator[source]#
Bases:
XmlActuator[XmlMotorActuatorCfg]Wrapper for XML-defined <motor> actuators.
Methods:
compute(cmd)Compute low-level actuator control signal from high-level commands.
- 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:
ActuatorCfgWrap existing XML-defined <motor> actuators.
Methods:
build(entity, target_ids, target_names)Build actuator instance.
__init__(*, target_names_expr[, ...])- 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.
Methods:
compute(cmd)Compute low-level actuator control signal from high-level commands.
- 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:
ActuatorCfgWrap existing XML-defined <muscle> actuators.
Methods:
build(entity, target_ids, target_names)Build actuator instance.
__init__(*, target_names_expr[, ...])- 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.
Methods:
compute(cmd)Compute low-level actuator control signal from high-level commands.
- 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:
ActuatorCfgWrap existing XML-defined <position> actuators.
Methods:
build(entity, target_ids, target_names)Build actuator instance.
__init__(*, target_names_expr[, ...])- 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.
Methods:
compute(cmd)Compute low-level actuator control signal from high-level commands.
- 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:
ActuatorCfgWrap existing XML-defined <velocity> actuators.
Methods:
build(entity, target_ids, target_names)Build actuator instance.
__init__(*, target_names_expr[, ...])- 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.