Robot.ik_LM
- Robot.ik_LM(Tep, end=None, start=None, q0=None, ilimit=30, slimit=100, tol=1e-06, mask=None, joint_limits=True, k=1.0, method='chan')
- Fast levenberg-Marquadt Numerical Inverse Kinematics Solver - A method which provides functionality to perform numerical inverse kinematics (IK) using the Levemberg-Marquadt method. 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. - Parameters:
- end ( - Union[- str,- Link,- Gripper,- None]) – the link considered as the end-effector
- start ( - Union[- str,- Link,- Gripper,- None]) – the link considered as the base frame, defaults to the robots’s base frame
- q0 ( - Optional[- ndarray]) – 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 ( - Optional[- ndarray]) – A 6 vector which assigns weights to Cartesian degrees-of-freedom error priority
- joint_limits ( - bool) – Reject solutions with joint limit violations
- seed – 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- stepmethod
 
- Return type:
 - Synopsis - The operation is defined by the choice of the - methodkwarg.- 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 makes a - pandarobot object, makes a goal pose- Tep, and then solves for the joint coordinates which result in the pose- Tepusing the ikine_LM method.- >>> import roboticstoolbox as rtb >>> panda = rtb.models.Panda() >>> Tep = panda.fkine([0, -0.3, 0, -2.2, 0, 2, 0.7854]) >>> panda.ikine_LM(Tep) IKSolution(q=array([-1.176 , -0.6001, 0.9677, -2.1706, 0.5363, 1.8653, 0.3663]), success=True, iterations=39, searches=4, residual=4.525953207786055e-11, reason='Success') - Notes - The value for the - kkwarg will depend on the- methodchosen 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 - Changed in version 1.0.4: Merged the Levemberg-Marquadt IK solvers into the ik_LM method