|
| 1 | +.. _IK: |
| 2 | + |
| 3 | + |
| 4 | +Inverse Kinematics |
| 5 | +================== |
| 6 | + |
| 7 | + |
| 8 | +The Robotics Toolbox supports an extensive set of numerical inverse kinematics (IK) tools and we will demonstrate the different ways these IK tools can be interacted with in this document. |
| 9 | + |
| 10 | +For a **tutorial** on numerical IK, see `here <https://bit.ly/3ak5GDi>`_. |
| 11 | + |
| 12 | +Within the Toolbox, we have two sets of solvers: solvers written in C++ and solvers written in Python. However, within all of our solvers there are several common arguments: |
| 13 | + |
| 14 | +.. rubric:: Tep |
| 15 | + |
| 16 | +``Tep`` represent the desired end-effector pose. |
| 17 | + |
| 18 | +A note on the semantics of the above variable: |
| 19 | + |
| 20 | +* **T** represents an SE(3) (a homogeneous tranformation matrix in 3 dimensions, a 4x4 matrix) |
| 21 | +* *e* is short for end-effector referring to the end of the kinematic chain |
| 22 | +* *p* is short for prime or desired |
| 23 | +* Since there is no letter to the left of the **T**, the world or base reference frame is implied |
| 24 | + |
| 25 | +Therefore, ``Tep`` refers to the desired end-effector pose in the base robot frame represented as an SE(3). |
| 26 | + |
| 27 | +.. rubric:: ilimit |
| 28 | + |
| 29 | +The ``ilimit`` specifies how many iterations are allowed within a single search. After ``ilimit`` is reached, either, a new attempt is made or the IK solution has failed depending on ``slimit`` |
| 30 | + |
| 31 | +.. rubric:: slimit |
| 32 | + |
| 33 | +The ``slimit`` specifies how many searches are allowed before the problem is deemed unsolvable. The maximum number of iterations allowed is therefore ``ilimit`` x ``slimit``. By having ``slimit`` > 1, a global search is performed. Since finding a solution with numerical IK heavily depends on the initial choice of ``q0``, performing a global search where ``slimit`` >> 1 will provide a far greater chance of success. |
| 34 | + |
| 35 | +.. rubric:: q0 |
| 36 | + |
| 37 | +``q0`` is the inital joint coordinate vector. If ``q0`` is 1 dimensional (, ``n``), then ``q0`` is only used for the first attempt, after which a new random valid initial joint coordinate vector will be generated. If ``q0`` is 2 dimensional (``slimit``, ``n``), then the next vector within ``q0`` will be used for the next search. |
| 38 | + |
| 39 | +.. rubric:: tol |
| 40 | + |
| 41 | +``tol`` sets the error tolerance before the solution is deemed successful. The error is typically set by some quadratic error function |
| 42 | + |
| 43 | +.. math:: |
| 44 | +
|
| 45 | + E = \frac{1}{2} \vec{e}^{\top} \mat{W}_e \vec{e} |
| 46 | +
|
| 47 | +where :math:`\vec{e} \in \mathbb{R}^6` is the angle-axis error, and :math:`\mat{W}_e` assigns weights to Cartesian degrees-of-freedom |
| 48 | + |
| 49 | +.. rubric:: mask |
| 50 | + |
| 51 | +``mask`` is a (,6) array that sets :math:`\mat{W}_e` in error equation above. The vector has six elements that correspond to translation in X, Y and Z, and rotation about X, Y and Z respectively. The value can be 0 (for ignore) or above to assign a priority relative to other Cartesian DoF. |
| 52 | + |
| 53 | +For the case where the manipulator has fewer than 6 DoF the solution space has more dimensions than can be spanned by the manipulator joint coordinates. |
| 54 | + |
| 55 | +In this case we use the ``mask`` option where the ``mask`` vector specifies the Cartesian DOF that will be ignored in reaching a solution. The number of non-zero elements must equal the number of manipulator DOF. |
| 56 | + |
| 57 | +For example when using a 3 DOF manipulator tool orientation might be unimportant, in which case use the option ``mask=[1, 1, 1, 0, 0, 0]``. |
| 58 | + |
| 59 | +.. rubric:: joint_limits |
| 60 | + |
| 61 | +setting ``joint_limits = True`` will reject solutions with joint limit violations. Note that finding a solution with valid joint coordinates is likely to take longer than without. |
| 62 | + |
| 63 | +.. rubric:: Others |
| 64 | + |
| 65 | +There are other arguments which may be unique to the solver, so check the documentation of the solver you wish to use for a complete list and explanation of arguments. |
| 66 | + |
| 67 | +C++ Solvers |
| 68 | +----------- |
| 69 | + |
| 70 | +These solvers are written in high performance C++ and wrapped in Python methods. The methods are made available within the :py:class:`~roboticstoolbox.robot.ETS.ETS` and :py:class:`~roboticstoolbox.robot.Robot.Robot` classes. Being written in C++, these solvers are extraordinarily fast and typically take 30 to 90 µs. However, these solvers are hard to extend or modify. |
| 71 | + |
| 72 | +These methods have been written purely for speed so they do not contain the niceties of the Python alternative. For example, if you give the incorrect length for the ``q0`` vector, you could end up with a ``seg-fault`` or other undetermined behaviour. Therefore, when using these methods it is very important that you understand each of the parameters and the parameters passed are of the correct type and length. |
| 73 | + |
| 74 | +The C++ solvers return a tuple with the following members: |
| 75 | + |
| 76 | +============== ========= ===================================================================================================== |
| 77 | +Element Type Description |
| 78 | +============== ========= ===================================================================================================== |
| 79 | +``q`` `ndarray` The joint coordinates of the solution. Note that these will not be valid if failed to find a solution |
| 80 | +``success`` `bool` True if a valid solution was found |
| 81 | +``iterations`` `int` How many iterations were performed |
| 82 | +``searches`` `int` How many searches were performed |
| 83 | +``residual`` `float` The final error value from the cost function |
| 84 | +============== ========= ===================================================================================================== |
| 85 | + |
| 86 | +The C++ solvers can be identified as methods which start with ``ik_``. |
| 87 | + |
| 88 | +.. rubric:: ETS C++ IK Methods |
| 89 | + |
| 90 | +.. autosummary:: |
| 91 | + :toctree: stubs |
| 92 | + |
| 93 | + ~roboticstoolbox.robot.ETS.ETS.ik_LM |
| 94 | + ~roboticstoolbox.robot.ETS.ETS.ik_GN |
| 95 | + ~roboticstoolbox.robot.ETS.ETS.ik_NR |
| 96 | + |
| 97 | +.. rubric:: Robot C++ IK Methods |
| 98 | + |
| 99 | +.. autosummary:: |
| 100 | + :toctree: stubs |
| 101 | + |
| 102 | + ~roboticstoolbox.robot.Robot.Robot.ik_LM |
| 103 | + ~roboticstoolbox.robot.Robot.Robot.ik_GN |
| 104 | + ~roboticstoolbox.robot.Robot.Robot.ik_NR |
| 105 | + |
| 106 | +In the following example, we create a :py:class:`~roboticstoolbox.models.URDF.Panda` robot and one of the fast IK solvers available within the :py:class:`~roboticstoolbox.robot.Robot.Robot` class. |
| 107 | + |
| 108 | +.. runblock:: pycon |
| 109 | + |
| 110 | + >>> import roboticstoolbox as rtb |
| 111 | + >>> # Make a Panda robot |
| 112 | + >>> panda = rtb.models.Panda() |
| 113 | + >>> # Make a goal pose |
| 114 | + >>> Tep = panda.fkine([0, -0.3, 0, -2.2, 0, 2, 0.7854]) |
| 115 | + >>> # Solve the IK problem |
| 116 | + >>> panda.ik_LM(Tep) |
| 117 | + |
| 118 | +In the following example, we create a :py:class:`~roboticstoolbox.models.URDF.Panda` robot and and then get the :py:class:`~roboticstoolbox.robot.ETS.ETS` representation. Subsequently, we use one of the fast IK solvers available within the :py:class:`~roboticstoolbox.robot.ETS.ETS` class. |
| 119 | + |
| 120 | +.. runblock:: pycon |
| 121 | + |
| 122 | + >>> import roboticstoolbox as rtb |
| 123 | + >>> # Make a Panda robot |
| 124 | + >>> panda = rtb.models.Panda() |
| 125 | + >>> # Get the ETS |
| 126 | + >>> ets = panda.ets() |
| 127 | + >>> # Make a goal pose |
| 128 | + >>> Tep = ets.fkine([0, -0.3, 0, -2.2, 0, 2, 0.7854]) |
| 129 | + >>> # Solve the IK problem |
| 130 | + >>> ets.ik_LM(Tep) |
| 131 | + |
| 132 | + |
| 133 | + |
| 134 | + |
| 135 | + |
| 136 | +Python Solvers |
| 137 | +-------------- |
| 138 | + |
| 139 | +These solvers are Python classes which extend the abstract base class :py:class:`~roboticstoolbox.robot.IK.IKSolver` and the :py:meth:`~roboticstoolbox.robot.IK.IKSolver.solve` method returns an :py:class:`~roboticstoolbox.robot.IK.IKSolution`. These solvers are slow and will typically take 100 - 1000 ms. However, these solvers are easy to extend and modify. |
| 140 | + |
| 141 | +.. rubric:: The Abstract Base Class |
| 142 | + |
| 143 | +.. toctree:: |
| 144 | + :maxdepth: 1 |
| 145 | + |
| 146 | + iksolver |
| 147 | + |
| 148 | +The :py:class:`~roboticstoolbox.robot.IK.IKSolver` provides basic functionality for performing numerical IK. Superclasses can inherit this class and must implement the :py:meth:`~roboticstoolbox.robot.IK.IKSolver.solve` method. Additionally a superclass redefine any other methods necessary such as :py:meth:`~roboticstoolbox.robot.IK.IKSolver.error` to provide a custom error function. |
| 149 | + |
| 150 | +.. rubric:: The Solution DataClass |
| 151 | + |
| 152 | +.. toctree:: |
| 153 | + :maxdepth: 1 |
| 154 | + |
| 155 | + iksolution |
| 156 | + |
| 157 | +The :py:class:`~roboticstoolbox.robot.IK.IKSolution` is a :py:class:`dataclasses.dataclass` instance with the following members. |
| 158 | + |
| 159 | +============== ========= ===================================================================================================== |
| 160 | +Element Type Description |
| 161 | +============== ========= ===================================================================================================== |
| 162 | +``q`` `ndarray` The joint coordinates of the solution. Note that these will not be valid if failed to find a solution |
| 163 | +``success`` `bool` True if a valid solution was found |
| 164 | +``iterations`` `int` How many iterations were performed |
| 165 | +``searches`` `int` How many searches were performed |
| 166 | +``residual`` `float` The final error value from the cost function |
| 167 | +``reason`` `str` The reason the IK problem failed if applicable |
| 168 | +============== ========= ===================================================================================================== |
| 169 | + |
| 170 | +.. rubric:: The Implemented IK Solvers |
| 171 | + |
| 172 | +These solvers can be identified as a :py:class:`Class` starting with ``IK_``. |
| 173 | + |
| 174 | +.. toctree:: |
| 175 | + :maxdepth: 1 |
| 176 | + |
| 177 | + ik_lm |
| 178 | + ik_qp |
| 179 | + ik_gn |
| 180 | + ik_nr |
| 181 | + |
| 182 | +.. rubric:: Example |
| 183 | + |
| 184 | +In the following example, we create an IK Solver class and pass an :py:class:`~roboticstoolbox.robot.ETS.ETS` to it to solve the problem. This style may be preferable to experiments where you wish to compare the same solver on different robots. |
| 185 | + |
| 186 | +.. runblock:: pycon |
| 187 | + |
| 188 | + >>> import roboticstoolbox as rtb |
| 189 | + >>> # Make a Panda robot |
| 190 | + >>> panda = rtb.models.Panda() |
| 191 | + >>> # Get the ETS of the Panda |
| 192 | + >>> ets = panda.ets() |
| 193 | + >>> # Make an IK solver |
| 194 | + >>> solver = rtb.IK_LM() |
| 195 | + >>> # Make a goal pose |
| 196 | + >>> Tep = panda.fkine([0, -0.3, 0, -2.2, 0, 2, 0.7854]) |
| 197 | + >>> # Solve the IK problem |
| 198 | + >>> solver.solve(ets, Tep) |
| 199 | + |
| 200 | + |
| 201 | + |
| 202 | +.. IK Solvers Available with an ETS |
| 203 | +.. ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 204 | +
|
| 205 | +Additionally, these :py:class:`Class` based solvers have been implemented as methods within the :py:class:`~roboticstoolbox.robot.ETS.ETS` and :py:class:`~roboticstoolbox.robot.Robot.Robot` classes. The method names start with ``ikine_``. |
| 206 | + |
| 207 | + |
| 208 | +.. toctree: |
| 209 | + :caption: IK Solvers from an ETS |
| 210 | +
|
| 211 | +
|
| 212 | +.. rubric:: ETS Python IK Methods |
| 213 | + |
| 214 | + |
| 215 | +.. autosummary:: |
| 216 | + :toctree: stubs |
| 217 | + |
| 218 | + ~roboticstoolbox.robot.ETS.ETS.ikine_LM |
| 219 | + ~roboticstoolbox.robot.ETS.ETS.ikine_QP |
| 220 | + ~roboticstoolbox.robot.ETS.ETS.ikine_GN |
| 221 | + ~roboticstoolbox.robot.ETS.ETS.ikine_NR |
| 222 | + |
| 223 | + |
| 224 | +.. rubric:: Robot Python IK Methods |
| 225 | + |
| 226 | +.. autosummary:: |
| 227 | + :toctree: stubs |
| 228 | + |
| 229 | + ~roboticstoolbox.robot.Robot.Robot.ikine_LM |
| 230 | + ~roboticstoolbox.robot.Robot.Robot.ikine_QP |
| 231 | + ~roboticstoolbox.robot.Robot.Robot.ikine_GN |
| 232 | + ~roboticstoolbox.robot.Robot.Robot.ikine_NR |
| 233 | + |
| 234 | + |
| 235 | +.. rubric:: Example |
| 236 | + |
| 237 | +In the following example, we create a :py:class:`~roboticstoolbox.models.URDF.Panda` robot and one of the IK solvers available within the :py:class:`~roboticstoolbox.robot.Robot.Robot` class. This style is far more convenient than the above example. |
| 238 | + |
| 239 | +.. runblock:: pycon |
| 240 | + |
| 241 | + >>> import roboticstoolbox as rtb |
| 242 | + >>> # Make a Panda robot |
| 243 | + >>> panda = rtb.models.Panda() |
| 244 | + >>> # Make a goal pose |
| 245 | + >>> Tep = panda.fkine([0, -0.3, 0, -2.2, 0, 2, 0.7854]) |
| 246 | + >>> # Solve the IK problem |
| 247 | + >>> panda.ikine_LM(Tep) |
| 248 | + |
| 249 | +In the following example, we create a :py:class:`~roboticstoolbox.models.URDF.Panda` robot and and then get the :py:class:`~roboticstoolbox.robot.ETS.ETS` representation. Subsequently, we use one of the IK solvers available within the :py:class:`~roboticstoolbox.robot.ETS.ETS` class. |
| 250 | + |
| 251 | +.. runblock:: pycon |
| 252 | + |
| 253 | + >>> import roboticstoolbox as rtb |
| 254 | + >>> # Make a Panda robot |
| 255 | + >>> panda = rtb.models.Panda() |
| 256 | + >>> # Get the ETS |
| 257 | + >>> ets = panda.ets() |
| 258 | + >>> # Make a goal pose |
| 259 | + >>> Tep = ets.fkine([0, -0.3, 0, -2.2, 0, 2, 0.7854]) |
| 260 | + >>> # Solve the IK problem |
| 261 | + >>> ets.ikine_LM(Tep) |
0 commit comments