Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
52 changes: 3 additions & 49 deletions source/isaaclab/isaaclab/controllers/joint_impedance.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,58 +5,12 @@

from __future__ import annotations

from collections.abc import Sequence
from dataclasses import MISSING
from typing import TYPE_CHECKING

import torch

from isaaclab.utils import configclass


@configclass
class JointImpedanceControllerCfg:
"""Configuration for joint impedance regulation controller."""

command_type: str = "p_abs"
"""Type of command: p_abs (absolute) or p_rel (relative)."""

dof_pos_offset: Sequence[float] | None = None
"""Offset to DOF position command given to controller. (default: None).

If None then position offsets are set to zero.
"""

impedance_mode: str = MISSING
"""Type of gains: "fixed", "variable", "variable_kp"."""

inertial_compensation: bool = False
"""Whether to perform inertial compensation (inverse dynamics)."""

gravity_compensation: bool = False
"""Whether to perform gravity compensation."""

stiffness: float | Sequence[float] = MISSING
"""The positional gain for determining desired torques based on joint position error."""

damping_ratio: float | Sequence[float] | None = None
"""The damping ratio is used in-conjunction with positional gain to compute desired torques
based on joint velocity error.

The following math operation is performed for computing velocity gains:
:math:`d_gains = 2 * sqrt(p_gains) * damping_ratio`.
"""

stiffness_limits: tuple[float, float] = (0, 300)
"""Minimum and maximum values for positional gains.

Note: Used only when :obj:`impedance_mode` is "variable" or "variable_kp".
"""

damping_ratio_limits: tuple[float, float] = (0, 100)
"""Minimum and maximum values for damping ratios used to compute velocity gains.

Note: Used only when :obj:`impedance_mode` is "variable".
"""
if TYPE_CHECKING:
from .joint_impedance_cfg import JointImpedanceControllerCfg


class JointImpedanceController:
Expand Down
60 changes: 60 additions & 0 deletions source/isaaclab/isaaclab/controllers/joint_impedance_cfg.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

from __future__ import annotations

from collections.abc import Sequence
from dataclasses import MISSING

from isaaclab.utils import configclass


@configclass
class JointImpedanceControllerCfg:
"""Configuration for joint impedance regulation controller."""

class_type: type | str = "isaaclab.controllers.joint_impedance:JointImpedanceController"
"""The associated controller class."""

command_type: str = "p_abs"
"""Type of command: p_abs (absolute) or p_rel (relative)."""

dof_pos_offset: Sequence[float] | None = None
"""Offset to DOF position command given to controller. (default: None).

If None then position offsets are set to zero.
"""

impedance_mode: str = MISSING
"""Type of gains: "fixed", "variable", "variable_kp"."""

inertial_compensation: bool = False
"""Whether to perform inertial compensation (inverse dynamics)."""

gravity_compensation: bool = False
"""Whether to perform gravity compensation."""

stiffness: float | Sequence[float] = MISSING
"""The positional gain for determining desired torques based on joint position error."""

damping_ratio: float | Sequence[float] | None = None
"""The damping ratio is used in-conjunction with positional gain to compute desired torques
based on joint velocity error.

The following math operation is performed for computing velocity gains:
:math:`d_gains = 2 * sqrt(p_gains) * damping_ratio`.
"""

stiffness_limits: tuple[float, float] = (0, 300)
"""Minimum and maximum values for positional gains.

Note: Used only when :obj:`impedance_mode` is "variable" or "variable_kp".
"""

damping_ratio_limits: tuple[float, float] = (0, 100)
"""Minimum and maximum values for damping ratios used to compute velocity gains.

Note: Used only when :obj:`impedance_mode` is "variable".
"""
118 changes: 11 additions & 107 deletions source/isaaclab/isaaclab/controllers/pink_ik/local_frame_task.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,114 +3,18 @@
#
# SPDX-License-Identifier: BSD-3-Clause

from collections.abc import Sequence
"""Deprecated compatibility shim for Pink task imports.

import numpy as np
import pinocchio as pin
from pink.tasks.frame_task import FrameTask
Prefer importing from ``isaaclab.controllers.pink_ik.pink_tasks``.
"""

from .pink_kinematics_configuration import PinkKinematicsConfiguration
from __future__ import annotations

import warnings

class LocalFrameTask(FrameTask):
"""
A task that computes error in a local (custom) frame.
Inherits from FrameTask but overrides compute_error.
"""

