There are two broad approaches:
- analytic solutions, given an end-effector pose, directly compute the joint coordinates. In general the solution is not unique, so you can compute a set of possible joint coordinates. Some may cause the robot to hit things in its environment (or itself), or your task might help you choose a particular solution, ie. you might prefer the elbow to up (or down), or the robot to have its arm to the left (or right) of its trunk. In general there are constraints on obtaining an analytic solution, for 6-axis robots, a spherical wrist (all axes intersect)is assumed. The analytic solutions for many different types of robots have been computed over the decades and you can probably find a paper that gives a solution for your robot.
- numeric solutions, as described in the other answers, uses an optimisation approach to adjust the joint coordinates until the forward kinematics gives the right solution. Again, there's a huge literature on this, and lots of software.
Using my Robotics Toolbox for MATLAB, I create a model of a well known 6-axis robot using Denavit-Hartenberg parameters
>> mdl_puma560
>> p560
p560 =
Puma 560 [Unimation]:: 6 axis, RRRRRR, stdDH, fastRNE
- viscous friction; params of 8/95;
+---+-----------+-----------+-----------+-----------+-----------+
| j | theta | d | a | alpha | offset |
+---+-----------+-----------+-----------+-----------+-----------+
| 1| q1| 0| 0| 1.5708| 0|
| 2| q2| 0| 0.4318| 0| 0|
| 3| q3| 0.15005| 0.0203| -1.5708| 0|
| 4| q4| 0.4318| 0| 1.5708| 0|
| 5| q5| 0| 0| -1.5708| 0|
| 6| q6| 0| 0| 0| 0|
+---+-----------+-----------+-----------+-----------+-----------+
then choose a random joint coordinate
>> q = rand(1,6)
q =
0.7922 0.9595 0.6557 0.0357 0.8491 0.9340
then compute the forward kinematics
>> T = p560.fkine(q)
T =
-0.9065 0.0311 -0.4210 -0.02271
0.2451 0.8507 -0.4649 -0.2367
0.3437 -0.5247 -0.7788 0.3547
0 0 0 1
Now we can compute the inverse kinematics using a published analytic solution for a robot with 6 joints and a spherical wrist
>> p560.ikine6s(T)
ans =
0.7922 0.9595 0.6557 0.0357 0.8491 0.9340
and voila, we have the original joint coordinates.
The numerical solution
>> p560.ikine(T)
Warning: ikine: rejected-step limit 100 exceeded (pose 1), final err 0.63042
> In SerialLink/ikine (line 244)
Warning: failed to converge: try a different initial value of joint coordinates
> In SerialLink/ikine (line 273)
ans =
[]
has failed, and this is a common problem since they typically need a good initial solution. Let's try
>> p560.ikine(T, 'q0', [1 1 0 0 0 0])
ans =
0.7922 0.9595 0.6557 0.0357 0.8491 0.9340
which now gives an answer but it is different to the analytic solution. That's ok though, since there are multiple solutions to the IK problem. We can verify that our solution is correct by computing the forward kinematics
>> p560.fkine(ans)
ans =
-0.9065 0.0311 -0.4210 -0.02271
0.2451 0.8507 -0.4649 -0.2367
0.3437 -0.5247 -0.7788 0.3547
0 0 0 1
and checking that it is the same as the transform we started with (which it is).
Other resources: