ETS.ikine_GN

ETS.ikine_GN(Tep, q0=None, ilimit=30, slimit=100, tol=1e-06, mask=None, joint_limits=True, seed=None, pinv=False, kq=0.0, km=0.0, ps=0.0, pi=0.3, **kwargs)[source]

Gauss-Newton Numerical Inverse Kinematics Solver

A method which provides functionality to perform numerical inverse kinematics (IK) using the Gauss-Newton method.

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 to True

Parameters:
  • Tep (Union[ndarray, SE3]) – The desired end-effector pose

  • q0 (Union[ndarray, List[float], Tuple[float], Set[float], None]) – The initial joint coordinate vector

  • ilimit (int) – How many iterations are allowed within a search before a new search is started

  • slimit (int) – How many searches are allowed before being deemed unsuccessful

  • tol (float) – Maximum allowed residual error E

  • mask (Union[ndarray, List[float], Tuple[float], Set[float], None]) – A 6 vector which assigns weights to Cartesian degrees-of-freedom error priority

  • joint_limits (bool) – Reject solutions with joint limit violations

  • seed (Optional[int]) – A seed for the private RNG used to generate random joint coordinate vectors

  • pinv (bool) – If True, will use the psuedoinverse in the step method instead of the normal inverse

  • kq (float) – The gain for joint limit avoidance. Setting to 0.0 will remove this completely from the solution

  • km (float) – The gain for maximisation. Setting to 0.0 will remove this completely from the solution

  • ps (float) – The minimum angle/distance (in radians or metres) in which the joint is allowed to approach to its limit

  • pi (Union[ndarray, float]) – The influence angle/distance (in radians or metres) in null space motion becomes active

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 the ets of a panda robot object, makes a goal pose Tep, and then solves for the joint coordinates which result in the pose Tep using the ikine_GN method.

>>> import roboticstoolbox as rtb
>>> panda = rtb.models.Panda().ets()
>>> Tep = panda.fkine([0, -0.3, 0, -2.2, 0, 2, 0.7854])
>>> panda.ikine_GN(Tep)
IKSolution(q=array([-0.8553, -0.5978,  2.3022, -1.3476, -2.6294,  2.498 ,  0.9897]), success=False, iterations=100, searches=100, residual=0.0, reason='iteration and search limit reached, 100 numpy.LinAlgError encountered')

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.

This class supports null-space motion to assist with maximising manipulability and avoiding joint limits. These are enabled by setting kq and km to non-zero values.

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).

See also

IK_NR

An IK Solver class which implements the Newton-Raphson optimisation technique

ikine_LM

Implements the IK_LM class as a method within the ETS class

ikine_NR

Implements the IK_NR class as a method within the ETS class

ikine_QP

Implements the IK_QP class as a method within the ETS class

Changed in version 1.0.4: Added the Gauss-Newton IK solver method on the ETS class