uwlab.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 multi-constraint differential inverse kinematics controller. |
Differential Inverse Kinematics With Multiple Bodies#
- class uwlab.controllers.MultiConstraintDifferentialIKController[source]#
Bases:
object
Differential inverse kinematics (IK) controller.
Note
This controller extends Isaac Lab differential inverse kinematic and provides multi constraints solution.
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.
- Currently only below methods are supported :
“dls”: Damped version of Moore-Penrose pseudo-inverse (also called Levenberg-Marquardt)
Caution
Isaac Lab non-multiconstraints version implementation contains methods such as pinv, svd, trans, however their solution is not yet implemented even though these inputs are available.
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 [3] https://isaac-sim.github.io/IsaacLab/source/api/lab/isaaclab.controllers.html
Methods:
__init__
(cfg, num_bodies, 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: MultiConstraintDifferentialIKControllerCfg, num_bodies: int, 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 * num_bodies) or (N, 6 * num_bodies) or (N, 7 * num_bodies).
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 uwlab.controllers.MultiConstraintDifferentialIKControllerCfg#
Bases:
DifferentialIKControllerCfg
Configuration for multi-constraint differential inverse kinematics controller.