Skip to content

Commit 71df868

Browse files
Adds null-space control option within OperationSpaceController (#1557)
# Description This PR adds an option to enable null-space control within `OperationSpaceController` (following the discussions in #913). ## Details Currently, `OperationSpaceController` controls only the task space, which results in joint movements within the null-space of redundant robotic manipulators. In general, it is desirable to have some control over the robot null-space, e.g., to prevent the joints from going near their limits. Hence, the PR adds the following: - An optional nullspace (position) control integrated into `OperationSpaceController`. This controller attracts the robot joints to provided targets whereas possible, in parallel to the task-space target. - Test cases for `OperationSpaceController` that use null-space control. - Updates to the related tutorial script and documentation to use and describe null-space control. - Integration of (optional) null-space control to `OperationSpaceControllerAction` with predefined joint targets, e.g., default joint positions, joint centers, zero joint position. - Integration of null-space control to `"Isaac-Reach-Franka-OSC-v0"` manager-based environment. Null-space control utilizes either the dynamically consistent Jacobian inverse or the Moore–Penrose inverse, depending on whether the full inertia matrix is available. ## Type of change - New feature (non-breaking change which adds functionality) - This change requires a documentation update ## Checklist - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there --------- Signed-off-by: Özhan Özen <[email protected]> Co-authored-by: Kelly Guo <[email protected]>
1 parent 874b7b6 commit 71df868

File tree

13 files changed

+412
-38
lines changed

13 files changed

+412
-38
lines changed

docs/source/tutorials/05_controllers/run_osc.rst

Lines changed: 18 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -86,14 +86,26 @@ If desired, the inertial coupling between the translational and rotational axes
8686
If it is desired to include the gravity compensation in the operational space command, the ``gravity_compensation``
8787
should be set to ``True``.
8888

89+
A final consideration regarding the operational space control is what to do with the null-space of redundant robots.
90+
The null-space is the subspace of the joint space that does not affect the task space coordinates. If nothing is done
91+
to control the null-space, the robot joints will float without moving the end-effector. This might be undesired (e.g.,
92+
the robot joints might get close to their limits), and one might want to control the robot behaviour within its
93+
null-space. One way to do is to set ``nullspace_control`` to ``"position"`` (by default it is ``"none"``) which
94+
integrates a null-space PD controller to attract the robot joints to desired targets without affecting the task
95+
space. The behaviour of this null-space controller can be defined using the ``nullspace_stiffness`` and
96+
``nullspace_damping_ratio`` arguments. Please note that theoretical decoupling of the null-space and task space
97+
accelerations is only possible when ``inertial_dynamics_decoupling`` is set to ``True`` and
98+
``partial_inertial_dynamics_decoupling`` is set to ``False``.
99+
89100
The included OSC implementation performs the computation in a batched format and uses PyTorch operations.
90101

91102
In this tutorial, we will use ``"pose_abs"`` for controlling the motion in all axes except the z-axis and
92103
``"wrench_abs"`` for controlling the force in the z-axis. Moreover, we will include the full inertia decoupling in
93104
the motion control and not include the gravity compensation, as the gravity is disabled from the robot configuration.
94-
Finally, we set the impedance mode to ``"variable_kp"`` to dynamically change the stiffness values
105+
We set the impedance mode to ``"variable_kp"`` to dynamically change the stiffness values
95106
(``motion_damping_ratio_task`` is set to ``1``: the kd values adapt according to kp values to maintain a critically
96-
damped response).
107+
damped response). Finally, ``nullspace_control`` is set to use ``"position"`` where the joint set points are provided
108+
to be the center of the joint position limits.
97109

98110
.. literalinclude:: ../../../../source/standalone/tutorials/05_controllers/run_osc.py
99111
:language: python
@@ -104,13 +116,14 @@ Updating the states of the robot
104116
--------------------------------------------
105117

106118
The OSC implementation is a computation-only class. Thus, it expects the user to provide the necessary information
107-
about the robot. This includes the robot's Jacobian matrix, mass/inertia matrix, end-effector pose, velocity, and
108-
contact force, all in the root frame. Moreover, the user should provide gravity compensation vector, if desired.
119+
about the robot. This includes the robot's Jacobian matrix, mass/inertia matrix, end-effector pose, velocity, contact
120+
force (all in the root frame), and finally, the joint positions and velocities. Moreover, the user should provide
121+
gravity compensation vector and null-space joint position targets if required.
109122

110123
.. literalinclude:: ../../../../source/standalone/tutorials/05_controllers/run_osc.py
111124
:language: python
112125
:start-at: # Update robot states
113-
:end-before: return jacobian_b, mass_matrix, gravity, ee_pose_b, ee_vel_b, root_pose_w, ee_pose_w, ee_force_b
126+
:end-before: # Update the target commands
114127