def __init__(
self,
frame: str,
base_link_frame_name: str,
position_cost: float | Sequence[float],
orientation_cost: float | Sequence[float],
lm_damping: float = 0.0,
gain: float = 1.0,
):
"""
Initialize the LocalFrameTask with configuration.

This task computes pose errors in a local (custom) frame rather than the world frame,
allowing for more flexible control strategies where the reference frame can be
specified independently.

Args:
frame: Name of the frame to control (end-effector or target frame).
base_link_frame_name: Name of the base link frame used as reference frame
for computing transforms and errors.
position_cost: Cost weight(s) for position error. Can be a single float
for uniform weighting or a sequence of 3 floats for per-axis weighting.
orientation_cost: Cost weight(s) for orientation error. Can be a single float
for uniform weighting or a sequence of 3 floats for per-axis weighting.
lm_damping: Levenberg-Marquardt damping factor for numerical stability.
Defaults to 0.0 (no damping).
gain: Task gain factor that scales the overall task contribution.
Defaults to 1.0.
"""
super().__init__(frame, position_cost, orientation_cost, lm_damping, gain)
self.base_link_frame_name = base_link_frame_name
self.transform_target_to_base = None

def set_target(self, transform_target_to_base: pin.SE3) -> None:
"""Set task target pose in the world frame.

Args:
transform_target_to_world: Transform from the task target frame to
the world frame.
"""
self.transform_target_to_base = transform_target_to_base.copy()

def set_target_from_configuration(self, configuration: PinkKinematicsConfiguration) -> None:
"""Set task target pose from a robot configuration.

Args:
configuration: Robot configuration.
"""
if not isinstance(configuration, PinkKinematicsConfiguration):
raise ValueError("configuration must be a PinkKinematicsConfiguration")
self.set_target(configuration.get_transform(self.frame, self.base_link_frame_name))

def compute_error(self, configuration: PinkKinematicsConfiguration) -> np.ndarray:
"""
Compute the error between current and target pose in a local frame.
"""
if not isinstance(configuration, PinkKinematicsConfiguration):
raise ValueError("configuration must be a PinkKinematicsConfiguration")
if self.transform_target_to_base is None:
raise ValueError(f"no target set for frame '{self.frame}'")

transform_frame_to_base = configuration.get_transform(self.frame, self.base_link_frame_name)
transform_target_to_frame = transform_frame_to_base.actInv(self.transform_target_to_base)

error_in_frame: np.ndarray = pin.log(transform_target_to_frame).vector
return error_in_frame

def compute_jacobian(self, configuration: PinkKinematicsConfiguration) -> np.ndarray:
r"""Compute the frame task Jacobian.

The task Jacobian :math:`J(q) \in \mathbb{R}^{6 \times n_v}` is the
derivative of the task error :math:`e(q) \in \mathbb{R}^6` with respect
to the configuration :math:`q`. The formula for the frame task is:

.. math::

J(q) = -\text{Jlog}_6(T_{tb}) {}_b J_{0b}(q)

The derivation of the formula for this Jacobian is detailed in
[Caron2023]_. See also
:func:`pink.tasks.task.Task.compute_jacobian` for more context on task
Jacobians.

Args:
configuration: Robot configuration :math:`q`.

Returns:
Jacobian matrix :math:`J`, expressed locally in the frame.
"""
if self.transform_target_to_base is None:
raise Exception(f"no target set for frame '{self.frame}'")
transform_frame_to_base = configuration.get_transform(self.frame, self.base_link_frame_name)
transform_frame_to_target = self.transform_target_to_base.actInv(transform_frame_to_base)
jacobian_in_frame = configuration.get_frame_jacobian(self.frame)
J = -pin.Jlog6(transform_frame_to_target) @ jacobian_in_frame
return J
warnings.warn(
"`isaaclab.controllers.pink_ik.local_frame_task` is deprecated; "
"import from `isaaclab.controllers.pink_ik.pink_tasks` instead.",
DeprecationWarning,
stacklevel=2,
)
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@

from __future__ import annotations

from typing import Any

import numpy as np
import pinocchio as pin
import scipy.linalg.blas as blas
Expand Down Expand Up @@ -87,7 +89,7 @@ class NullSpacePostureTask(Task):

