omni.isaac.lab.controllers#
Sub-package for different controllers and motion-generators.
Controllers or motion generators are responsible for closed-loop tracking of a given command. The controller can be a simple PID controller or a more complex controller such as impedance control or inverse kinematics control. The controller is responsible for generating the desired joint-level commands to be sent to the robot.
Classes
Differential inverse kinematics (IK) controller. |
|
Configuration for differential inverse kinematics controller. |
|
Operational-space controller. |
|
Configuration for operational-space controller. |
Differential Inverse Kinematics#
- class omni.isaac.lab.controllers.DifferentialIKController[source]#
Bases:
object
Differential inverse kinematics (IK) controller.
This controller is based on the concept of differential inverse kinematics [1, 2] which is a method for computing the change in joint positions that yields the desired change in pose.
\[\begin{split}\Delta \mathbf{q} &= \mathbf{J}^{\dagger} \Delta \mathbf{x} \\ \mathbf{q}_{\text{desired}} &= \mathbf{q}_{\text{current}} + \Delta \mathbf{q}\end{split}\]where \(\mathbf{J}^{\dagger}\) is the pseudo-inverse of the Jacobian matrix \(\mathbf{J}\), \(\Delta \mathbf{x}\) is the desired change in pose, and \(\mathbf{q}_{\text{current}}\) is the current joint positions.
To deal with singularity in Jacobian, the following methods are supported for computing inverse of the Jacobian:
“pinv”: Moore-Penrose pseudo-inverse
“svd”: Adaptive singular-value decomposition (SVD)
“trans”: Transpose of matrix
“dls”: Damped version of Moore-Penrose pseudo-inverse (also called Levenberg-Marquardt)
Caution
The controller does not assume anything about the frames of the current and desired end-effector pose, or the joint-space velocities. It is up to the user to ensure that these quantities are given in the correct format.
Reference:
Robot Dynamics Lecture Notes by Marco Hutter (ETH Zurich)
Introduction to Inverse Kinematics by Samuel R. Buss (University of California, San Diego)
Methods:
__init__
(cfg, num_envs, device)Initialize the controller.
reset
([env_ids])Reset the internals.
set_command
(command[, ee_pos, ee_quat])Set target end-effector pose command.
compute
(ee_pos, ee_quat, jacobian, joint_pos)Computes the target joint positions that will yield the desired end effector pose.
Attributes:
Dimension of the controller's input command.
- __init__(cfg: DifferentialIKControllerCfg, num_envs: int, device: str)[source]#
Initialize the controller.
- Parameters:
cfg – The configuration for the controller.
num_envs – The number of environments.
device – The device to use for computations.
- reset(env_ids: torch.Tensor | None = None)[source]#
Reset the internals.
- Parameters:
env_ids – The environment indices to reset. If None, then all environments are reset.
- set_command(command: torch.Tensor, ee_pos: torch.Tensor | None = None, ee_quat: torch.Tensor | None = None)[source]#
Set target end-effector pose command.
Based on the configured command type and relative mode, the method computes the desired end-effector pose. It is up to the user to ensure that the command is given in the correct frame. The method only applies the relative mode if the command type is
position_rel
orpose_rel
.- Parameters:
command – The input command in shape (N, 3) or (N, 6) or (N, 7).
ee_pos – The current end-effector position in shape (N, 3). This is only needed if the command type is
position_rel
orpose_rel
.ee_quat – The current end-effector orientation (w, x, y, z) in shape (N, 4). This is only needed if the command type is
position_*
orpose_rel
.
- Raises:
ValueError – If the command type is
position_*
andee_quat
is None.ValueError – If the command type is
position_rel
andee_pos
is None.ValueError – If the command type is
pose_rel
and eitheree_pos
oree_quat
is None.
- compute(ee_pos: torch.Tensor, ee_quat: torch.Tensor, jacobian: torch.Tensor, joint_pos: torch.Tensor) torch.Tensor [source]#
Computes the target joint positions that will yield the desired end effector pose.
- Parameters:
ee_pos – The current end-effector position in shape (N, 3).
ee_quat – The current end-effector orientation in shape (N, 4).
jacobian – The geometric jacobian matrix in shape (N, 6, num_joints).
joint_pos – The current joint positions in shape (N, num_joints).
- Returns:
The target joint positions commands in shape (N, num_joints).
- class omni.isaac.lab.controllers.DifferentialIKControllerCfg[source]#
Bases:
object
Configuration for differential inverse kinematics controller.
Attributes:
Type of task-space command to control the articulation's body.
Whether to use relative mode for the controller.
Method for computing inverse of Jacobian.
Parameters for the inverse-kinematics method.
- command_type: Literal['position', 'pose']#
Type of task-space command to control the articulation’s body.
If “position”, then the controller only controls the position of the articulation’s body. Otherwise, the controller controls the pose of the articulation’s body.
- use_relative_mode: bool#
Whether to use relative mode for the controller. Defaults to False.
If True, then the controller treats the input command as a delta change in the position/pose. Otherwise, the controller treats the input command as the absolute position/pose.
- ik_params: dict[str, float] | None#
Parameters for the inverse-kinematics method. Defaults to None, in which case the default parameters for the method are used.
- Moore-Penrose pseudo-inverse (“pinv”):
“k_val”: Scaling of computed delta-joint positions (default: 1.0).
- Adaptive Singular Value Decomposition (“svd”):
“k_val”: Scaling of computed delta-joint positions (default: 1.0).
“min_singular_value”: Single values less than this are suppressed to zero (default: 1e-5).
- Jacobian transpose (“trans”):
“k_val”: Scaling of computed delta-joint positions (default: 1.0).
- Damped Moore-Penrose pseudo-inverse (“dls”):
“lambda_val”: Damping coefficient (default: 0.01).
Operational Space controllers#
- class omni.isaac.lab.controllers.OperationalSpaceController[source]#
Bases:
object
Operational-space controller.
Reference:
A unified approach for motion and force control of robot manipulators: The operational space formulation by Oussama Khatib (Stanford University)
Robot Dynamics Lecture Notes by Marco Hutter (ETH Zurich)
Methods:
__init__
(cfg, num_envs, device)Initialize operational-space controller.
reset
()Reset the internals.
set_command
(command[, current_ee_pose_b, ...])Set the task-space targets and impedance parameters.
compute
(jacobian_b[, current_ee_pose_b, ...])Performs inference with the controller.
Attributes:
Dimension of the action space of controller.
- __init__(cfg: OperationalSpaceControllerCfg, num_envs: int, device: str)[source]#
Initialize operational-space controller.
- Parameters:
cfg – The configuration for operational-space controller.
num_envs – The number of environments.
device – The device to use for computations.
- Raises:
ValueError – When invalid control command is provided.
- set_command(command: torch.Tensor, current_ee_pose_b: torch.Tensor | None = None, current_task_frame_pose_b: torch.Tensor | None = None)[source]#
Set the task-space targets and impedance parameters.
- Parameters:
command (torch.Tensor) – A concatenated tensor of shape (
num_envs
,action_dim
) containing task-space targets (i.e., pose/wrench) and impedance parameters.current_ee_pose_b (torch.Tensor, optional) – Current end-effector pose, in root frame, of shape (
num_envs
, 7), containing position and quaternion(w, x, y, z)
. Required for relative commands. Defaults to None.current_task_frame_pose_b – Current pose of the task frame, in root frame, in which the targets and the (motion/wrench) control axes are defined. It is a tensor of shape (
num_envs
, 7), containing position and the quaternion(w, x, y, z)
. Defaults to None.
- Format:
Task-space targets, ordered according to ‘command_types’:
Absolute pose: shape (
num_envs
, 7), containing position and quaternion(w, x, y, z)
. Relative pose: shape (num_envs
, 6), containing delta position and rotation in axis-angle form. Absolute wrench: shape (num_envs
, 6), containing force and torque.Impedance parameters: stiffness for
variable_kp
, or stiffness, followed by damping ratio forvariable
:Stiffness: shape (
num_envs
, 6) Damping ratio: shape (num_envs
, 6)
- Raises:
ValueError – When the command dimensions are invalid.
ValueError – When an invalid impedance mode is provided.
ValueError – When the current end-effector pose is not provided for the
pose_rel
command.ValueError – When an invalid control command is provided.
- compute(jacobian_b: torch.Tensor, current_ee_pose_b: torch.Tensor | None = None, current_ee_vel_b: torch.Tensor | None = None, current_ee_force_b: torch.Tensor | None = None, mass_matrix: torch.Tensor | None = None, gravity: torch.Tensor | None = None, current_joint_pos: torch.Tensor | None = None, current_joint_vel: torch.Tensor | None = None, nullspace_joint_pos_target: torch.Tensor | None = None) torch.Tensor [source]#
Performs inference with the controller.
- Parameters:
jacobian_b – The Jacobian matrix of the end-effector in root frame. It is a tensor of shape (
num_envs
, 6,num_DoF
).current_ee_pose_b – The current end-effector pose in root frame. It is a tensor of shape (
num_envs
, 7), which contains the position and quaternion(w, x, y, z)
. Defaults toNone
.current_ee_vel_b – The current end-effector velocity in root frame. It is a tensor of shape (
num_envs
, 6), which contains the linear and angular velocities. Defaults to None.current_ee_force_b – The current external force on the end-effector in root frame. It is a tensor of shape (
num_envs
, 3), which contains the linear force. Defaults toNone
.mass_matrix – The joint-space mass/inertia matrix. It is a tensor of shape (
num_envs
,num_DoF
,num_DoF
). Defaults toNone
.gravity – The joint-space gravity vector. It is a tensor of shape (
num_envs
,num_DoF
). Defaults toNone
.current_joint_pos – The current joint positions. It is a tensor of shape (
num_envs
,num_DoF
). Defaults toNone
.current_joint_vel – The current joint velocities. It is a tensor of shape (
num_envs
,num_DoF
). Defaults toNone
.nullspace_joint_pos_target – The target joint positions the null space controller is trying to enforce, when possible. It is a tensor of shape (
num_envs
,num_DoF
).
- Raises:
ValueError – When motion-control is enabled but the current end-effector pose or velocity is not provided.
ValueError – When inertial dynamics decoupling is enabled but the mass matrix is not provided.
ValueError – When the current end-effector pose is not provided for the
pose_rel
command.ValueError – When closed-loop force control is enabled but the current end-effector force is not provided.
ValueError – When gravity compensation is enabled but the gravity vector is not provided.
ValueError – When null-space control is enabled but the system is not redundant.
ValueError – When dynamically consistent pseudo-inverse is enabled but the mass matrix inverse is not provided.
ValueError – When null-space control is enabled but the current joint positions and velocities are not provided.
ValueError – When target joint positions are provided for null-space control but their dimensions do not match the current joint positions.
ValueError – When an invalid null-space control method is provided.
- Returns:
The joint efforts computed by the controller. It is a tensor of shape (
num_envs
,num_DoF
).- Return type:
Tensor
- class omni.isaac.lab.controllers.OperationalSpaceControllerCfg[source]#
Bases:
object
Configuration for operational-space controller.
Attributes:
Type of task-space targets.
Motion direction to control in task reference frame.
Contact wrench direction to control in task reference frame.
Whether to perform inertial dynamics decoupling for motion control (inverse dynamics).
Whether to ignore the inertial coupling between the translational & rotational motions.
Whether to perform gravity compensation.
"fixed"
,"variable"
,"variable_kp"
.The positional gain for determining operational space command forces based on task-space pose error.
The damping ratio is used in-conjunction with positional gain to compute operational space command forces based on task-space velocity error.
Minimum and maximum values for positional gains.
Minimum and maximum values for damping ratios used to compute velocity gains.
The proportional gain for determining operational space command forces for closed-loop contact force control.
"none"
,"position"
.The stiffness for null space control.
The damping ratio for null space control.
- target_types: Sequence[str]#
Type of task-space targets.
- It has two sub-strings joined by underscore:
type of task-space target:
"pose"
,"wrench"
reference for the task-space targets:
"abs"
(absolute),"rel"
(relative, only for pose)
- motion_control_axes_task: Sequence[int]#
Motion direction to control in task reference frame. Mark as
0/1
for each axis.
- contact_wrench_control_axes_task: Sequence[int]#
Contact wrench direction to control in task reference frame. Mark as 0/1 for each axis.
- inertial_dynamics_decoupling: bool#
Whether to perform inertial dynamics decoupling for motion control (inverse dynamics).
- partial_inertial_dynamics_decoupling: bool#
Whether to ignore the inertial coupling between the translational & rotational motions.
- motion_stiffness_task: float | Sequence[float]#
The positional gain for determining operational space command forces based on task-space pose error.
- motion_damping_ratio_task: float | Sequence[float]#
The damping ratio is used in-conjunction with positional gain to compute operational space command forces based on task-space velocity error.
- The following math operation is performed for computing velocity gains:
\(d_gains = 2 * sqrt(p_gains) * damping_ratio\).
- motion_stiffness_limits_task: tuple[float, float]#
Minimum and maximum values for positional gains.
Note: Used only when
impedance_mode
is"variable"
or"variable_kp"
.
- motion_damping_ratio_limits_task: tuple[float, float]#
Minimum and maximum values for damping ratios used to compute velocity gains.
Note: Used only when
impedance_mode
is"variable"
.
- contact_wrench_stiffness_task: float | Sequence[float] | None#
The proportional gain for determining operational space command forces for closed-loop contact force control.
If
None
, then open-loop control of desired contact wrench is performed.Note: since only the linear forces could be measured at the moment, only the first three elements are used for the feedback loop.