115128

116129
Computing robot command

source/extensions/omni.isaac.lab/config/extension.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
[package]
22

33
# Note: Semantic Versioning is used: https://semver.org/
4-
version = "0.30.0"
4+
version = "0.30.1"
55

66
# Description
77
title = "Isaac Lab framework for Robot Learning"

source/extensions/omni.isaac.lab/docs/CHANGELOG.rst

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,20 @@
11
Changelog
22
---------
33

4+
0.30.1 (2024-12-17)
5+
~~~~~~~~~~~~~~~~~~~
6+
7+
Added
8+
^^^^^
9+
10+
* Added null-space (position) control option to :class:`omni.isaac.lab.controllers.OperationalSpaceController`.
11+
* Added test cases that uses null-space control for :class:`omni.isaac.lab.controllers.OperationalSpaceController`.
12+
* Added information regarding null-space control to the tutorial script and documentation of
13+
:class:`omni.isaac.lab.controllers.OperationalSpaceController`.
14+
* Added arguments to set specific null-space joint position targets within
15+
:class:`omni.isaac.lab.envs.mdp.actions.OperationalSpaceControllerAction` class.
16+
17+
418
0.30.0 (2024-12-16)
519
~~~~~~~~~~~~~~~~~~~
620

source/extensions/omni.isaac.lab/omni/isaac/lab/controllers/operational_space.py