def __init__(
self,
cost: float,
cost: float | Any,
lm_damping: float = 0.0,
gain: float = 1.0,
controlled_frames: list[str] | None = None,
Expand All @@ -111,6 +113,15 @@ def __init__(
controlled_joints: Joint names to control in the posture task. If None or
empty, all actuated joints are controlled.
"""
# Support class_type(cfg) construction by accepting a config object as first argument.
if not isinstance(cost, (int, float)):
cfg = cost
cost = float(getattr(cfg, "cost"))
lm_damping = float(getattr(cfg, "lm_damping", lm_damping))
gain = float(getattr(cfg, "gain", gain))
controlled_frames = getattr(cfg, "controlled_frames", controlled_frames)
controlled_joints = getattr(cfg, "controlled_joints", controlled_joints)

super().__init__(cost=cost, gain=gain, lm_damping=lm_damping)
self.target_q: np.ndarray | None = None
self.controlled_frames: list[str] = controlled_frames or []
Expand Down
44 changes: 34 additions & 10 deletions source/isaaclab/isaaclab/controllers/pink_ik/pink_ik.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,17 +14,21 @@

from __future__ import annotations

from typing import TYPE_CHECKING
from typing import TYPE_CHECKING, cast

import numpy as np
import torch
from pink import solve_ik
from pink.tasks import Task

from isaaclab.assets import ArticulationCfg
from isaaclab.controllers import utils as controller_utils
from isaaclab.utils.assets import retrieve_file_path
from isaaclab.utils.string import resolve_matching_names_values

from .null_space_posture_task import NullSpacePostureTask
from .pink_kinematics_configuration import PinkKinematicsConfiguration
from .pink_task_cfg import PinkIKTaskCfg

if TYPE_CHECKING:
from .pink_ik_cfg import PinkIKControllerCfg
Expand Down Expand Up @@ -74,10 +78,25 @@ def __init__(
# Validate consistency between controlled_joint_indices and configuration
self._validate_consistency(cfg, controlled_joint_indices)

# Resolve URDF/mesh paths at runtime. If only usd_path is provided, convert USD→URDF first.
if cfg.urdf_path is None and cfg.usd_path is not None:
import tempfile

urdf_output_dir = cfg.urdf_output_dir or tempfile.gettempdir()
urdf_path, mesh_path = controller_utils.convert_usd_to_urdf(
cfg.usd_path, urdf_output_dir, force_conversion=True
)
else:
urdf_path = retrieve_file_path(cfg.urdf_path) if cfg.urdf_path else cfg.urdf_path
mesh_path = retrieve_file_path(cfg.mesh_path) if cfg.mesh_path else cfg.mesh_path

if urdf_path is None:
raise ValueError("Either urdf_path or usd_path must be provided in the controller configuration")

# Initialize the Kinematics model used by pink IK to control robot
self.pink_configuration = PinkKinematicsConfiguration(
urdf_path=cfg.urdf_path,
mesh_path=cfg.mesh_path,
urdf_path=urdf_path,
mesh_path=mesh_path,
controlled_joint_names=cfg.joint_names,
)

Expand All @@ -93,16 +112,19 @@ def __init__(
)
self.init_joint_positions = np.zeros(len(pink_joint_names))
self.init_joint_positions[indices] = np.array(values)
self._variable_input_tasks = [task_cfg.class_type(task_cfg) for task_cfg in cfg.variable_input_tasks]
self._fixed_input_tasks = [task_cfg.class_type(task_cfg) for task_cfg in cfg.fixed_input_tasks]
self.cfg.variable_input_tasks = cast(list[Task | PinkIKTaskCfg], self._variable_input_tasks)
self.cfg.fixed_input_tasks = cast(list[Task | PinkIKTaskCfg], self._fixed_input_tasks)

# Set the default targets for each task from the configuration
for task in cfg.variable_input_tasks:
for task in self._variable_input_tasks:
# If task is a NullSpacePostureTask, set the target to the initial joint positions
if isinstance(task, NullSpacePostureTask):
task.set_target(self.init_joint_positions)
continue
task.set_target_from_configuration(self.pink_configuration)
for task in cfg.fixed_input_tasks:
task.set_target_from_configuration(self.pink_configuration)
getattr(task, "set_target_from_configuration")(self.pink_configuration)
for task in self._fixed_input_tasks:
getattr(task, "set_target_from_configuration")(self.pink_configuration)

# Create joint ordering mappings
self._setup_joint_ordering_mappings()
Expand All @@ -127,6 +149,8 @@ def _validate_consistency(self, cfg: PinkIKControllerCfg, controlled_joint_indic
)

# Check: Joint name consistency - verify that the indices point to the expected joint names
if cfg.all_joint_names is None:
raise ValueError("cfg.all_joint_names cannot be None")
actual_joint_names = [cfg.all_joint_names[idx] for idx in controlled_joint_indices]
if actual_joint_names != cfg.joint_names:
mismatches = []
Expand Down Expand Up @@ -184,7 +208,7 @@ def update_null_space_joint_targets(self, curr_joint_pos: np.ndarray):
Args:
curr_joint_pos: The current joint positions of shape (num_joints,).
"""
for task in self.cfg.variable_input_tasks:
for task in self._variable_input_tasks:
if isinstance(task, NullSpacePostureTask):
task.set_target(curr_joint_pos)

Expand Down Expand Up @@ -220,7 +244,7 @@ def compute(
try:
velocity = solve_ik(
self.pink_configuration,
self.cfg.variable_input_tasks + self.cfg.fixed_input_tasks,
self._variable_input_tasks + self._fixed_input_tasks,
dt,
solver="daqp",
safety_break=self.cfg.fail_on_joint_limit_violation,
Expand Down
Loading
Loading