ETS.ikine_NR
- ETS.ikine_NR(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]
Newton-Raphson Numerical Inverse Kinematics Solver
A method which provides functionality to perform numerical inverse kinematics (IK) using the Newton-Raphson 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 toTrue
- Parameters:
q0 (
Union
[ndarray
,List
[float
],Tuple
[float
],Set
[float
],None
]) – The initial joint coordinate vectorilimit (
int
) – How many iterations are allowed within a search before a new search is startedslimit (
int
) – How many searches are allowed before being deemed unsuccessfultol (
float
) – Maximum allowed residual error Emask (
Union
[ndarray
,List
[float
],Tuple
[float
],Set
[float
],None
]) – A 6 vector which assigns weights to Cartesian degrees-of-freedom error priorityjoint_limits (
bool
) – Reject solutions with joint limit violationsseed (
Optional
[int
]) – A seed for the private RNG used to generate random joint coordinate vectorspinv (
bool
) – If True, will use the psuedoinverse in thestep
method instead of the normal inversekq (
float
) – The gain for joint limit avoidance. Setting to 0.0 will remove this completely from the solutionkm (
float
) – The gain for maximisation. Setting to 0.0 will remove this completely from the solutionps (
float
) – The minimum angle/distance (in radians or metres) in which the joint is allowed to approach to its limitpi (
Union
[ndarray
,float
]) – The influence angle/distance (in radians or metres) in null space motion becomes active
Synopsis
Each iteration uses the Newton-Raphson optimisation method
\[\vec{q}_{k+1} = \vec{q}_k + {^0\mat{J}(\vec{q}_k)}^{-1} \vec{e}_k\]Examples
The following example gets the
ets
of apanda
robot object, makes a goal poseTep
, and then solves for the joint coordinates which result in the poseTep
using theikine_NR
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_NR(Tep) IKSolution(q=array([ 1.2619, -1.1522, 0.1673, -1.007 , 2.5686, 0.6884, 2.4083]), 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
Changed in version 1.0.4: Added the Newton-Raphson IK solver method on the
ETS
class