IK_GN - Gauss-Newton Numerical IK
- class roboticstoolbox.robot.IK.IK_GN(name='IK Solver', 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]
Bases:
IKSolver
Gauss-Newton Numerical Inverse Kinematics Solver
A class which provides functionality to perform numerical inverse kinematics (IK) using the Gauss-Newton method. See
step
method for mathematical description.Note
When using this class with redundant robots (>6 DoF),
pinv
must be set toTrue
- Parameters:
name (
str
) – The name of the IK algorithmilimit (
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
Examples
The following example gets the
ets
of apanda
robot object, instantiates theIK_GN
solver class using default parameters, makes a goal poseTep
, and then solves for the joint coordinates which result in the poseTep
using thesolve
method.>>> import roboticstoolbox as rtb >>> panda = rtb.models.Panda().ets() >>> solver = rtb.IK_GN(pinv=True) >>> Tep = panda.fkine([0, -0.3, 0, -2.2, 0, 2, 0.7854]) >>> solver.solve(panda, Tep) IKSolution(q=array([ 1.2886, 1.4862, -2.1934, -2.0771, 1.244 , 1.1468, -0.096 ]), success=True, iterations=53, searches=4, residual=9.796561164911834e-10, reason='Success')
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. When the the problem is solvable, it converges very quickly.
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.3: Added the Gauss-Newton IK solver class
Methods
|
Performs a single iteration of the Gauss-Newton optimisation method |
|
Solves the IK problem |
|
Calculates the error between Te and Tep |
Private Methods
|
Generate a random valid joint configuration using a private RNG |
|
Checks if the joints are within their respective limits |