@@ -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
0 commit comments