Lines changed: 104 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -77,11 +77,15 @@ def __init__(self, cfg: OperationalSpaceControllerCfg, num_envs: int, device: st
7777
self._selection_matrix_force_b = torch.zeros_like(self._selection_matrix_force_task)
7878
# -- commands
7979
self._task_space_target_task = torch.zeros(self.num_envs, self.target_dim, device=self._device)
80-
# -- buffers for motion/force control
80+
# -- Placeholders for motion/force control
8181
self.desired_ee_pose_task = None
8282
self.desired_ee_pose_b = None
8383
self.desired_ee_wrench_task = None
8484
self.desired_ee_wrench_b = None
85+
# -- buffer for operational space mass matrix
86+
self._os_mass_matrix_b = torch.zeros(self.num_envs, 6, 6, device=self._device)
87+
# -- Placeholder for the inverse of joint space mass matrix
88+
self._mass_matrix_inv = None
8589
# -- motion control gains
8690
self._motion_p_gains_task = torch.diag_embed(
8791
torch.ones(self.num_envs, 6, device=self._device)
@@ -127,6 +131,14 @@ def __init__(self, cfg: OperationalSpaceControllerCfg, num_envs: int, device: st
127131
# -- end-effector contact wrench
128132
self._ee_contact_wrench_b = torch.zeros(self.num_envs, 6, device=self._device)
129133

134+
# -- buffers for null-space control gains
135+
self._nullspace_p_gain = torch.tensor(self.cfg.nullspace_stiffness, dtype=torch.float, device=self._device)
136+
self._nullspace_d_gain = (
137+
2
138+
* torch.sqrt(self._nullspace_p_gain)
139+
* torch.tensor(self.cfg.nullspace_damping_ratio, dtype=torch.float, device=self._device)
140+
)
141+
130142
"""
131143
Properties.
132144
"""
@@ -338,6 +350,9 @@ def compute(
338350
current_ee_force_b: torch.Tensor | None = None,
339351
mass_matrix: torch.Tensor | None = None,
340352
gravity: torch.Tensor | None = None,
353+
current_joint_pos: torch.Tensor | None = None,
354+
current_joint_vel: torch.Tensor | None = None,
355+
nullspace_joint_pos_target: torch.Tensor | None = None,
341356
) -> torch.Tensor:
342357
"""Performs inference with the controller.
343358
@@ -348,19 +363,33 @@ def compute(
348363
(``num_envs``, 7), which contains the position and quaternion ``(w, x, y, z)``. Defaults to ``None``.
349364
current_ee_vel_b: The current end-effector velocity in root frame. It is a tensor of shape
350365
(``num_envs``, 6), which contains the linear and angular velocities. Defaults to None.
351-
current_ee_force_b: The current external force on the end-effector in root frame.
352-
It is a tensor of shape (``num_envs``, 3), which contains the linear force. Defaults to ``None``.
366+
current_ee_force_b: The current external force on the end-effector in root frame. It is a tensor of
367+
shape (``num_envs``, 3), which contains the linear force. Defaults to ``None``.
353368
mass_matrix: The joint-space mass/inertia matrix. It is a tensor of shape (``num_envs``, ``num_DoF``,
354-
``num_DoF``). Defaults to ``None``.
369+
``num_DoF``). Defaults to ``None``.
355370
gravity: The joint-space gravity vector. It is a tensor of shape (``num_envs``, ``num_DoF``). Defaults
356-
to ``None``.
371+
to ``None``.
372+
current_joint_pos: The current joint positions. It is a tensor of shape (``num_envs``, ``num_DoF``).
373+
Defaults to ``None``.
374+
current_joint_vel: The current joint velocities. It is a tensor of shape (``num_envs``, ``num_DoF``).
375+
Defaults to ``None``.
376+
nullspace_joint_pos_target: The target joint positions the null space controller is trying to enforce, when
377+
possible. It is a tensor of shape (``num_envs``, ``num_DoF``).
357378
358379
Raises:
359380
ValueError: When motion-control is enabled but the current end-effector pose or velocity is not provided.
360381
ValueError: When inertial dynamics decoupling is enabled but the mass matrix is not provided.
361382
ValueError: When the current end-effector pose is not provided for the ``pose_rel`` command.
362383
ValueError: When closed-loop force control is enabled but the current end-effector force is not provided.
363384
ValueError: When gravity compensation is enabled but the gravity vector is not provided.
385+
ValueError: When null-space control is enabled but the system is not redundant.
386+
ValueError: When dynamically consistent pseudo-inverse is enabled but the mass matrix inverse is not
387+
provided.
388+
ValueError: When null-space control is enabled but the current joint positions and velocities are not
389+
provided.
390+
ValueError: When target joint positions are provided for null-space control but their dimensions do not
391+
match the current joint positions.
392+
ValueError: When an invalid null-space control method is provided.
364393
365394
Returns:
366395
Tensor: The joint efforts computed by the controller. It is a tensor of shape (``num_envs``, ``num_DoF``).
@@ -398,23 +427,21 @@ def compute(
398427
if mass_matrix is None:
399428
raise ValueError("Mass matrix is required for inertial decoupling.")
400429
# Compute operational space mass matrix
401-
mass_matrix_inv = torch.inverse(mass_matrix)
430+
self._mass_matrix_inv = torch.inverse(mass_matrix)
402431
if self.cfg.partial_inertial_dynamics_decoupling:
403-
# Create a zero tensor representing the mass matrix, to fill in the non-zero elements later
404-
os_mass_matrix = torch.zeros(self.num_envs, 6, 6, device=self._device)
405432
# Fill in the translational and rotational parts of the inertia separately, ignoring their coupling
406-
os_mass_matrix[:, 0:3, 0:3] = torch.inverse(
407-
jacobian_b[:, 0:3] @ mass_matrix_inv @ jacobian_b[:, 0:3].mT
433+
self._os_mass_matrix_b[:, 0:3, 0:3] = torch.inverse(
434+
jacobian_b[:, 0:3] @ self._mass_matrix_inv @ jacobian_b[:, 0:3].mT
408435
)
409-
os_mass_matrix[:, 3:6, 3:6] = torch.inverse(
410-
jacobian_b[:, 3:6] @ mass_matrix_inv @ jacobian_b[:, 3:6].mT
436+
self._os_mass_matrix_b[:, 3:6, 3:6] = torch.inverse(
437+
jacobian_b[:, 3:6] @ self._mass_matrix_inv @ jacobian_b[:, 3:6].mT
411438
)
412439
else:
413440
# Calculate the operational space mass matrix fully accounting for the couplings
414-
os_mass_matrix = torch.inverse(jacobian_b @ mass_matrix_inv @ jacobian_b.mT)
441+
self._os_mass_matrix_b[:] = torch.inverse(jacobian_b @ self._mass_matrix_inv @ jacobian_b.mT)
415442
# (Generalized) operational space command forces
416443
# F = (J M^(-1) J^T)^(-1) * \ddot(x_des) = M_task * \ddot(x_des)
417-
os_command_forces_b = os_mass_matrix @ des_ee_acc_b
444+
os_command_forces_b = self._os_mass_matrix_b @ des_ee_acc_b
418445
else:
419446
# Task-space impedance control: command forces = \ddot(x_des).
420447
# Please note that the definition of task-space impedance control varies in literature.
@@ -455,4 +482,67 @@ def compute(
455482
# add gravity compensation
456483
joint_efforts += gravity
457484

485+
# Add null-space control
486+
# -- Free null-space control
487+
if self.cfg.nullspace_control == "none":
488+
# No additional control is applied in the null space.
489+
pass
490+
else:
491+
# Check if the system is redundant
492+
if num_DoF <= 6:
493+
raise ValueError("Null-space control is only applicable for redundant manipulators.")
494+
495+
# Calculate the pseudo-inverse of the Jacobian
496+
if self.cfg.inertial_dynamics_decoupling and not self.cfg.partial_inertial_dynamics_decoupling:
497+
# Dynamically consistent pseudo-inverse allows decoupling of null space and task space
498+
if self._mass_matrix_inv is None or mass_matrix is None:
499+
raise ValueError("Mass matrix inverse is required for dynamically consistent pseudo-inverse")
500+
jacobian_pinv_transpose = self._os_mass_matrix_b @ jacobian_b @ self._mass_matrix_inv
501+
else:
502+
# Moore-Penrose pseudo-inverse if full inertia matrix is not available (e.g., no/partial decoupling)
503+
jacobian_pinv_transpose = torch.pinverse(jacobian_b).mT
504+
505+
# Calculate the null-space projector
506+
nullspace_jacobian_transpose = (
507+
torch.eye(n=num_DoF, device=self._device) - jacobian_b.mT @ jacobian_pinv_transpose
508+
)
509+
510+
# Null space position control
511+
if self.cfg.nullspace_control == "position":
512+
513+
# Check if the current joint positions and velocities are provided
514+
if current_joint_pos is None or current_joint_vel is None:
515+
raise ValueError("Current joint positions and velocities are required for null-space control.")
516+
517+
# Calculate the joint errors for nullspace position control
518+
if nullspace_joint_pos_target is None:
519+
nullspace_joint_pos_target = torch.zeros_like(current_joint_pos)
520+
# Check if the dimensions of the target nullspace joint positions match the current joint positions
521+
elif nullspace_joint_pos_target.shape != current_joint_pos.shape:
522+
raise ValueError(
523+
f"The target nullspace joint positions shape '{nullspace_joint_pos_target.shape}' does not"
524+
f"match the current joint positions shape '{current_joint_pos.shape}'."
525+
)
526+
527+
joint_pos_error_nullspace = nullspace_joint_pos_target - current_joint_pos
528+
joint_vel_error_nullspace = -current_joint_vel
529+
530+
# Calculate the desired joint accelerations
531+
joint_acc_nullspace = (
532+
self._nullspace_p_gain * joint_pos_error_nullspace
533+
+ self._nullspace_d_gain * joint_vel_error_nullspace
534+
).unsqueeze(-1)
535+
536+
# Calculate the projected torques in null-space
537+
if mass_matrix is not None:
538+
tau_null = (nullspace_jacobian_transpose @ mass_matrix @ joint_acc_nullspace).squeeze(-1)
539+
else:
540+
tau_null = nullspace_jacobian_transpose @ joint_acc_nullspace
541+
542+
# Add the null-space joint efforts to the total joint efforts
543+
joint_efforts += tau_null
544+
545+
else:
546+
raise ValueError(f"Invalid null-space control method: {self.cfg.nullspace_control}.")
547+
458548
return joint_efforts

source/extensions/omni.isaac.lab/omni/isaac/lab/controllers/operational_space_cfg.py

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -75,3 +75,16 @@ class OperationalSpaceControllerCfg:
7575
Note: since only the linear forces could be measured at the moment,
7676
only the first three elements are used for the feedback loop.
7777
"""
78+
79+
nullspace_control: str = "none"
80+
"""The null space control method for redundant manipulators: ``"none"``, ``"position"``.
81+
82+
Note: ``"position"`` is used to drive the redundant manipulator to zero configuration by default. If
83+
``target_joint_pos`` is provided in the ``compute()`` method, it will be driven to this configuration.
84+
"""
85+
86+
nullspace_stiffness: float = 10.0
87+
"""The stiffness for null space control."""
88+
89+
nullspace_damping_ratio: float = 1.0
90+
"""The damping ratio for null space control."""

source/extensions/omni.isaac.lab/omni/isaac/lab/envs/mdp/actions/actions_cfg.py

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -303,3 +303,10 @@ class OffsetCfg:
303303

304304
damping_ratio_scale: float = 1.0
305305
"""Scale factor for the damping ratio commands. Defaults to 1.0."""
306+
307+
nullspace_joint_pos_target: str = "none"
308+
"""The joint targets for the null-space control: ``"none"``, ``"zero"``, ``"default"``, ``"center"``.
309+
310+
Note: Functional only when ``nullspace_control`` is set to ``"position"`` within the
311+
``OperationalSpaceControllerCfg``.
312+
"""

0 commit comments

Comments
 (0)