Robot.ik_GN
- Robot.ik_GN(Tep, end=None, start=None, q0=None, ilimit=30, slimit=100, tol=1e-06, mask=None, joint_limits=True, pinv=True, pinv_damping=0.0)
Fast numerical inverse kinematics by Gauss-Newton optimization
sol = ets.ik_GN(Tep)
are the joint coordinates (n) corresponding to the robot end-effector poseTep
which is anSE3
orndarray
object. This method can be used for robots with any number of degrees of freedom. This is a fast solver implemented in C++.See the Inverse Kinematics Docs Page for more details and for a tutorial on numerical IK, see here.
Note
When using this method with redundant robots (>6 DoF),
pinv
must be set toTrue
- Parameters:
Tep (
Union
[ndarray
,SE3
]) – The desired end-effector pose or pose trajectoryend (
Union
[str
,Link
,Gripper
,None
]) – the link considered as the end-effectorstart (
Union
[str
,Link
,Gripper
,None
]) – the link considered as the base frame, defaults to the robots’s base frameq0 (
Optional
[ndarray
]) – initial joint configuration (default to random valid joint configuration contrained by the joint limits of the robot)ilimit (
int
) – maximum number of iterations per searchslimit (
int
) – maximum number of search attemptstol (
float
) – final error tolerancemask (
Optional
[ndarray
]) – a mask vector which weights the end-effector error priority. Corresponds to translation in X, Y and Z and rotation about X, Y and Z respectivelyjoint_limits (
bool
) – constrain the solution to being within the joint limits of the robot (reject solution with invalid joint configurations and perfrom another search up to the slimit)pinv (
int
) – Use the psuedo-inverse instad of the normal matrix inversepinv_damping (
float
) – Damping factor for the psuedo-inverse
- Return type:
- Returns:
sol – tuple (q, success, iterations, searches, residual)
The return value
sol
is a tuple with elements============ ========== ===============================================
Element Type Description
============ ========== ===============================================
q
ndarray(n) joint coordinates in units of radians or metressuccess
int whether a solution was founditerations
int total number of iterationssearches
int total number of searchesresidual
float final value of cost function============ ========== ===============================================
If
success == 0
theq
values will be valid numbers, but thesolution will be in error. The amount of error is indicated by
the
residual
.
Synopsis
Each iteration uses the Gauss-Newton optimisation method
\[\begin{split}\vec{q}_{k+1} &= \vec{q}_k + \left( {\mat{J}(\vec{q}_k)}^\top \mat{W}_e \ {\mat{J}(\vec{q}_k)} \right)^{-1} \bf{g}_k \\ \bf{g}_k &= {\mat{J}(\vec{q}_k)}^\top \mat{W}_e \vec{e}_k\end{split}\]where \(\mat{J} = {^0\mat{J}}\) is the base-frame manipulator Jacobian. If \(\mat{J}(\vec{q}_k)\) is non-singular, and \(\mat{W}_e = \mat{1}_n\), then the above provides the pseudoinverse solution. However, if \(\mat{J}(\vec{q}_k)\) is singular, the above can not be computed and the GN solution is infeasible.
Examples
The following example gets a
panda
robot object, makes a goal poseTep
, and then solves for the joint coordinates which result in the poseTep
using theikine_GN
method.>>> import roboticstoolbox as rtb >>> panda = rtb.models.Panda() >>> Tep = panda.fkine([0, -0.3, 0, -2.2, 0, 2, 0.7854]) >>> panda.ik_GN(Tep) (array([-1.0805, -0.5328, 0.9086, -2.1781, 0.4612, 1.9018, 0.4239]), 1, 510, 32, 2.803306327008683e-09)
Notes
When using the this method, the initial joint coordinates \(q_0\), should correspond to a non-singular manipulator pose, since it uses the manipulator Jacobian.
References
J. Haviland, and P. Corke. “Manipulator Differential Kinematics Part I: Kinematics, Velocity, and Applications.” arXiv preprint arXiv:2207.01796 (2022).
J. Haviland, and P. Corke. “Manipulator Differential Kinematics Part II: Acceleration and Advanced Applications.” arXiv preprint arXiv:2207.01794 (2022).