This repository was archived by the owner on Feb 21, 2020. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 17
/
Copy pathIK_server.py
229 lines (169 loc) · 10.9 KB
/
IK_server.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
#!/usr/bin/env python
# This file is part of Robotic Arm: Pick and Place project for Udacity Robotics nano-degree program
import rospy
import tf
from kuka_arm.srv import *
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
from geometry_msgs.msg import Pose
from mpmath import *
from sympy import symbols, cos, sin, pi, simplify, pprint, tan, expand_trig, sqrt, trigsimp, atan2
from sympy.matrices import Matrix
def get_hypotenuse(a, b):
# calculate the longest side given the two shorter sides
# of a right triangle using pythagorean theorem
return sqrt(a*a + b*b)
def get_cosine_law_angle(a, b, c):
# given all sides of a triangle a, b, c
# calculate angle gamma between sides a and b using cosine law
cos_gamma = (a*a + b*b - c*c) / (2*a*b)
sin_gamma = sqrt(1 - cos_gamma * cos_gamma)
gamma = atan2(sin_gamma, cos_gamma)
return gamma
def get_wrist_center(gripper_point, R0g, dg = 0.303):
# get the coordinates of the wrist center wrt to the base frame (xw, yw, zw)
# given the following info:
# the coordinates of the gripper (end effector) (x, y, z)
# the rotation of the gripper in gripper frame wrt to the base frame (R0u)
# the distance between gripper and wrist center dg which is along common z axis
# check WRITEUP.pdf for more info
xu, yu, zu = gripper_point
nx, ny, nz = R0g[0, 2], R0g[1, 2], R0g[2, 2]
xw = xu - dg * nx
yw = yu - dg * ny
zw = zu - dg * nz
return xw, yw, zw
def get_first_three_angles(wrist_center):
# given the wrist center which a tuple of 3 numbers x, y, z
# (x, y, z) is the wrist center point wrt base frame
# return the angles q1, q2, q3 for each respective joint
# given geometry of the kuka kr210
# check WRITEUP.pdf for more info
x, y, z = wrist_center
a1, a2, a3 = 0.35, 1.25, -0.054
d1, d4 = 0.75, 1.5
l = 1.50097168527591 # get_hypotenuse(d4, abs(a3))
phi = 1.53481186671284 # atan2(d4, abs(a3))
x_prime = get_hypotenuse(x, y)
mx = x_prime - a1
my = z - d1
m = get_hypotenuse(mx, my)
alpha = atan2(my, mx)
gamma = get_cosine_law_angle(l, a2, m)
beta = get_cosine_law_angle(m, a2, l)
q1 = atan2(y, x)
q2 = pi/2 - beta - alpha
q3 = -(gamma - phi)
return q1, q2, q3
def get_last_three_angles(R):
#Recall that from our simplification, R36 (R) equals the following:
#Matrix([
#[-sin(q4)*sin(q6) + cos(q4)*cos(q5)*cos(q6), -sin(q4)*cos(q6) - sin(q6)*cos(q4)*cos(q5), -sin(q5)*cos(q4)],
#[ sin(q5)*cos(q6), -sin(q5)*sin(q6), cos(q5)],
#[-sin(q4)*cos(q5)*cos(q6) - sin(q6)*cos(q4), sin(q4)*sin(q6)*cos(q5) - cos(q4)*cos(q6), sin(q4)*sin(q5)]])
#From trigonometry we can get q4, q5, q6 if we know numerical values of all cells of matrix R36 (R)
#check WRITEUP.pdf for more info
sin_q4 = R[2, 2]
cos_q4 = -R[0, 2]
sin_q5 = sqrt(R[0, 2]**2 + R[2, 2]**2)
cos_q5 = R[1, 2]
sin_q6 = -R[1, 1]
cos_q6 = R[1, 0]
q4 = atan2(sin_q4, cos_q4)
q5 = atan2(sin_q5, cos_q5)
q6 = atan2(sin_q6, cos_q6)
return q4, q5, q6
def get_angles(x, y, z, roll, pitch, yaw):
# input: given position and orientation of the gripper_URDF wrt base frame
# output: angles q1, q2, q3, q4, q5, q6
gripper_point = x, y, z
################################################################################
# All important symbolic transformations matrices are declared below
################################################################################
q1, q2, q3, q4, q5, q6 = symbols('q1:7')
alpha, beta, gamma = symbols('alpha beta gamma', real = True)
px, py, pz = symbols('px py pz', real = True)
# Rotation of joint 3 wrt to the base frame interms the first three angles q1, q2, q3
R03 = Matrix([
[sin(q2 + q3)*cos(q1), cos(q1)*cos(q2 + q3), -sin(q1)],
[sin(q1)*sin(q2 + q3), sin(q1)*cos(q2 + q3), cos(q1)],
[ cos(q2 + q3), -sin(q2 + q3), 0]])
# Transpose of R03
R03T = Matrix([
[sin(q2 + q3)*cos(q1), sin(q1)*sin(q2 + q3), cos(q2 + q3)],
[cos(q1)*cos(q2 + q3), sin(q1)*cos(q2 + q3), -sin(q2 + q3)],
[ -sin(q1), cos(q1), 0]])
# Rotation of joint 6 wrt to frame of joint 3 interms of the last three angles q4, q5, q6
R36 = Matrix([
[-sin(q4)*sin(q6) + cos(q4)*cos(q5)*cos(q6), -sin(q4)*cos(q6) - sin(q6)*cos(q4)*cos(q5), -sin(q5)*cos(q4)],
[ sin(q5)*cos(q6), -sin(q5)*sin(q6), cos(q5)],
[-sin(q4)*cos(q5)*cos(q6) - sin(q6)*cos(q4), sin(q4)*sin(q6)*cos(q5) - cos(q4)*cos(q6), sin(q4)*sin(q5)]])
# Rotation of urdf_gripper with respect to the base frame interms of alpha = yaw, beta = pitch, gamma = roll
R0u = Matrix([
[1.0*cos(alpha)*cos(beta), -1.0*sin(alpha)*cos(gamma) + sin(beta)*sin(gamma)*cos(alpha), 1.0*sin(alpha)*sin(gamma) + sin(beta)*cos(alpha)*cos(gamma)],
[1.0*sin(alpha)*cos(beta), sin(alpha)*sin(beta)*sin(gamma) + 1.0*cos(alpha)*cos(gamma), sin(alpha)*sin(beta)*cos(gamma) - 1.0*sin(gamma)*cos(alpha)],
[ -1.0*sin(beta), 1.0*sin(gamma)*cos(beta), 1.0*cos(beta)*cos(gamma)]])
# Total transform of gripper wrt to base frame given orientation yaw (alpha), pitch (beta), roll (beta) and position px, py, pz
T0g_b = Matrix([
[1.0*sin(alpha)*sin(gamma) + sin(beta)*cos(alpha)*cos(gamma), 1.0*sin(alpha)*cos(gamma) - 1.0*sin(beta)*sin(gamma)*cos(alpha), 1.0*cos(alpha)*cos(beta), px],
[sin(alpha)*sin(beta)*cos(gamma) - 1.0*sin(gamma)*cos(alpha), -1.0*sin(alpha)*sin(beta)*sin(gamma) - 1.0*cos(alpha)*cos(gamma), 1.0*sin(alpha)*cos(beta), py],
[ 1.0*cos(beta)*cos(gamma), -1.0*sin(gamma)*cos(beta), -1.0*sin(beta), pz],
[ 0, 0, 0, 1]])
# Total transform of gripper wrt to base frame given angles q1, q2, q3, q4, q5, q6
T0g_a = Matrix([
[((sin(q1)*sin(q4) + sin(q2 + q3)*cos(q1)*cos(q4))*cos(q5) + sin(q5)*cos(q1)*cos(q2 + q3))*cos(q6) - (-sin(q1)*cos(q4) + sin(q4)*sin(q2 + q3)*cos(q1))*sin(q6), -((sin(q1)*sin(q4) + sin(q2 + q3)*cos(q1)*cos(q4))*cos(q5) + sin(q5)*cos(q1)*cos(q2 + q3))*sin(q6) + (sin(q1)*cos(q4) - sin(q4)*sin(q2 + q3)*cos(q1))*cos(q6), -(sin(q1)*sin(q4) + sin(q2 + q3)*cos(q1)*cos(q4))*sin(q5) + cos(q1)*cos(q5)*cos(q2 + q3), -0.303*sin(q1)*sin(q4)*sin(q5) + 1.25*sin(q2)*cos(q1) - 0.303*sin(q5)*sin(q2 + q3)*cos(q1)*cos(q4) - 0.054*sin(q2 + q3)*cos(q1) + 0.303*cos(q1)*cos(q5)*cos(q2 + q3) + 1.5*cos(q1)*cos(q2 + q3) + 0.35*cos(q1)],
[ ((sin(q1)*sin(q2 + q3)*cos(q4) - sin(q4)*cos(q1))*cos(q5) + sin(q1)*sin(q5)*cos(q2 + q3))*cos(q6) - (sin(q1)*sin(q4)*sin(q2 + q3) + cos(q1)*cos(q4))*sin(q6), -((sin(q1)*sin(q2 + q3)*cos(q4) - sin(q4)*cos(q1))*cos(q5) + sin(q1)*sin(q5)*cos(q2 + q3))*sin(q6) - (sin(q1)*sin(q4)*sin(q2 + q3) + cos(q1)*cos(q4))*cos(q6), -(sin(q1)*sin(q2 + q3)*cos(q4) - sin(q4)*cos(q1))*sin(q5) + sin(q1)*cos(q5)*cos(q2 + q3), 1.25*sin(q1)*sin(q2) - 0.303*sin(q1)*sin(q5)*sin(q2 + q3)*cos(q4) - 0.054*sin(q1)*sin(q2 + q3) + 0.303*sin(q1)*cos(q5)*cos(q2 + q3) + 1.5*sin(q1)*cos(q2 + q3) + 0.35*sin(q1) + 0.303*sin(q4)*sin(q5)*cos(q1)],
[ -(sin(q5)*sin(q2 + q3) - cos(q4)*cos(q5)*cos(q2 + q3))*cos(q6) - sin(q4)*sin(q6)*cos(q2 + q3), (sin(q5)*sin(q2 + q3) - cos(q4)*cos(q5)*cos(q2 + q3))*sin(q6) - sin(q4)*cos(q6)*cos(q2 + q3), -sin(q5)*cos(q4)*cos(q2 + q3) - sin(q2 + q3)*cos(q5), -0.303*sin(q5)*cos(q4)*cos(q2 + q3) - 0.303*sin(q2 + q3)*cos(q5) - 1.5*sin(q2 + q3) + 1.25*cos(q2) - 0.054*cos(q2 + q3) + 0.75],
[ 0, 0, 0, 1]])
# Rotation of urdf_gripper wrt (DH) gripper frame from rotz(pi) * roty(-pi/2) and it's transpose
Rgu_eval = Matrix([[0, 0, 1], [0, -1.00000000000000, 0], [1.00000000000000, 0, 0]])
RguT_eval = Matrix([[0, 0, 1], [0, -1.00000000000000, 0], [1.00000000000000, 0, 0]])
################################################################################
# Inverse kinematics transformations starts below
################################################################################
R0u_eval = R0u.evalf(subs = {alpha: yaw, beta: pitch, gamma: roll})
R0g_eval = R0u_eval * RguT_eval
wrist_center = get_wrist_center(gripper_point, R0g_eval, dg = 0.303)
j1, j2, j3 = get_first_three_angles(wrist_center)
R03T_eval = R03T.evalf(subs = {q1: j1.evalf(), q2: j2.evalf(), q3: j3.evalf()})
R36_eval = R03T_eval * R0g_eval
j4, j5, j6 = get_last_three_angles(R36_eval)
j1 = j1.evalf()
j2 = j2.evalf()
j3 = j3.evalf()
j4 = j4.evalf()
j5 = j5.evalf()
j6 = j6.evalf()
return j1, j2, j3, j4, j5, j6
def handle_calculate_IK(req):
rospy.loginfo("Received %s eef-poses from the plan" % len(req.poses))
if len(req.poses) < 1:
print "No valid poses received"
return -1
else:
joint_trajectory_list = []
for i in xrange(0, len(req.poses)):
joint_trajectory_point = JointTrajectoryPoint()
# Extract end-effector position and orientation from request
# px,py,pz = end-effector position
# roll, pitch, yaw = end-effector orientation
x = req.poses[i].position.x
y = req.poses[i].position.y
z = req.poses[i].position.z
(roll, pitch, yaw) = tf.transformations.euler_from_quaternion(
[req.poses[i].orientation.x, req.poses[i].orientation.y,
req.poses[i].orientation.z, req.poses[i].orientation.w])
# Calculate joint angles using Geometric IK method
j1, j2, j3, j4, j5, j6 = get_angles(x, y, z, roll, pitch, yaw)
# Populate response for the IK request
joint_trajectory_point.positions = [j1, j2, j3, j4, j5, j6]
oint_trajectory_list.append(joint_trajectory_point)
rospy.loginfo("length of Joint Trajectory List: %s" % len(joint_trajectory_list))
return CalculateIKResponse(joint_trajectory_list)
def IK_server():
# initialize node and declare calculate_ik service
rospy.init_node('IK_server')
s = rospy.Service('calculate_ik', CalculateIK, handle_calculate_IK)
print "Ready to receive an IK request"
rospy.spin()
if __name__ == "__main__":
IK_server()