omni.isaac.lab.actuators#
Sub-package for different actuator models.
Actuator models are used to model the behavior of the actuators in an articulation. These are usually meant to be used in simulation to model different actuator dynamics and delays.
There are two main categories of actuator models that are supported:
Implicit: Motor model with ideal PD from the physics engine. This is similar to having a continuous time PD controller. The motor model is implicit in the sense that the motor model is not explicitly defined by the user.
Explicit: Motor models based on physical drive models.
Physics-based: Derives the motor models based on first-principles.
Neural Network-based: Learned motor models from actuator data.
Every actuator model inherits from the omni.isaac.lab.actuators.ActuatorBase
class,
which defines the common interface for all actuator models. The actuator models are handled
and called by the omni.isaac.lab.assets.Articulation
class.
Classes
Base class for actuator models over a collection of actuated joints in an articulation. |
|
Configuration for default actuators in an articulation. |
|
Implicit actuator model that is handled by the simulation. |
|
Configuration for an implicit actuator. |
|
Ideal torque-controlled actuator model with a simple saturation model. |
|
Configuration for an ideal PD actuator. |
|
Direct control (DC) motor actuator model with velocity-based saturation model. |
|
Configuration for direct control (DC) motor actuator model. |
|
Ideal PD actuator with delayed command application. |
|
Configuration for a delayed PD actuator. |
|
Ideal PD actuator with angle-dependent torque limits. |
|
Configuration for a remotized PD actuator. |
|
Actuator model based on multi-layer perceptron and joint history. |
|
Configuration for MLP-based actuator model. |
|
Actuator model based on recurrent neural network (LSTM). |
|
Configuration for LSTM-based actuator model. |
Actuator Base#
- class omni.isaac.lab.actuators.ActuatorBase[source]#
Base class for actuator models over a collection of actuated joints in an articulation.
Actuator models augment the simulated articulation joints with an external drive dynamics model. The model is used to convert the user-provided joint commands (positions, velocities and efforts) into the desired joint positions, velocities and efforts that are applied to the simulated articulation.
The base class provides the interface for the actuator models. It is responsible for parsing the actuator parameters from the configuration and storing them as buffers. It also provides the interface for resetting the actuator state and computing the desired joint commands for the simulation.
For each actuator model, a corresponding configuration class is provided. The configuration class is used to parse the actuator parameters from the configuration. It also specifies the joint names for which the actuator model is applied. These names can be specified as regular expressions, which are matched against the joint names in the articulation.
To see how the class is used, check the
omni.isaac.lab.assets.Articulation
class.Methods:
__init__
(cfg, joint_names, joint_ids, ...[, ...])Initialize the actuator.
reset
(env_ids)Reset the internals within the group.
compute
(control_action, joint_pos, joint_vel)Process the actuator group actions and compute the articulation actions.
Attributes:
The stiffness (P gain) of the PD controller.
The damping (D gain) of the PD controller.
The armature of the actuator joints.
The joint friction of the actuator joints.
The effort limit for the actuator group.
The velocity limit for the actuator group.
The computed effort for the actuator group.
The applied effort for the actuator group.
Number of actuators in the group.
Articulation's joint names that are part of the group.
Articulation's joint indices that are part of the group.
- __init__(cfg: ActuatorBaseCfg, joint_names: list[str], joint_ids: slice | Sequence[int], num_envs: int, device: str, stiffness: torch.Tensor | float = 0.0, damping: torch.Tensor | float = 0.0, armature: torch.Tensor | float = 0.0, friction: torch.Tensor | float = 0.0, effort_limit: torch.Tensor | float = torch.inf, velocity_limit: torch.Tensor | float = torch.inf)[source]#
Initialize the actuator.
Note
The actuator parameters are parsed from the configuration and stored as buffers. If the parameters are not specified in the configuration, then the default values provided in the arguments are used.
- Parameters:
cfg – The configuration of the actuator model.
joint_names – The joint names in the articulation.
joint_ids – The joint indices in the articulation. If
slice(None)
, then all the joints in the articulation are part of the group.num_envs – Number of articulations in the view.
device – Device used for processing.
stiffness – The default joint stiffness (P gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
damping – The default joint damping (D gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
armature – The default joint armature. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
friction – The default joint friction. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
effort_limit – The default effort limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
velocity_limit – The default velocity limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
- stiffness: torch.Tensor#
The stiffness (P gain) of the PD controller. Shape is (num_envs, num_joints).
- damping: torch.Tensor#
The damping (D gain) of the PD controller. Shape is (num_envs, num_joints).
- armature: torch.Tensor#
The armature of the actuator joints. Shape is (num_envs, num_joints).
- friction: torch.Tensor#
The joint friction of the actuator joints. Shape is (num_envs, num_joints).
- effort_limit: torch.Tensor#
The effort limit for the actuator group. Shape is (num_envs, num_joints).
- velocity_limit: torch.Tensor#
The velocity limit for the actuator group. Shape is (num_envs, num_joints).
- computed_effort: torch.Tensor#
The computed effort for the actuator group. Shape is (num_envs, num_joints).
- applied_effort: torch.Tensor#
The applied effort for the actuator group. Shape is (num_envs, num_joints).
- property joint_indices: slice | Sequence[int]#
Articulation’s joint indices that are part of the group.
Note
If
slice(None)
is returned, then the group contains all the joints in the articulation. We do this to avoid unnecessary indexing of the joints for performance reasons.
- abstract reset(env_ids: Sequence[int])[source]#
Reset the internals within the group.
- Parameters:
env_ids – List of environment IDs to reset.
- abstract compute(control_action: ArticulationActions, joint_pos: torch.Tensor, joint_vel: torch.Tensor) ArticulationActions [source]#
Process the actuator group actions and compute the articulation actions.
It computes the articulation actions based on the actuator model type
- Parameters:
control_action – The joint action instance comprising of the desired joint positions, joint velocities and (feed-forward) joint efforts.
joint_pos – The current joint positions of the joints in the group. Shape is (num_envs, num_joints).
joint_vel – The current joint velocities of the joints in the group. Shape is (num_envs, num_joints).
- Returns:
The computed desired joint positions, joint velocities and joint efforts.
- class omni.isaac.lab.actuators.ActuatorBaseCfg[source]#
Configuration for default actuators in an articulation.
Attributes:
Articulation's joint names that are part of the group.
Force/Torque limit of the joints in the group.
Velocity limit of the joints in the group.
Stiffness gains (also known as p-gain) of the joints in the group.
Damping gains (also known as d-gain) of the joints in the group.
Armature of the joints in the group.
Joint friction of the joints in the group.
- joint_names_expr: list[str]#
Articulation’s joint names that are part of the group.
Note
This can be a list of joint names or a list of regex expressions (e.g. “.*”).
- effort_limit: dict[str, float] | float | None#
Force/Torque limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- velocity_limit: dict[str, float] | float | None#
Velocity limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- stiffness: dict[str, float] | float | None#
Stiffness gains (also known as p-gain) of the joints in the group.
If None, the stiffness is set to the value from the USD joint prim.
- damping: dict[str, float] | float | None#
Damping gains (also known as d-gain) of the joints in the group.
If None, the damping is set to the value from the USD joint prim.
Implicit Actuator#
- class omni.isaac.lab.actuators.ImplicitActuator[source]#
Bases:
ActuatorBase
Implicit actuator model that is handled by the simulation.
This performs a similar function as the
IdealPDActuator
class. However, the PD control is handled implicitly by the simulation which performs continuous-time integration of the PD control law. This is generally more accurate than the explicit PD control law used inIdealPDActuator
when the simulation time-step is large.Note
The articulation class sets the stiffness and damping parameters from the configuration into the simulation. Thus, the parameters are not used in this class.
Caution
The class is only provided for consistency with the other actuator models. It does not implement any functionality and should not be used. All values should be set to the simulation directly.
Attributes:
The configuration for the actuator model.
Articulation's joint indices that are part of the group.
Articulation's joint names that are part of the group.
Number of actuators in the group.
The computed effort for the actuator group.
The applied effort for the actuator group.
The effort limit for the actuator group.
The velocity limit for the actuator group.
The stiffness (P gain) of the PD controller.
The damping (D gain) of the PD controller.
The armature of the actuator joints.
The joint friction of the actuator joints.
Methods:
reset
(*args, **kwargs)Reset the internals within the group.
compute
(control_action, joint_pos, joint_vel)Process the actuator group actions and compute the articulation actions.
__init__
(cfg, joint_names, joint_ids, ...[, ...])Initialize the actuator.
- cfg: ImplicitActuatorCfg#
The configuration for the actuator model.
- reset(*args, **kwargs)[source]#
Reset the internals within the group.
- Parameters:
env_ids – List of environment IDs to reset.
- compute(control_action: ArticulationActions, joint_pos: torch.Tensor, joint_vel: torch.Tensor) ArticulationActions [source]#
Process the actuator group actions and compute the articulation actions.
In case of implicit actuator, the control action is directly returned as the computed action. This function is a no-op and does not perform any computation on the input control action. However, it computes the approximate torques for the actuated joint since PhysX does not compute this quantity explicitly.
- Parameters:
control_action – The joint action instance comprising of the desired joint positions, joint velocities and (feed-forward) joint efforts.
joint_pos – The current joint positions of the joints in the group. Shape is (num_envs, num_joints).
joint_vel – The current joint velocities of the joints in the group. Shape is (num_envs, num_joints).
- Returns:
The computed desired joint positions, joint velocities and joint efforts.
- __init__(cfg: ActuatorBaseCfg, joint_names: list[str], joint_ids: slice | Sequence[int], num_envs: int, device: str, stiffness: torch.Tensor | float = 0.0, damping: torch.Tensor | float = 0.0, armature: torch.Tensor | float = 0.0, friction: torch.Tensor | float = 0.0, effort_limit: torch.Tensor | float = torch.inf, velocity_limit: torch.Tensor | float = torch.inf)#
Initialize the actuator.
Note
The actuator parameters are parsed from the configuration and stored as buffers. If the parameters are not specified in the configuration, then the default values provided in the arguments are used.
- Parameters:
cfg – The configuration of the actuator model.
joint_names – The joint names in the articulation.
joint_ids – The joint indices in the articulation. If
slice(None)
, then all the joints in the articulation are part of the group.num_envs – Number of articulations in the view.
device – Device used for processing.
stiffness – The default joint stiffness (P gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
damping – The default joint damping (D gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
armature – The default joint armature. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
friction – The default joint friction. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
effort_limit – The default effort limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
velocity_limit – The default velocity limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
- property joint_indices: slice | Sequence[int]#
Articulation’s joint indices that are part of the group.
Note
If
slice(None)
is returned, then the group contains all the joints in the articulation. We do this to avoid unnecessary indexing of the joints for performance reasons.
- computed_effort: torch.Tensor#
The computed effort for the actuator group. Shape is (num_envs, num_joints).
- applied_effort: torch.Tensor#
The applied effort for the actuator group. Shape is (num_envs, num_joints).
- effort_limit: torch.Tensor#
The effort limit for the actuator group. Shape is (num_envs, num_joints).
- velocity_limit: torch.Tensor#
The velocity limit for the actuator group. Shape is (num_envs, num_joints).
- stiffness: torch.Tensor#
The stiffness (P gain) of the PD controller. Shape is (num_envs, num_joints).
- damping: torch.Tensor#
The damping (D gain) of the PD controller. Shape is (num_envs, num_joints).
- armature: torch.Tensor#
The armature of the actuator joints. Shape is (num_envs, num_joints).
- friction: torch.Tensor#
The joint friction of the actuator joints. Shape is (num_envs, num_joints).
- class omni.isaac.lab.actuators.ImplicitActuatorCfg[source]#
Bases:
ActuatorBaseCfg
Configuration for an implicit actuator.
Note
The PD control is handled implicitly by the simulation.
Attributes:
Articulation's joint names that are part of the group.
Force/Torque limit of the joints in the group.
Velocity limit of the joints in the group.
Stiffness gains (also known as p-gain) of the joints in the group.
Damping gains (also known as d-gain) of the joints in the group.
Armature of the joints in the group.
Joint friction of the joints in the group.
- joint_names_expr: list[str]#
Articulation’s joint names that are part of the group.
Note
This can be a list of joint names or a list of regex expressions (e.g. “.*”).
- effort_limit: dict[str, float] | float | None#
Force/Torque limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- velocity_limit: dict[str, float] | float | None#
Velocity limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- stiffness: dict[str, float] | float | None#
Stiffness gains (also known as p-gain) of the joints in the group.
If None, the stiffness is set to the value from the USD joint prim.
- damping: dict[str, float] | float | None#
Damping gains (also known as d-gain) of the joints in the group.
If None, the damping is set to the value from the USD joint prim.
Ideal PD Actuator#
- class omni.isaac.lab.actuators.IdealPDActuator[source]#
Bases:
ActuatorBase
Ideal torque-controlled actuator model with a simple saturation model.
It employs the following model for computing torques for the actuated joint \(j\):
\[\tau_{j, computed} = k_p * (q - q_{des}) + k_d * (\dot{q} - \dot{q}_{des}) + \tau_{ff}\]where, \(k_p\) and \(k_d\) are joint stiffness and damping gains, \(q\) and \(\dot{q}\) are the current joint positions and velocities, \(q_{des}\), \(\dot{q}_{des}\) and \(\tau_{ff}\) are the desired joint positions, velocities and torques commands.
The clipping model is based on the maximum torque applied by the motor. It is implemented as:
\[\begin{split}\tau_{j, max} & = \gamma \times \tau_{motor, max} \\ \tau_{j, applied} & = clip(\tau_{computed}, -\tau_{j, max}, \tau_{j, max})\end{split}\]where the clipping function is defined as \(clip(x, x_{min}, x_{max}) = min(max(x, x_{min}), x_{max})\). The parameters \(\gamma\) is the gear ratio of the gear box connecting the motor and the actuated joint ends, and \(\tau_{motor, max}\) is the maximum motor effort possible. These parameters are read from the configuration instance passed to the class.
Attributes:
The configuration for the actuator model.
Articulation's joint indices that are part of the group.
Articulation's joint names that are part of the group.
Number of actuators in the group.
The computed effort for the actuator group.
The applied effort for the actuator group.
The effort limit for the actuator group.
The velocity limit for the actuator group.
The stiffness (P gain) of the PD controller.
The damping (D gain) of the PD controller.
The armature of the actuator joints.
The joint friction of the actuator joints.
Methods:
reset
(env_ids)Reset the internals within the group.
compute
(control_action, joint_pos, joint_vel)Process the actuator group actions and compute the articulation actions.
__init__
(cfg, joint_names, joint_ids, ...[, ...])Initialize the actuator.
- cfg: IdealPDActuatorCfg#
The configuration for the actuator model.
- reset(env_ids: Sequence[int])[source]#
Reset the internals within the group.
- Parameters:
env_ids – List of environment IDs to reset.
- compute(control_action: ArticulationActions, joint_pos: torch.Tensor, joint_vel: torch.Tensor) ArticulationActions [source]#
Process the actuator group actions and compute the articulation actions.
It computes the articulation actions based on the actuator model type
- Parameters:
control_action – The joint action instance comprising of the desired joint positions, joint velocities and (feed-forward) joint efforts.
joint_pos – The current joint positions of the joints in the group. Shape is (num_envs, num_joints).
joint_vel – The current joint velocities of the joints in the group. Shape is (num_envs, num_joints).
- Returns:
The computed desired joint positions, joint velocities and joint efforts.
- __init__(cfg: ActuatorBaseCfg, joint_names: list[str], joint_ids: slice | Sequence[int], num_envs: int, device: str, stiffness: torch.Tensor | float = 0.0, damping: torch.Tensor | float = 0.0, armature: torch.Tensor | float = 0.0, friction: torch.Tensor | float = 0.0, effort_limit: torch.Tensor | float = torch.inf, velocity_limit: torch.Tensor | float = torch.inf)#
Initialize the actuator.
Note
The actuator parameters are parsed from the configuration and stored as buffers. If the parameters are not specified in the configuration, then the default values provided in the arguments are used.
- Parameters:
cfg – The configuration of the actuator model.
joint_names – The joint names in the articulation.
joint_ids – The joint indices in the articulation. If
slice(None)
, then all the joints in the articulation are part of the group.num_envs – Number of articulations in the view.
device – Device used for processing.
stiffness – The default joint stiffness (P gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
damping – The default joint damping (D gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
armature – The default joint armature. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
friction – The default joint friction. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
effort_limit – The default effort limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
velocity_limit – The default velocity limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
- property joint_indices: slice | Sequence[int]#
Articulation’s joint indices that are part of the group.
Note
If
slice(None)
is returned, then the group contains all the joints in the articulation. We do this to avoid unnecessary indexing of the joints for performance reasons.
- computed_effort: torch.Tensor#
The computed effort for the actuator group. Shape is (num_envs, num_joints).
- applied_effort: torch.Tensor#
The applied effort for the actuator group. Shape is (num_envs, num_joints).
- effort_limit: torch.Tensor#
The effort limit for the actuator group. Shape is (num_envs, num_joints).
- velocity_limit: torch.Tensor#
The velocity limit for the actuator group. Shape is (num_envs, num_joints).
- stiffness: torch.Tensor#
The stiffness (P gain) of the PD controller. Shape is (num_envs, num_joints).
- damping: torch.Tensor#
The damping (D gain) of the PD controller. Shape is (num_envs, num_joints).
- armature: torch.Tensor#
The armature of the actuator joints. Shape is (num_envs, num_joints).
- friction: torch.Tensor#
The joint friction of the actuator joints. Shape is (num_envs, num_joints).
- class omni.isaac.lab.actuators.IdealPDActuatorCfg[source]#
Bases:
ActuatorBaseCfg
Configuration for an ideal PD actuator.
Attributes:
Articulation's joint names that are part of the group.
Force/Torque limit of the joints in the group.
Velocity limit of the joints in the group.
Stiffness gains (also known as p-gain) of the joints in the group.
Damping gains (also known as d-gain) of the joints in the group.
Armature of the joints in the group.
Joint friction of the joints in the group.
- joint_names_expr: list[str]#
Articulation’s joint names that are part of the group.
Note
This can be a list of joint names or a list of regex expressions (e.g. “.*”).
- effort_limit: dict[str, float] | float | None#
Force/Torque limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- velocity_limit: dict[str, float] | float | None#
Velocity limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- stiffness: dict[str, float] | float | None#
Stiffness gains (also known as p-gain) of the joints in the group.
If None, the stiffness is set to the value from the USD joint prim.
- damping: dict[str, float] | float | None#
Damping gains (also known as d-gain) of the joints in the group.
If None, the damping is set to the value from the USD joint prim.
DC Motor Actuator#
- class omni.isaac.lab.actuators.DCMotor[source]#
Bases:
IdealPDActuator
Direct control (DC) motor actuator model with velocity-based saturation model.
It uses the same model as the
IdealActuator
for computing the torques from input commands. However, it implements a saturation model defined by DC motor characteristics.A DC motor is a type of electric motor that is powered by direct current electricity. In most cases, the motor is connected to a constant source of voltage supply, and the current is controlled by a rheostat. Depending on various design factors such as windings and materials, the motor can draw a limited maximum power from the electronic source, which limits the produced motor torque and speed.
A DC motor characteristics are defined by the following parameters:
Continuous-rated speed (\(\dot{q}_{motor, max}\)) : The maximum-rated speed of the motor.
Continuous-stall torque (\(\tau_{motor, max}\)): The maximum-rated torque produced at 0 speed.
Saturation torque (\(\tau_{motor, sat}\)): The maximum torque that can be outputted for a short period.
Based on these parameters, the instantaneous minimum and maximum torques are defined as follows:
\[\begin{split}\tau_{j, max}(\dot{q}) & = clip \left (\tau_{j, sat} \times \left(1 - \frac{\dot{q}}{\dot{q}_{j, max}}\right), 0.0, \tau_{j, max} \right) \\ \tau_{j, min}(\dot{q}) & = clip \left (\tau_{j, sat} \times \left( -1 - \frac{\dot{q}}{\dot{q}_{j, max}}\right), - \tau_{j, max}, 0.0 \right)\end{split}\]where \(\gamma\) is the gear ratio of the gear box connecting the motor and the actuated joint ends, \(\dot{q}_{j, max} = \gamma^{-1} \times \dot{q}_{motor, max}\), \(\tau_{j, max} = \gamma \times \tau_{motor, max}\) and \(\tau_{j, peak} = \gamma \times \tau_{motor, peak}\) are the maximum joint velocity, maximum joint torque and peak torque, respectively. These parameters are read from the configuration instance passed to the class.
Using these values, the computed torques are clipped to the minimum and maximum values based on the instantaneous joint velocity:
\[\tau_{j, applied} = clip(\tau_{computed}, \tau_{j, min}(\dot{q}), \tau_{j, max}(\dot{q}))\]Attributes:
The configuration for the actuator model.
Articulation's joint indices that are part of the group.
Articulation's joint names that are part of the group.
Number of actuators in the group.
The computed effort for the actuator group.
The applied effort for the actuator group.
The effort limit for the actuator group.
The velocity limit for the actuator group.
The stiffness (P gain) of the PD controller.
The damping (D gain) of the PD controller.
The armature of the actuator joints.
The joint friction of the actuator joints.
Methods:
__init__
(cfg, *args, **kwargs)Initialize the actuator.
compute
(control_action, joint_pos, joint_vel)Process the actuator group actions and compute the articulation actions.
reset
(env_ids)Reset the internals within the group.
- cfg: DCMotorCfg#
The configuration for the actuator model.
- __init__(cfg: DCMotorCfg, *args, **kwargs)[source]#
Initialize the actuator.
Note
The actuator parameters are parsed from the configuration and stored as buffers. If the parameters are not specified in the configuration, then the default values provided in the arguments are used.
- Parameters:
cfg – The configuration of the actuator model.
joint_names – The joint names in the articulation.
joint_ids – The joint indices in the articulation. If
slice(None)
, then all the joints in the articulation are part of the group.num_envs – Number of articulations in the view.
device – Device used for processing.
stiffness – The default joint stiffness (P gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
damping – The default joint damping (D gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
armature – The default joint armature. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
friction – The default joint friction. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
effort_limit – The default effort limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
velocity_limit – The default velocity limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
- compute(control_action: ArticulationActions, joint_pos: torch.Tensor, joint_vel: torch.Tensor) ArticulationActions [source]#
Process the actuator group actions and compute the articulation actions.
It computes the articulation actions based on the actuator model type
- Parameters:
control_action – The joint action instance comprising of the desired joint positions, joint velocities and (feed-forward) joint efforts.
joint_pos – The current joint positions of the joints in the group. Shape is (num_envs, num_joints).
joint_vel – The current joint velocities of the joints in the group. Shape is (num_envs, num_joints).
- Returns:
The computed desired joint positions, joint velocities and joint efforts.
- property joint_indices: slice | Sequence[int]#
Articulation’s joint indices that are part of the group.
Note
If
slice(None)
is returned, then the group contains all the joints in the articulation. We do this to avoid unnecessary indexing of the joints for performance reasons.
- reset(env_ids: Sequence[int])#
Reset the internals within the group.
- Parameters:
env_ids – List of environment IDs to reset.
- computed_effort: torch.Tensor#
The computed effort for the actuator group. Shape is (num_envs, num_joints).
- applied_effort: torch.Tensor#
The applied effort for the actuator group. Shape is (num_envs, num_joints).
- effort_limit: torch.Tensor#
The effort limit for the actuator group. Shape is (num_envs, num_joints).
- velocity_limit: torch.Tensor#
The velocity limit for the actuator group. Shape is (num_envs, num_joints).
- stiffness: torch.Tensor#
The stiffness (P gain) of the PD controller. Shape is (num_envs, num_joints).
- damping: torch.Tensor#
The damping (D gain) of the PD controller. Shape is (num_envs, num_joints).
- armature: torch.Tensor#
The armature of the actuator joints. Shape is (num_envs, num_joints).
- friction: torch.Tensor#
The joint friction of the actuator joints. Shape is (num_envs, num_joints).
- class omni.isaac.lab.actuators.DCMotorCfg[source]#
Bases:
IdealPDActuatorCfg
Configuration for direct control (DC) motor actuator model.
Attributes:
Peak motor force/torque of the electric DC motor (in N-m).
Articulation's joint names that are part of the group.
Force/Torque limit of the joints in the group.
Velocity limit of the joints in the group.
Stiffness gains (also known as p-gain) of the joints in the group.
Damping gains (also known as d-gain) of the joints in the group.
Armature of the joints in the group.
Joint friction of the joints in the group.
- joint_names_expr: list[str]#
Articulation’s joint names that are part of the group.
Note
This can be a list of joint names or a list of regex expressions (e.g. “.*”).
- effort_limit: dict[str, float] | float | None#
Force/Torque limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- velocity_limit: dict[str, float] | float | None#
Velocity limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- stiffness: dict[str, float] | float | None#
Stiffness gains (also known as p-gain) of the joints in the group.
If None, the stiffness is set to the value from the USD joint prim.
- damping: dict[str, float] | float | None#
Damping gains (also known as d-gain) of the joints in the group.
If None, the damping is set to the value from the USD joint prim.
Delayed PD Actuator#
- class omni.isaac.lab.actuators.DelayedPDActuator[source]#
Bases:
IdealPDActuator
Ideal PD actuator with delayed command application.
This class extends the
IdealPDActuator
class by adding a delay to the actuator commands. The delay is implemented using a circular buffer that stores the actuator commands for a certain number of physics steps. The most recent actuation value is pushed to the buffer at every physics step, but the final actuation value applied to the simulation is lagged by a certain number of physics steps.The amount of time lag is configurable and can be set to a random value between the minimum and maximum time lag bounds at every reset. The minimum and maximum time lag values are set in the configuration instance passed to the class.
Attributes:
The configuration for the actuator model.
Articulation's joint indices that are part of the group.
Articulation's joint names that are part of the group.
Number of actuators in the group.
The computed effort for the actuator group.
The applied effort for the actuator group.
The effort limit for the actuator group.
The velocity limit for the actuator group.
The stiffness (P gain) of the PD controller.
The damping (D gain) of the PD controller.
The armature of the actuator joints.
The joint friction of the actuator joints.
Methods:
__init__
(cfg, *args, **kwargs)Initialize the actuator.
reset
(env_ids)Reset the internals within the group.
compute
(control_action, joint_pos, joint_vel)Process the actuator group actions and compute the articulation actions.
- cfg: DelayedPDActuatorCfg#
The configuration for the actuator model.
- __init__(cfg: DelayedPDActuatorCfg, *args, **kwargs)[source]#
Initialize the actuator.
Note
The actuator parameters are parsed from the configuration and stored as buffers. If the parameters are not specified in the configuration, then the default values provided in the arguments are used.
- Parameters:
cfg – The configuration of the actuator model.
joint_names – The joint names in the articulation.
joint_ids – The joint indices in the articulation. If
slice(None)
, then all the joints in the articulation are part of the group.num_envs – Number of articulations in the view.
device – Device used for processing.
stiffness – The default joint stiffness (P gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
damping – The default joint damping (D gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
armature – The default joint armature. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
friction – The default joint friction. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
effort_limit – The default effort limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
velocity_limit – The default velocity limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
- reset(env_ids: Sequence[int])[source]#
Reset the internals within the group.
- Parameters:
env_ids – List of environment IDs to reset.
- compute(control_action: ArticulationActions, joint_pos: torch.Tensor, joint_vel: torch.Tensor) ArticulationActions [source]#
Process the actuator group actions and compute the articulation actions.
It computes the articulation actions based on the actuator model type
- Parameters:
control_action – The joint action instance comprising of the desired joint positions, joint velocities and (feed-forward) joint efforts.
joint_pos – The current joint positions of the joints in the group. Shape is (num_envs, num_joints).
joint_vel – The current joint velocities of the joints in the group. Shape is (num_envs, num_joints).
- Returns:
The computed desired joint positions, joint velocities and joint efforts.
- property joint_indices: slice | Sequence[int]#
Articulation’s joint indices that are part of the group.
Note
If
slice(None)
is returned, then the group contains all the joints in the articulation. We do this to avoid unnecessary indexing of the joints for performance reasons.
- computed_effort: torch.Tensor#
The computed effort for the actuator group. Shape is (num_envs, num_joints).
- applied_effort: torch.Tensor#
The applied effort for the actuator group. Shape is (num_envs, num_joints).
- effort_limit: torch.Tensor#
The effort limit for the actuator group. Shape is (num_envs, num_joints).
- velocity_limit: torch.Tensor#
The velocity limit for the actuator group. Shape is (num_envs, num_joints).
- stiffness: torch.Tensor#
The stiffness (P gain) of the PD controller. Shape is (num_envs, num_joints).
- damping: torch.Tensor#
The damping (D gain) of the PD controller. Shape is (num_envs, num_joints).
- armature: torch.Tensor#
The armature of the actuator joints. Shape is (num_envs, num_joints).
- friction: torch.Tensor#
The joint friction of the actuator joints. Shape is (num_envs, num_joints).
- class omni.isaac.lab.actuators.DelayedPDActuatorCfg[source]#
Bases:
IdealPDActuatorCfg
Configuration for a delayed PD actuator.
Attributes:
Articulation's joint names that are part of the group.
Force/Torque limit of the joints in the group.
Velocity limit of the joints in the group.
Stiffness gains (also known as p-gain) of the joints in the group.
Damping gains (also known as d-gain) of the joints in the group.
Armature of the joints in the group.
Joint friction of the joints in the group.
Minimum number of physics time-steps with which the actuator command may be delayed.
Maximum number of physics time-steps with which the actuator command may be delayed.
- joint_names_expr: list[str]#
Articulation’s joint names that are part of the group.
Note
This can be a list of joint names or a list of regex expressions (e.g. “.*”).
- effort_limit: dict[str, float] | float | None#
Force/Torque limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- velocity_limit: dict[str, float] | float | None#
Velocity limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- stiffness: dict[str, float] | float | None#
Stiffness gains (also known as p-gain) of the joints in the group.
If None, the stiffness is set to the value from the USD joint prim.
- damping: dict[str, float] | float | None#
Damping gains (also known as d-gain) of the joints in the group.
If None, the damping is set to the value from the USD joint prim.
- armature: dict[str, float] | float | None#
Armature of the joints in the group. Defaults to None.
If None, the armature is set to the value from the USD joint prim.
- friction: dict[str, float] | float | None#
Joint friction of the joints in the group. Defaults to None.
If None, the joint friction is set to the value from the USD joint prim.
Remotized PD Actuator#
- class omni.isaac.lab.actuators.RemotizedPDActuator[source]#
Bases:
DelayedPDActuator
Ideal PD actuator with angle-dependent torque limits.
This class extends the
DelayedPDActuator
class by adding angle-dependent torque limits to the actuator. The torque limits are applied by querying a lookup table describing the relationship between the joint angle and the maximum output torque. The lookup table is provided in the configuration instance passed to the class.The torque limits are interpolated based on the current joint positions and applied to the actuator commands.
Methods:
__init__
(cfg, joint_names, joint_ids, ...[, ...])Initialize the actuator.
reset
(env_ids)Reset the internals within the group.
compute
(control_action, joint_pos, joint_vel)Process the actuator group actions and compute the articulation actions.
Attributes:
Articulation's joint indices that are part of the group.
Articulation's joint names that are part of the group.
Number of actuators in the group.
The configuration for the actuator model.
The computed effort for the actuator group.
The applied effort for the actuator group.
The effort limit for the actuator group.
The velocity limit for the actuator group.
The stiffness (P gain) of the PD controller.
The damping (D gain) of the PD controller.
The armature of the actuator joints.
The joint friction of the actuator joints.
- __init__(cfg: RemotizedPDActuatorCfg, joint_names: list[str], joint_ids: Sequence[int], num_envs: int, device: str, stiffness: torch.Tensor | float = 0.0, damping: torch.Tensor | float = 0.0, armature: torch.Tensor | float = 0.0, friction: torch.Tensor | float = 0.0, effort_limit: torch.Tensor | float = torch.inf, velocity_limit: torch.Tensor | float = torch.inf)[source]#
Initialize the actuator.
Note
The actuator parameters are parsed from the configuration and stored as buffers. If the parameters are not specified in the configuration, then the default values provided in the arguments are used.
- Parameters:
cfg – The configuration of the actuator model.
joint_names – The joint names in the articulation.
joint_ids – The joint indices in the articulation. If
slice(None)
, then all the joints in the articulation are part of the group.num_envs – Number of articulations in the view.
device – Device used for processing.
stiffness – The default joint stiffness (P gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
damping – The default joint damping (D gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
armature – The default joint armature. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
friction – The default joint friction. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
effort_limit – The default effort limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
velocity_limit – The default velocity limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
- property joint_indices: slice | Sequence[int]#
Articulation’s joint indices that are part of the group.
Note
If
slice(None)
is returned, then the group contains all the joints in the articulation. We do this to avoid unnecessary indexing of the joints for performance reasons.
- reset(env_ids: Sequence[int])#
Reset the internals within the group.
- Parameters:
env_ids – List of environment IDs to reset.
- cfg: DelayedPDActuatorCfg#
The configuration for the actuator model.
- computed_effort: torch.Tensor#
The computed effort for the actuator group. Shape is (num_envs, num_joints).
- applied_effort: torch.Tensor#
The applied effort for the actuator group. Shape is (num_envs, num_joints).
- effort_limit: torch.Tensor#
The effort limit for the actuator group. Shape is (num_envs, num_joints).
- velocity_limit: torch.Tensor#
The velocity limit for the actuator group. Shape is (num_envs, num_joints).
- stiffness: torch.Tensor#
The stiffness (P gain) of the PD controller. Shape is (num_envs, num_joints).
- damping: torch.Tensor#
The damping (D gain) of the PD controller. Shape is (num_envs, num_joints).
- armature: torch.Tensor#
The armature of the actuator joints. Shape is (num_envs, num_joints).
- friction: torch.Tensor#
The joint friction of the actuator joints. Shape is (num_envs, num_joints).
- compute(control_action: ArticulationActions, joint_pos: torch.Tensor, joint_vel: torch.Tensor) ArticulationActions [source]#
Process the actuator group actions and compute the articulation actions.
It computes the articulation actions based on the actuator model type
- Parameters:
control_action – The joint action instance comprising of the desired joint positions, joint velocities and (feed-forward) joint efforts.
joint_pos – The current joint positions of the joints in the group. Shape is (num_envs, num_joints).
joint_vel – The current joint velocities of the joints in the group. Shape is (num_envs, num_joints).
- Returns:
The computed desired joint positions, joint velocities and joint efforts.
- class omni.isaac.lab.actuators.RemotizedPDActuatorCfg[source]#
Bases:
DelayedPDActuatorCfg
Configuration for a remotized PD actuator.
Note
The torque output limits for this actuator is derived from a linear interpolation of a lookup table in
joint_parameter_lookup
. This table describes the relationship between joint angles and the output torques.Attributes:
Articulation's joint names that are part of the group.
Force/Torque limit of the joints in the group.
Velocity limit of the joints in the group.
Stiffness gains (also known as p-gain) of the joints in the group.
Damping gains (also known as d-gain) of the joints in the group.
Armature of the joints in the group.
Joint friction of the joints in the group.
Minimum number of physics time-steps with which the actuator command may be delayed.
Maximum number of physics time-steps with which the actuator command may be delayed.
Joint parameter lookup table.
- joint_names_expr: list[str]#
Articulation’s joint names that are part of the group.
Note
This can be a list of joint names or a list of regex expressions (e.g. “.*”).
- effort_limit: dict[str, float] | float | None#
Force/Torque limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- velocity_limit: dict[str, float] | float | None#
Velocity limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- stiffness: dict[str, float] | float | None#
Stiffness gains (also known as p-gain) of the joints in the group.
If None, the stiffness is set to the value from the USD joint prim.
- damping: dict[str, float] | float | None#
Damping gains (also known as d-gain) of the joints in the group.
If None, the damping is set to the value from the USD joint prim.
- armature: dict[str, float] | float | None#
Armature of the joints in the group. Defaults to None.
If None, the armature is set to the value from the USD joint prim.
- friction: dict[str, float] | float | None#
Joint friction of the joints in the group. Defaults to None.
If None, the joint friction is set to the value from the USD joint prim.
- min_delay: int#
Minimum number of physics time-steps with which the actuator command may be delayed. Defaults to 0.
- max_delay: int#
Maximum number of physics time-steps with which the actuator command may be delayed. Defaults to 0.
- joint_parameter_lookup: torch.Tensor#
Joint parameter lookup table. Shape is (num_lookup_points, 3).
This tensor describes the relationship between the joint angle (rad), the transmission ratio (in/out), and the output torque (N*m). The table is used to interpolate the output torque based on the joint angle.
MLP Network Actuator#
- class omni.isaac.lab.actuators.ActuatorNetMLP[source]#
Bases:
DCMotor
Actuator model based on multi-layer perceptron and joint history.
Many times the analytical model is not sufficient to capture the actuator dynamics, the delay in the actuator response, or the non-linearities in the actuator. In these cases, a neural network model can be used to approximate the actuator dynamics. This model is trained using data collected from the physical actuator and maps the joint state and the desired joint command to the produced torque by the actuator.
This class implements the learned model as a neural network based on the work from Hwangbo et al. [HLD+19]. The class stores the history of the joint positions errors and velocities which are used to provide input to the neural network. The model is loaded as a TorchScript.
Note
Only the desired joint positions are used as inputs to the network.
Attributes:
The configuration of the actuator model.
Articulation's joint indices that are part of the group.
Articulation's joint names that are part of the group.
Number of actuators in the group.
The computed effort for the actuator group.
The applied effort for the actuator group.
The effort limit for the actuator group.
The velocity limit for the actuator group.
The stiffness (P gain) of the PD controller.
The damping (D gain) of the PD controller.
The armature of the actuator joints.
The joint friction of the actuator joints.
Methods:
__init__
(cfg, *args, **kwargs)Initialize the actuator.
reset
(env_ids)Reset the internals within the group.
compute
(control_action, joint_pos, joint_vel)Process the actuator group actions and compute the articulation actions.
- cfg: ActuatorNetMLPCfg#
The configuration of the actuator model.
- __init__(cfg: ActuatorNetMLPCfg, *args, **kwargs)[source]#
Initialize the actuator.
Note
The actuator parameters are parsed from the configuration and stored as buffers. If the parameters are not specified in the configuration, then the default values provided in the arguments are used.
- Parameters:
cfg – The configuration of the actuator model.
joint_names – The joint names in the articulation.
joint_ids – The joint indices in the articulation. If
slice(None)
, then all the joints in the articulation are part of the group.num_envs – Number of articulations in the view.
device – Device used for processing.
stiffness – The default joint stiffness (P gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
damping – The default joint damping (D gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
armature – The default joint armature. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
friction – The default joint friction. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
effort_limit – The default effort limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
velocity_limit – The default velocity limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
- property joint_indices: slice | Sequence[int]#
Articulation’s joint indices that are part of the group.
Note
If
slice(None)
is returned, then the group contains all the joints in the articulation. We do this to avoid unnecessary indexing of the joints for performance reasons.
- reset(env_ids: Sequence[int])[source]#
Reset the internals within the group.
- Parameters:
env_ids – List of environment IDs to reset.
- computed_effort: torch.Tensor#
The computed effort for the actuator group. Shape is (num_envs, num_joints).
- applied_effort: torch.Tensor#
The applied effort for the actuator group. Shape is (num_envs, num_joints).
- effort_limit: torch.Tensor#
The effort limit for the actuator group. Shape is (num_envs, num_joints).
- velocity_limit: torch.Tensor#
The velocity limit for the actuator group. Shape is (num_envs, num_joints).
- stiffness: torch.Tensor#
The stiffness (P gain) of the PD controller. Shape is (num_envs, num_joints).
- damping: torch.Tensor#
The damping (D gain) of the PD controller. Shape is (num_envs, num_joints).
- armature: torch.Tensor#
The armature of the actuator joints. Shape is (num_envs, num_joints).
- friction: torch.Tensor#
The joint friction of the actuator joints. Shape is (num_envs, num_joints).
- compute(control_action: ArticulationActions, joint_pos: torch.Tensor, joint_vel: torch.Tensor) ArticulationActions [source]#
Process the actuator group actions and compute the articulation actions.
It computes the articulation actions based on the actuator model type
- Parameters:
control_action – The joint action instance comprising of the desired joint positions, joint velocities and (feed-forward) joint efforts.
joint_pos – The current joint positions of the joints in the group. Shape is (num_envs, num_joints).
joint_vel – The current joint velocities of the joints in the group. Shape is (num_envs, num_joints).
- Returns:
The computed desired joint positions, joint velocities and joint efforts.
- class omni.isaac.lab.actuators.ActuatorNetMLPCfg[source]#
Bases:
DCMotorCfg
Configuration for MLP-based actuator model.
Attributes:
Stiffness gains (also known as p-gain) of the joints in the group.
Damping gains (also known as d-gain) of the joints in the group.
Path to the file containing network weights.
Articulation's joint names that are part of the group.
Force/Torque limit of the joints in the group.
Velocity limit of the joints in the group.
Armature of the joints in the group.
Joint friction of the joints in the group.
Peak motor force/torque of the electric DC motor (in N-m).
Scaling of the joint position errors input to the network.
Scaling of the joint velocities input to the network.
Scaling of the joint efforts output from the network.
Order of the inputs to the network.
Indices of the actuator history buffer passed as inputs to the network.
- stiffness: dict[str, float] | float | None#
Stiffness gains (also known as p-gain) of the joints in the group.
If None, the stiffness is set to the value from the USD joint prim.
- damping: dict[str, float] | float | None#
Damping gains (also known as d-gain) of the joints in the group.
If None, the damping is set to the value from the USD joint prim.
- joint_names_expr: list[str]#
Articulation’s joint names that are part of the group.
Note
This can be a list of joint names or a list of regex expressions (e.g. “.*”).
- effort_limit: dict[str, float] | float | None#
Force/Torque limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- velocity_limit: dict[str, float] | float | None#
Velocity limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- armature: dict[str, float] | float | None#
Armature of the joints in the group. Defaults to None.
If None, the armature is set to the value from the USD joint prim.
- friction: dict[str, float] | float | None#
Joint friction of the joints in the group. Defaults to None.
If None, the joint friction is set to the value from the USD joint prim.
LSTM Network Actuator#
- class omni.isaac.lab.actuators.ActuatorNetLSTM[source]#
Bases:
DCMotor
Actuator model based on recurrent neural network (LSTM).
Unlike the MLP implementation Hwangbo et al. [HLD+19], this class implements the learned model as a temporal neural network (LSTM) based on the work from Rudin et al. [RHRH22]. This removes the need of storing a history as the hidden states of the recurrent network captures the history.
Note
Only the desired joint positions are used as inputs to the network.
Attributes:
The configuration of the actuator model.
Articulation's joint indices that are part of the group.
Articulation's joint names that are part of the group.
Number of actuators in the group.
The computed effort for the actuator group.
The applied effort for the actuator group.
The effort limit for the actuator group.
The velocity limit for the actuator group.
The stiffness (P gain) of the PD controller.
The damping (D gain) of the PD controller.
The armature of the actuator joints.
The joint friction of the actuator joints.
Methods:
__init__
(cfg, *args, **kwargs)Initialize the actuator.
reset
(env_ids)Reset the internals within the group.
compute
(control_action, joint_pos, joint_vel)Process the actuator group actions and compute the articulation actions.
- cfg: ActuatorNetLSTMCfg#
The configuration of the actuator model.
- __init__(cfg: ActuatorNetLSTMCfg, *args, **kwargs)[source]#
Initialize the actuator.
Note
The actuator parameters are parsed from the configuration and stored as buffers. If the parameters are not specified in the configuration, then the default values provided in the arguments are used.
- Parameters:
cfg – The configuration of the actuator model.
joint_names – The joint names in the articulation.
joint_ids – The joint indices in the articulation. If
slice(None)
, then all the joints in the articulation are part of the group.num_envs – Number of articulations in the view.
device – Device used for processing.
stiffness – The default joint stiffness (P gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
damping – The default joint damping (D gain). Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
armature – The default joint armature. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
friction – The default joint friction. Defaults to 0.0. If a tensor, then the shape is (num_envs, num_joints).
effort_limit – The default effort limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
velocity_limit – The default velocity limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints).
- reset(env_ids: Sequence[int])[source]#
Reset the internals within the group.
- Parameters:
env_ids – List of environment IDs to reset.
- compute(control_action: ArticulationActions, joint_pos: torch.Tensor, joint_vel: torch.Tensor) ArticulationActions [source]#
Process the actuator group actions and compute the articulation actions.
It computes the articulation actions based on the actuator model type
- Parameters:
control_action – The joint action instance comprising of the desired joint positions, joint velocities and (feed-forward) joint efforts.
joint_pos – The current joint positions of the joints in the group. Shape is (num_envs, num_joints).
joint_vel – The current joint velocities of the joints in the group. Shape is (num_envs, num_joints).
- Returns:
The computed desired joint positions, joint velocities and joint efforts.
- property joint_indices: slice | Sequence[int]#
Articulation’s joint indices that are part of the group.
Note
If
slice(None)
is returned, then the group contains all the joints in the articulation. We do this to avoid unnecessary indexing of the joints for performance reasons.
- computed_effort: torch.Tensor#
The computed effort for the actuator group. Shape is (num_envs, num_joints).
- applied_effort: torch.Tensor#
The applied effort for the actuator group. Shape is (num_envs, num_joints).
- effort_limit: torch.Tensor#
The effort limit for the actuator group. Shape is (num_envs, num_joints).
- velocity_limit: torch.Tensor#
The velocity limit for the actuator group. Shape is (num_envs, num_joints).
- stiffness: torch.Tensor#
The stiffness (P gain) of the PD controller. Shape is (num_envs, num_joints).
- damping: torch.Tensor#
The damping (D gain) of the PD controller. Shape is (num_envs, num_joints).
- armature: torch.Tensor#
The armature of the actuator joints. Shape is (num_envs, num_joints).
- friction: torch.Tensor#
The joint friction of the actuator joints. Shape is (num_envs, num_joints).
- class omni.isaac.lab.actuators.ActuatorNetLSTMCfg[source]#
Bases:
DCMotorCfg
Configuration for LSTM-based actuator model.
Attributes:
Stiffness gains (also known as p-gain) of the joints in the group.
Damping gains (also known as d-gain) of the joints in the group.
Path to the file containing network weights.
Articulation's joint names that are part of the group.
Force/Torque limit of the joints in the group.
Velocity limit of the joints in the group.
Armature of the joints in the group.
Joint friction of the joints in the group.
Peak motor force/torque of the electric DC motor (in N-m).
- stiffness: dict[str, float] | float | None#
Stiffness gains (also known as p-gain) of the joints in the group.
If None, the stiffness is set to the value from the USD joint prim.
- damping: dict[str, float] | float | None#
Damping gains (also known as d-gain) of the joints in the group.
If None, the damping is set to the value from the USD joint prim.
- joint_names_expr: list[str]#
Articulation’s joint names that are part of the group.
Note
This can be a list of joint names or a list of regex expressions (e.g. “.*”).
- effort_limit: dict[str, float] | float | None#
Force/Torque limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- velocity_limit: dict[str, float] | float | None#
Velocity limit of the joints in the group. Defaults to None.
If None, the limit is set to the value specified in the USD joint prim.
- armature: dict[str, float] | float | None#
Armature of the joints in the group. Defaults to None.
If None, the armature is set to the value from the USD joint prim.