ETS.ikine_LM

ETS.ikine_LM(Tep, q0=None, ilimit=30, slimit=100, tol=1e-06, mask=None, joint_limits=True, seed=None, k=1.0, method='chan', kq=0.0, km=0.0, ps=0.0, pi=0.3, **kwargs)[source]

Levemberg-Marquadt Numerical Inverse Kinematics Solver

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

See the Inverse Kinematics Docs Page for more details and for a tutorial on numerical IK, see here.

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

  • k (float) – Sets the gain value for the damping matrix Wn in the next iteration. See synopsis

  • method (Literal['chan', 'wampler', 'sugihara']) – One of “chan”, “sugihara” or “wampler”. Defines which method is used to calculate the damping matrix Wn in the step method

  • 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

The operation is defined by the choice of the method kwarg.

The step is deined as

\[\begin{split}\vec{q}_{k+1} &= \vec{q}_k + \left( \mat{A}_k \right)^{-1} \bf{g}_k \\ % \mat{A}_k &= {\mat{J}(\vec{q}_k)}^\top \mat{W}_e \ {\mat{J}(\vec{q}_k)} + \mat{W}_n\end{split}\]

where \(\mat{W}_n = \text{diag}(\vec{w_n})(\vec{w_n} \in \mathbb{R}^n_{>0})\) is a diagonal damping matrix. The damping matrix ensures that \(\mat{A}_k\) is non-singular and positive definite. The performance of the LM method largely depends on the choice of \(\mat{W}_n\).

Chan’s Method

Chan proposed

\[\mat{W}_n = λ E_k \mat{1}_n\]

where λ is a constant which reportedly does not have much influence on performance. Use the kwarg k to adjust the weighting term λ.

Sugihara’s Method

Sugihara proposed

\[\mat{W}_n = E_k \mat{1}_n + \text{diag}(\hat{\vec{w}}_n)\]

where \(\hat{\vec{w}}_n \in \mathbb{R}^n\), \(\hat{w}_{n_i} = l^2 \sim 0.01 l^2\), and \(l\) is the length of a typical link within the manipulator. We provide the variable k as a kwarg to adjust the value of \(w_n\).

Wampler’s Method

Wampler proposed \(\vec{w_n}\) to be a constant. This is set through the k kwarg.

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_LM 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_LM(Tep)
IKSolution(q=array([-1.0134, -0.4938,  0.8625, -2.1822,  0.4142,  1.9214,  0.4602]), success=True, iterations=8, searches=1, residual=1.871393860120283e-08, reason='Success')

Notes

The value for the k kwarg will depend on the method chosen and the arm you are using. Use the following as a rough guide chan, k = 1.0 - 0.01, wampler, k = 0.01 - 0.0001, and sugihara, k = 0.1 - 0.0001

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_LM

An IK Solver class which implements the Levemberg Marquadt optimisation technique

ikine_NR

Implements the IK_NR class as a method within the ETS class

ikine_GN

Implements the IK_GN 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 Levemberg-Marquadt IK solver method on the ETS class