-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathIK_debug.py
300 lines (233 loc) · 11.2 KB
/
IK_debug.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
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
from sympy import *
from time import time
from mpmath import radians
#import tf
from optimiseIK import *
import numpy as np
'''
Format of test case is [ [[EE position],[EE orientation as quaternions]],[WC location],[joint angles]]
You can generate additional test cases by setting up your kuka project and running `$ roslaunch kuka_arm forward_kinematics.launch`
From here you can adjust the joint angles to find thetas, use the gripper to extract positions and orientation (in quaternion xyzw) and lastly use link 5
to find the position of the wrist center. These newly generated test cases can be added to the test_cases dictionary.
'''
test_cases = {1:[[[2.16135,-1.42635,1.55109],
[0.708611,0.186356,-0.157931,0.661967]],
[1.89451,-1.44302,1.69366],
[-0.65,0.45,-0.36,0.95,0.79,0.49]],
2:[[[-0.56754,0.93663,3.0038],
[0.62073, 0.48318,0.38759,0.480629]],
[-0.638,0.64198,2.9988],
[-0.79,-0.11,-2.33,1.94,1.14,-3.68]],
3:[[[-1.3863,0.02074,0.90986],
[0.01735,-0.2179,0.9025,0.371016]],
[-1.1669,-0.17989,0.85137],
[-2.99,-0.12,0.94,4.06,1.29,-4.12]],
4:[],
5:[]}
def test_code(test_case):
## Set up code
## Do not modify!
x = 0
class Position:
def __init__(self,EE_pos):
self.x = EE_pos[0]
self.y = EE_pos[1]
self.z = EE_pos[2]
class Orientation:
def __init__(self,EE_ori):
self.x = EE_ori[0]
self.y = EE_ori[1]
self.z = EE_ori[2]
self.w = EE_ori[3]
position = Position(test_case[0][0])
orientation = Orientation(test_case[0][1])
class Combine:
def __init__(self,position,orientation):
self.position = position
self.orientation = orientation
comb = Combine(position,orientation)
class Pose:
def __init__(self,comb):
self.poses = [comb]
req = Pose(comb)
start_time = time()
########################################################################################
##
## Insert IK code here!
#px = req.poses[x].position.x
#print(req.poses)
q1, q2, q3, q4, q5, q6, q7 = symbols('q1:8') #Theta
d1, d2, d3, d4, d5, d6, d7 = symbols('d1:8') #d-offset
a0, a1, a2, a3, a4, a5, a6 = symbols('a0:7') #
alpha0, alpha1, alpha2, alpha3, alpha4, alpha5, alpha6 = symbols('alpha0:7') # alpha twist angle..
'''dh = {
a0: 0, alpha0: 0, q1: q1, d1: 0.75,
a1: 0.35, alpha1: pi/2, q2: q2, d2: 0.00,
a2: 1.25, alpha2: 0, q3: q3 + pi/2, d3: 0.00,
a3: -0.054, alpha3: pi/2, q4: q4, d4: 1.50,
a4: 0, alpha4: pi/2, q5: q5, d5: 0.00,
a5: 0, alpha5: pi/2, q6: q6, d6: 0.00,
a6: 0, alpha6: 0, q7: 0, d7: 0.303
}'''
dh = {
a0: 0, alpha0: 0, q1: q1, d1: 0.75,
a1: 0.35, alpha1: -pi/2, q2: q2 - pi/2, d2: 0.00,
a2: 1.25, alpha2: 0, q3: q3, d3: 0.00,
a3: -0.054, alpha3: -pi/2, q4: q4, d4: 1.50,
a4: 0, alpha4: pi/2, q5: q5, d5: 0.00,
a5: 0, alpha5: -pi/2, q6: q6, d6: 0.00,
a6: 0, alpha6: 0, q7: 0, d7: 0.303
}
def homTransform(a, alpha, q, d):
Hm = Matrix([[cos(q), -sin(q), 0, a],
[sin(q)*cos(alpha), cos(alpha)*cos(q), -sin(alpha), -sin(alpha)*d],
[sin(alpha)*sin(q), sin(alpha)*cos(q), cos(alpha), cos(alpha)*d],
[0, 0, 0, 1]])
return Hm
# Define Rotation Matrices around X, Y, and Z
def Rot_X(q):
R_x = Matrix([[1, 0, 0 ],
[0, cos(q), -sin(q)],
[0, sin(q), cos(q)]
])
return R_x
def Rot_Y(q):
R_y = Matrix([[cos(q), 0, sin(q)],
[ 0 , 1 , 0 ],
[-sin(q) , 0 , cos(q)]
])
return R_y
def Rot_Z(q):
R_z = Matrix([[cos(q), -sin(q), 0],
[sin(q) , cos(q) , 0],
[ 0 , 0 , 0],
])
return R_z
def calculateJointAngles(Wc):
Wc_x = Wc[0]
Wc_y = Wc[1]
Wc_z = Wc[2]
sqd = sqrt(Wc_x**2 + Wc_y**2)
theta1 = atan2(Wc[1], Wc[0])
a = 1.501
b = sqrt(pow((sqd - 0.35), 2) + pow((Wc_z - 0.75), 2))
c = 1.25
angle_a = acos((b*b + c*c - a*a) / (2*b*c))
angle_b = acos((a*a + c*c - b*b) / (2*a*c))
angle_c = acos((a*a - c*c + b*b) / (2*a*b))
delta = atan2( Wc_z - 0.75, sqd - 0.35 )
theta2 = pi/2 - (angle_a + delta)
theta3 = pi/2 - (angle_b + 0.036)
return (theta1, theta2, theta3)
#Transformation matrices:
T0_1 = homTransform(a0, alpha0, q1, d1)
T0_1 = T0_1.subs(dh)
T1_2 = homTransform(a1, alpha1, q2, d2)
T1_2 = T1_2.subs(dh)
T2_3 = homTransform(a2, alpha2, q3, d3)
T2_3 = T2_3.subs(dh)
T3_4 = homTransform(a3, alpha3, q4, d4)
T3_4 = T3_4.subs(dh)
T5_6 = homTransform(a5, alpha5, q6, d6)
T5_6 = T5_6.subs(dh)
T6_G = homTransform(a6, alpha6, q7, d7)
T6_G = T6_G.subs(dh)
#FInal TRansformation matrix from base to gripper..
T0_G = simplify(T0_1 * T1_2 * T2_3 * T3_4 * T5_6 * T6_G)
#------------------------------------------------------------------------------------
# Inverse Kinematics Part starts here.......
#------------------------------------------------------------------------------------
# Initialize service response
joint_trajectory_list = []
for x in range(0, len(req.poses)):
#joint_trajectory_point = JointTrajectoryPoint()
#End Effector Position
px = req.poses[x].position.x
py = req.poses[x].position.y
pz = req.poses[x].position.z
EE_Matrix = Matrix([[px], [py], [pz]])
(roll, pitch, yaw) = (1.6544359732979843, 0.4899095071534359, 0.062392126062629866)
#End Effector Orientation angles
'''(roll, pitch, yaw) = tf.transformations.euler_from_quaternion(
[req.poses[x].orientation.x, req.poses[x].orientation.y,
req.poses[x].orientation.z, req.poses[x].orientation.w])'''
r, p, y = symbols('r, p, y')
#Intrinsic rotation applied on end-effector.
R_EE = Rot_Z(y) * Rot_Y(p) * Rot_X(r)
#Rotation Error
RotationError = Rot_Z(pi) * Rot_Y(-pi/2)
R_EE = R_EE * RotationError
# Substitute the End Effector Orientation angles for r, p, y
R_EE = R_EE.subs({'r' : roll, 'p': pitch, 'y': yaw})
#Wrist Center Position
Wc = EE_Matrix - 0.303 * R_EE[:, 2]
#Compute the Joint angles 1,2 & 3 from wrist center positions
theta1, theta2, theta3 = calculateJointAngles(Wc)
# Evaluate the Rotation Matrix from {0} to {3} with the obtained
# theta1, theta2 & theta3 values.
R0_3 = T0_1[0:3, 0:3] * T1_2[0:3, 0:3] * T2_3[0:3, 0:3]
R0_3 = R0_3.evalf(subs = {q1: theta1, q2: theta2, q3: theta3 })
R0_3_Tp = R0_3.T
# As we know that R_EE = R0_3 * R3_6 and inv(R0_3) = Transpose(R3_6) we can write,
R3_6 = R0_3_Tp * R_EE
# Now that we know the Rotation matrix from {3} to {6} and the
# End Effector Orientation at {6}. So from R3_6, Euler angles can be extracted
# and equalled with obtained roll, pitch and yaw angles.
theta4 = atan2(R3_6[2,2], -R3_6[0,2])
theta5 = atan2( sqrt(R3_6[0,2]**2 + R3_6[2,2]**2), R3_6[1,2] )
theta6 = atan2(-R3_6[1,1], R3_6[1,0])
##
########################################################################################
########################################################################################
## For additional debugging add your forward kinematics here. Use your previously calculated thetas
## as the input and output the position of your end effector as your_ee = [x,y,z]
## (OPTIONAL) YOUR CODE HERE!
## End your code input for forward kinematics here!
########################################################################################
## For error analysis please set the following variables of your WC location and EE location in the format of [x,y,z]
your_wc = [1,1,1] # <--- Load your calculated WC values in this array
your_ee = [1,1,1] # <--- Load your calculated end effector value from your forward kinematics
########################################################################################
## Error analysis
print ("\nTotal run time to calculate joint angles from pose is %04.4f seconds" % (time()-start_time))
# Find WC error
if not(sum(your_wc)==3):
wc_x_e = abs(your_wc[0]-test_case[1][0])
wc_y_e = abs(your_wc[1]-test_case[1][1])
wc_z_e = abs(your_wc[2]-test_case[1][2])
wc_offset = sqrt(wc_x_e**2 + wc_y_e**2 + wc_z_e**2)
print ("\nWrist error for x position is: %04.8f" % wc_x_e)
print ("Wrist error for y position is: %04.8f" % wc_y_e)
print ("Wrist error for z position is: %04.8f" % wc_z_e)
print ("Overall wrist offset is: %04.8f units" % wc_offset)
# Find theta errors
t_1_e = abs(theta1-test_case[2][0])
t_2_e = abs(theta2-test_case[2][1])
t_3_e = abs(theta3-test_case[2][2])
t_4_e = abs(theta4-test_case[2][3])
t_5_e = abs(theta5-test_case[2][4])
t_6_e = abs(theta6-test_case[2][5])
print ("\nTheta 1 error is: %04.8f" % t_1_e)
print ("Theta 2 error is: %04.8f" % t_2_e)
print ("Theta 3 error is: %04.8f" % t_3_e)
print ("Theta 4 error is: %04.8f" % t_4_e)
print ("Theta 5 error is: %04.8f" % t_5_e)
print ("Theta 6 error is: %04.8f" % t_6_e)
print ("\n**These theta errors may not be a correct representation of your code, due to the fact \
\nthat the arm can have muliple positions. It is best to add your forward kinmeatics to \
\nconfirm whether your code is working or not**")
print (" ")
# Find FK EE error
if not(sum(your_ee)==3):
ee_x_e = abs(your_ee[0]-test_case[0][0][0])
ee_y_e = abs(your_ee[1]-test_case[0][0][1])
ee_z_e = abs(your_ee[2]-test_case[0][0][2])
ee_offset = sqrt(ee_x_e**2 + ee_y_e**2 + ee_z_e**2)
print ("\nEnd effector error for x position is: %04.8f" % ee_x_e)
print ("End effector error for y position is: %04.8f" % ee_y_e)
print ("End effector error for z position is: %04.8f" % ee_z_e)
print ("Overall end effector offset is: %04.8f units \n" % ee_offset)
if __name__ == "__main__":
# Change test case number for different scenarios
test_case_number = 1
test_code(test_cases[test_case_number])