Skip to content

Commit 3988e21

Browse files
two_joint_arm.py
1 parent 599ddf2 commit 3988e21

File tree

1 file changed

+77
-0
lines changed

1 file changed

+77
-0
lines changed

RoboticArm/two_joint_arm.py

Lines changed: 77 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,77 @@
1+
"""
2+
Inverse kinematics of a two-joint arm
3+
Left-click the plot to set the goal position of the end effector
4+
5+
Author: Daniel Ingram (daniel-s-ingram)
6+
"""
7+
from __future__ import print_function, division
8+
9+
import matplotlib.pyplot as plt
10+
import numpy as np
11+
12+
from math import sin, cos, atan2, acos, pi
13+
14+
Kp = 15
15+
dt = 0.01
16+
17+
#Link lengths
18+
l1 = l2 = 1
19+
20+
shoulder = np.array([0, 0])
21+
22+
#Set initial goal position to the initial end-effector position
23+
x = 2
24+
y = 0
25+
26+
plt.ion()
27+
28+
def two_joint_arm():
29+
"""
30+
Computes the inverse kinematics for a planar 2DOF arm
31+
"""
32+
theta1 = theta2 = 0
33+
while True:
34+
try:
35+
theta2_goal = acos((x**2 + y**2 - l1**2 -l2**2)/(2*l1*l2))
36+
theta1_goal = atan2(y, x) - atan2(l2*sin(theta2_goal), (l1 + l2*cos(theta2_goal)))
37+
38+
if theta1_goal < 0:
39+
theta2_goal = -theta2_goal
40+
theta1_goal = atan2(y, x) - atan2(l2*sin(theta2_goal), (l1 + l2*cos(theta2_goal)))
41+
42+
theta1 = theta1 + Kp*ang_diff(theta1_goal, theta1)*dt
43+
theta2 = theta2 + Kp*ang_diff(theta2_goal, theta2)*dt
44+
except ValueError as e:
45+
print("Unreachable goal")
46+
47+
plot_arm(theta1, theta2, x, y)
48+
49+
def plot_arm(theta1, theta2, x, y):
50+
elbow = shoulder + np.array([l1*cos(theta1), l1*sin(theta1)])
51+
wrist = elbow + np.array([l2*cos(theta1+theta2), l2*sin(theta1+theta2)])
52+
plt.cla()
53+
plt.plot([shoulder[0], elbow[0]], [shoulder[1], elbow[1]], 'k-')
54+
plt.plot([elbow[0], wrist[0]], [elbow[1], wrist[1]], 'k-')
55+
plt.plot(shoulder[0], shoulder[1], 'ro')
56+
plt.plot(elbow[0], elbow[1], 'ro')
57+
plt.plot(wrist[0], wrist[1], 'ro')
58+
plt.plot([wrist[0], x], [wrist[1], y], 'g--')
59+
plt.plot(x, y, 'g*')
60+
plt.xlim(-2, 2)
61+
plt.ylim(-2, 2)
62+
plt.show()
63+
plt.pause(dt)
64+
65+
def ang_diff(theta1, theta2):
66+
#Returns the difference between two angles in the range -pi to +pi
67+
return (theta1-theta2+pi)%(2*pi)-pi
68+
69+
def click(event):
70+
global x, y
71+
x = event.xdata
72+
y = event.ydata
73+
74+
if __name__ == "__main__":
75+
fig = plt.figure()
76+
fig.canvas.mpl_connect("button_press_event", click)
77+
two_joint_arm()

0 commit comments

Comments
 (0)