two-link-ik.py¶
This script demonstrates calculating the forward and inverse kinematics for a planar two-link arm.
1#!/usr/bin/env python3
2"""two-link-ik.py: demonstration of forward and inverse kinematics for a two-link arm."""
3
4# Standard library modules.
5import math
6
7# Third-party library modules.
8import numpy as np
9
10#================================================================
11def two_link_forward_kinematics(q, len1=1.0, len2=1.0):
12 """Compute the forward kinematics. Returns the base-coordinate Cartesian
13 position of the elbow and endpoint for a given joint angle vector. Optional
14 parameters l1 and l2 are the link lengths. The base is assumed to be at the
15 origin.
16
17 :param q: two-element list or ndarray with [q1, q2] joint angles
18 :param len1: optional proximal link length
19 :param len2: optional distal link length
20 :return: tuple (elbow, end) of two-element ndarrays with [x,y] locations
21 """
22
23 elbow = np.array((len1 * math.sin(q[0]), -len1 * math.cos(q[0])))
24 end = elbow + np.array((len2 * math.sin(q[0]+q[1]), -len2 * math.cos(q[0]+q[1])))
25 return elbow, end
26
27#================================================================
28def two_link_inverse_kinematics(target, len1=1.0, len2=1.0):
29 """Compute two inverse kinematics solutions for a target end position. The
30 target is a Cartesian position vector (two-element ndarray) in world
31 coordinates, and the result vectors are joint angles as ndarrays [q0, q1].
32 If the target is out of reach, returns the closest pose.
33
34 :param target: two-element list or ndarray with [x1, y] target position
35 :param len1: optional proximal link length
36 :param len2: optional distal link length
37 :return: tuple (solution1, solution2) of two-element ndarrays with q1, q2 angles
38 """
39
40 # find the position of the point in polar coordinates
41 radiussq = np.dot(target, target)
42 radius = math.sqrt(radiussq)
43
44 # theta is the angle of target point w.r.t. -Y axis, same origin as arm
45 theta = math.atan2(target[0], -target[1])
46
47 # use the law of cosines to compute the elbow angle
48 # R**2 = l1**2 + l2**2 - 2*l1*l2*cos(pi - elbow)
49 # both elbow and -elbow are valid solutions
50 acosarg = (radiussq - len1**2 - len2**2) / (-2 * len1 * len2)
51 if acosarg < -1.0: elbow_supplement = math.pi
52 elif acosarg > 1.0: elbow_supplement = 0.0
53 else: elbow_supplement = math.acos(acosarg)
54
55 # use the law of sines to find the angle at the bottom vertex of the triangle defined by the links
56 # radius / sin(elbow_supplement) = l2 / sin(alpha)
57 if radius > 0.0:
58 alpha = math.asin(len2 * math.sin(elbow_supplement) / radius)
59 else:
60 alpha = 0.0
61
62 # compute the two solutions with opposite elbow sign
63 soln1 = np.array((theta - alpha, math.pi - elbow_supplement))
64 soln2 = np.array((theta + alpha, elbow_supplement - math.pi))
65
66 return soln1, soln2
67
68################################################################
69# When run as a script, try a sample problem:
70if __name__ == "__main__":
71
72 # choose a sample target position to test IK
73 target = np.array((0.5, 0.6))
74 ik = two_link_inverse_kinematics(target)
75 print("The following solutions should reach endpoint position %s: %s" % (target, ik))
76
77 # test the solutions:
78
79 p1 = two_link_forward_kinematics(ik[0])
80 p2 = two_link_forward_kinematics(ik[1])
81
82 print("Endpoint position for first solution :", p1[1])
83 print("Endpoint position for second solution:", p2[1])
Sample Output¶
The following solutions should reach endpoint position [0.5 0.6]: (array([1.27724626, 2.33921623]), array([ 3.61646249, -2.33921623]))
Endpoint position for first solution : [0.5 0.6]
Endpoint position for second solution: [0.5 0.6]