We have now released v0.3.0! Please use the latest version for the best experience.

orbit.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

DifferentialIKController

Differential inverse kinematics (IK) controller.

DifferentialIKControllerCfg

Configuration for differential inverse kinematics controller.

Differential Inverse Kinematics#

class omni.isaac.orbit.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.

\[\Delta \mathbf{q} = \mathbf{J}^{\dagger} \Delta \mathbf{x} \mathbf{q}_{\text{desired}} = \mathbf{q}_{\text{current}} + \Delta \mathbf{q}\]

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:

[1] https://ethz.ch/content/dam/ethz/special-interest/mavt/robotics-n-intelligent-systems/rsl-dam/documents/RobotDynamics2017/RD_HS2017script.pdf [2] https://www.cs.cmu.edu/~15464-s13/lectures/lecture6/iksurvey.pdf

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:

action_dim

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.

property action_dim: int#

Dimension of the controller’s input command.

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 or pose_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 or pose_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_* or pose_rel.

Raises:
  • ValueError – If the command type is position_* and ee_quat is None.

  • ValueError – If the command type is position_rel and ee_pos is None.

  • ValueError – If the command type is pose_rel and either ee_pos or ee_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.orbit.controllers.DifferentialIKControllerCfg[source]#

Bases: object

Configuration for differential inverse kinematics controller.

Attributes:

command_type

Type of task-space command to control the articulation's body.

use_relative_mode

Whether to use relative mode for the controller.

ik_method

Method for computing inverse of Jacobian.

ik_params

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_method: Literal['pinv', 'svd', 'trans', 'dls']#

Method for computing inverse of Jacobian.

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).