|
| 1 | +# Copyright 2017-2018 The dm_control Authors. |
| 2 | +# |
| 3 | +# Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +# you may not use this file except in compliance with the License. |
| 5 | +# You may obtain a copy of the License at |
| 6 | +# |
| 7 | +# http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +# |
| 9 | +# Unless required by applicable law or agreed to in writing, software |
| 10 | +# distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +# See the License for the specific language governing permissions and |
| 13 | +# limitations under the License. |
| 14 | +# ============================================================================ |
| 15 | + |
| 16 | +"""Functions for computing inverse kinematics on MuJoCo models.""" |
| 17 | + |
| 18 | +from __future__ import absolute_import |
| 19 | +from __future__ import division |
| 20 | +from __future__ import print_function |
| 21 | + |
| 22 | +import collections |
| 23 | + |
| 24 | +from absl import logging |
| 25 | +from dm_control.mujoco.wrapper.mjbindings import mjlib |
| 26 | +import numpy as np |
| 27 | +from six.moves import range |
| 28 | + |
| 29 | + |
| 30 | +_INVALID_JOINT_NAMES_TYPE = ( |
| 31 | + '`joint_names` must be either None, a list, a tuple, or a numpy array; ' |
| 32 | + 'got {}.') |
| 33 | +_REQUIRE_TARGET_POS_OR_QUAT = ( |
| 34 | + 'At least one of `target_pos` or `target_quat` must be specified.') |
| 35 | + |
| 36 | +IKResult = collections.namedtuple( |
| 37 | + 'IKResult', ['qpos', 'err_norm', 'steps', 'success']) |
| 38 | + |
| 39 | + |
| 40 | +def qpos_from_site_pose(physics, |
| 41 | + site_name, |
| 42 | + target_pos=None, |
| 43 | + target_quat=None, |
| 44 | + joint_names=None, |
| 45 | + tol=1e-14, |
| 46 | + rot_weight=1.0, |
| 47 | + regularization_threshold=0.1, |
| 48 | + regularization_strength=3e-2, |
| 49 | + max_update_norm=2.0, |
| 50 | + progress_thresh=20.0, |
| 51 | + max_steps=100, |
| 52 | + inplace=False): |
| 53 | + """Find joint positions that satisfy a target site position and/or rotation. |
| 54 | +
|
| 55 | + Args: |
| 56 | + physics: A `mujoco.Physics` instance. |
| 57 | + site_name: A string specifying the name of the target site. |
| 58 | + target_pos: A (3,) numpy array specifying the desired Cartesian position of |
| 59 | + the site, or None if the position should be unconstrained (default). |
| 60 | + One or both of `target_pos` or `target_quat` must be specified. |
| 61 | + target_quat: A (4,) numpy array specifying the desired orientation of the |
| 62 | + site as a quarternion, or None if the orientation should be unconstrained |
| 63 | + (default). One or both of `target_pos` or `target_quat` must be specified. |
| 64 | + joint_names: (optional) A list, tuple or numpy array specifying the names of |
| 65 | + one or more joints that can be manipulated in order to achieve the target |
| 66 | + site pose. If None (default), all joints may be manipulated. |
| 67 | + tol: (optional) Precision goal for `qpos` (the maximum value of `err_norm` |
| 68 | + in the stopping criterion). |
| 69 | + rot_weight: (optional) Determines the weight given to rotational error |
| 70 | + relative to translational error. |
| 71 | + regularization_threshold: (optional) L2 regularization will be used when |
| 72 | + inverting the Jacobian whilst `err_norm` is greater than this value. |
| 73 | + regularization_strength: (optional) Coefficient of the quadratic penalty |
| 74 | + on joint movements. |
| 75 | + max_update_norm: (optional) The maximum L2 norm of the update applied to |
| 76 | + the joint positions on each iteration. The update vector will be scaled |
| 77 | + such that its magnitude never exceeds this value. |
| 78 | + progress_thresh: (optional) If `err_norm` divided by the magnitude of the |
| 79 | + joint position update is greater than this value then the optimization |
| 80 | + will terminate prematurely. This is a useful heuristic to avoid getting |
| 81 | + stuck in local minima. |
| 82 | + max_steps: (optional) The maximum number of iterations to perform. |
| 83 | + inplace: (optional) If True, `physics.data` will be modified in place. |
| 84 | + Default value is False, i.e. a copy of `physics.data` will be made. |
| 85 | +
|
| 86 | + Returns: |
| 87 | + An `IKResult` namedtuple with the following fields: |
| 88 | + qpos: An (nq,) numpy array of joint positions. |
| 89 | + err_norm: A float, the weighted sum of L2 norms for the residual |
| 90 | + translational and rotational errors. |
| 91 | + steps: An int, the number of iterations that were performed. |
| 92 | + success: Boolean, True if we converged on a solution within `max_steps`, |
| 93 | + False otherwise. |
| 94 | +
|
| 95 | + Raises: |
| 96 | + ValueError: If both `target_pos` and `target_quat` are None, or if |
| 97 | + `joint_names` has an invalid type. |
| 98 | + """ |
| 99 | + |
| 100 | + dtype = physics.data.qpos.dtype |
| 101 | + |
| 102 | + if target_pos is not None and target_quat is not None: |
| 103 | + jac = np.empty((6, physics.model.nv), dtype=dtype) |
| 104 | + err = np.empty(6, dtype=dtype) |
| 105 | + jac_pos, jac_rot = jac[:3], jac[3:] |
| 106 | + err_pos, err_rot = err[:3], err[3:] |
| 107 | + else: |
| 108 | + jac = np.empty((3, physics.model.nv), dtype=dtype) |
| 109 | + err = np.empty(3, dtype=dtype) |
| 110 | + if target_pos is not None: |
| 111 | + jac_pos, jac_rot = jac, None |
| 112 | + err_pos, err_rot = err, None |
| 113 | + elif target_quat is not None: |
| 114 | + jac_pos, jac_rot = None, jac |
| 115 | + err_pos, err_rot = None, err |
| 116 | + else: |
| 117 | + raise ValueError(_REQUIRE_TARGET_POS_OR_QUAT) |
| 118 | + |
| 119 | + update_nv = np.zeros(physics.model.nv, dtype=dtype) |
| 120 | + |
| 121 | + if target_quat is not None: |
| 122 | + site_xquat = np.empty(4, dtype=dtype) |
| 123 | + neg_site_xquat = np.empty(4, dtype=dtype) |
| 124 | + err_rot_quat = np.empty(4, dtype=dtype) |
| 125 | + |
| 126 | + if not inplace: |
| 127 | + physics = physics.copy(share_model=True) |
| 128 | + |
| 129 | + # Ensure that the Cartesian position of the site is up to date. |
| 130 | + mjlib.mj_fwdPosition(physics.model.ptr, physics.data.ptr) |
| 131 | + |
| 132 | + # Convert site name to index. |
| 133 | + site_id = physics.model.name2id(site_name, 'site') |
| 134 | + |
| 135 | + # These are views onto the underlying MuJoCo buffers. mj_fwdPosition will |
| 136 | + # update them in place, so we can avoid indexing overhead in the main loop. |
| 137 | + site_xpos = physics.named.data.site_xpos[site_name] |
| 138 | + site_xmat = physics.named.data.site_xmat[site_name] |
| 139 | + |
| 140 | + # This is an index into the rows of `update` and the columns of `jac` |
| 141 | + # that selects DOFs associated with joints that we are allowed to manipulate. |
| 142 | + if joint_names is None: |
| 143 | + dof_indices = slice(None) # Update all DOFs. |
| 144 | + elif isinstance(joint_names, (list, np.ndarray, tuple)): |
| 145 | + if isinstance(joint_names, tuple): |
| 146 | + joint_names = list(joint_names) |
| 147 | + # Find the indices of the DOFs belonging to each named joint. Note that |
| 148 | + # these are not necessarily the same as the joint IDs, since a single joint |
| 149 | + # may have >1 DOF (e.g. ball joints). |
| 150 | + indexer = physics.named.model.dof_jntid.axes.row |
| 151 | + # `dof_jntid` is an `(nv,)` array indexed by joint name. We use its row |
| 152 | + # indexer to map each joint name to the indices of its corresponding DOFs. |
| 153 | + dof_indices = indexer.convert_key_item(joint_names) |
| 154 | + else: |
| 155 | + raise ValueError(_INVALID_JOINT_NAMES_TYPE.format(type(joint_names))) |
| 156 | + |
| 157 | + steps = 0 |
| 158 | + success = False |
| 159 | + |
| 160 | + for steps in range(max_steps): |
| 161 | + |
| 162 | + err_norm = 0.0 |
| 163 | + |
| 164 | + if target_pos is not None: |
| 165 | + # Translational error. |
| 166 | + err_pos[:] = target_pos - site_xpos |
| 167 | + err_norm += np.linalg.norm(err_pos) |
| 168 | + if target_quat is not None: |
| 169 | + # Rotational error. |
| 170 | + mjlib.mju_mat2Quat(site_xquat, site_xmat) |
| 171 | + mjlib.mju_negQuat(neg_site_xquat, site_xquat) |
| 172 | + mjlib.mju_mulQuat(err_rot_quat, target_quat, neg_site_xquat) |
| 173 | + mjlib.mju_quat2Vel(err_rot, err_rot_quat, 1) |
| 174 | + err_norm += np.linalg.norm(err_rot) * rot_weight |
| 175 | + |
| 176 | + if err_norm < tol: |
| 177 | + logging.debug('Converged after %i steps: err_norm=%3g', steps, err_norm) |
| 178 | + success = True |
| 179 | + break |
| 180 | + else: |
| 181 | + # TODO(b/112141670): Generalize this to other entities besides sites. |
| 182 | + mjlib.mj_jacSite( |
| 183 | + physics.model.ptr, physics.data.ptr, jac_pos, jac_rot, site_id) |
| 184 | + jac_joints = jac[:, dof_indices] |
| 185 | + |
| 186 | + # TODO(b/112141592): This does not take joint limits into consideration. |
| 187 | + reg_strength = ( |
| 188 | + regularization_strength if err_norm > regularization_threshold |
| 189 | + else 0.0) |
| 190 | + update_joints = nullspace_method( |
| 191 | + jac_joints, err, regularization_strength=reg_strength) |
| 192 | + |
| 193 | + update_norm = np.linalg.norm(update_joints) |
| 194 | + |
| 195 | + # Check whether we are still making enough progress, and halt if not. |
| 196 | + progress_criterion = err_norm / update_norm |
| 197 | + if progress_criterion > progress_thresh: |
| 198 | + logging.debug('Step %2i: err_norm / update_norm (%3g) > ' |
| 199 | + 'tolerance (%3g). Halting due to insufficient progress', |
| 200 | + steps, progress_criterion, progress_thresh) |
| 201 | + break |
| 202 | + |
| 203 | + if update_norm > max_update_norm: |
| 204 | + update_joints *= max_update_norm / update_norm |
| 205 | + |
| 206 | + # Write the entries for the specified joints into the full `update_nv` |
| 207 | + # vector. |
| 208 | + update_nv[dof_indices] = update_joints |
| 209 | + |
| 210 | + # Update `physics.qpos`, taking quaternions into account. |
| 211 | + mjlib.mj_integratePos(physics.model.ptr, physics.data.qpos, update_nv, 1) |
| 212 | + |
| 213 | + # Compute the new Cartesian position of the site. |
| 214 | + mjlib.mj_fwdPosition(physics.model.ptr, physics.data.ptr) |
| 215 | + |
| 216 | + logging.debug('Step %2i: err_norm=%-10.3g update_norm=%-10.3g', |
| 217 | + steps, err_norm, update_norm) |
| 218 | + |
| 219 | + if not success and steps == max_steps - 1: |
| 220 | + logging.warning('Failed to converge after %i steps: err_norm=%3g', |
| 221 | + steps, err_norm) |
| 222 | + |
| 223 | + if not inplace: |
| 224 | + # Our temporary copy of physics.data is about to go out of scope, and when |
| 225 | + # it does the underlying mjData pointer will be freed and physics.data.qpos |
| 226 | + # will be a view onto a block of deallocated memory. We therefore need to |
| 227 | + # make a copy of physics.data.qpos while physics.data is still alive. |
| 228 | + qpos = physics.data.qpos.copy() |
| 229 | + else: |
| 230 | + # If we're modifying physics.data in place then it's fine to return a view. |
| 231 | + qpos = physics.data.qpos |
| 232 | + |
| 233 | + return IKResult(qpos=qpos, err_norm=err_norm, steps=steps, success=success) |
| 234 | + |
| 235 | + |
| 236 | +def nullspace_method(jac_joints, delta, regularization_strength=0.0): |
| 237 | + """Calculates the joint velocities to achieve a specified end effector delta. |
| 238 | +
|
| 239 | + Args: |
| 240 | + jac_joints: The Jacobian of the end effector with respect to the joints. A |
| 241 | + numpy array of shape `(ndelta, nv)`, where `ndelta` is the size of `delta` |
| 242 | + and `nv` is the number of degrees of freedom. |
| 243 | + delta: The desired end-effector delta. A numpy array of shape `(3,)` or |
| 244 | + `(6,)` containing either position deltas, rotation deltas, or both. |
| 245 | + regularization_strength: (optional) Coefficient of the quadratic penalty |
| 246 | + on joint movements. Default is zero, i.e. no regularization. |
| 247 | +
|
| 248 | + Returns: |
| 249 | + An `(nv,)` numpy array of joint velocities. |
| 250 | +
|
| 251 | + Reference: |
| 252 | + Buss, S. R. S. (2004). Introduction to inverse kinematics with jacobian |
| 253 | + transpose, pseudoinverse and damped least squares methods. |
| 254 | + https://www.math.ucsd.edu/~sbuss/ResearchWeb/ikmethods/iksurvey.pdf |
| 255 | + """ |
| 256 | + hess_approx = jac_joints.T.dot(jac_joints) |
| 257 | + joint_delta = jac_joints.T.dot(delta) |
| 258 | + if regularization_strength > 0: |
| 259 | + # L2 regularization |
| 260 | + hess_approx += np.eye(hess_approx.shape[0]) * regularization_strength |
| 261 | + return np.linalg.solve(hess_approx, joint_delta) |
| 262 | + else: |
| 263 | + return np.linalg.lstsq(hess_approx, joint_delta)[0] |
0 commit comments