-
Notifications
You must be signed in to change notification settings - Fork 9
/
current_ik_code.py
1318 lines (1124 loc) · 52.3 KB
/
current_ik_code.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
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
# -*- coding: utf-8 -*-
"""Current IK Code
Automatically generated by Colaboratory.
Original file is located at
https://colab.research.google.com/drive/1LawTVylkYnmPMDTUGQ2cuVeWodHxg84W
"""
#! /usr/bin/env python
# imports
import copy
import time
import openravepy
import numpy as np
import pygame
import math
import httplib
import sys
import threading
import rospy
from std_msgs.msg import String
gripper_encoder_missing = 1
'''
👆👆👆👆
'''
def put_msg(message):
#global conn
global pub
global connFlag
try:
if not rospy.is_shutdown(): # the code runs until the is_shutdown() flag is true, used to terminate the program properly
#rospy.loginfo(message)
pub.publish(message)
rate.sleep()
# print ("The message to send is: {}".format(message))
#conn.request("PUT", "/arm/"+message+"/")
#conn.close()
except rospy.ROSInterruptException as e:
print "!!! ERROR in put_msg:"
print e
time.sleep(0.1)
def messageThread():
global message_to_send
while True:
message_lock.acquire()
try:
msg = message_to_send
finally:
message_lock.release()
put_msg(msg)
def homogenousTransform(dhVector): # set up a homogenous matrix given the parameters that describe a joint / the transformation
a = dhVector[0]
alpha = dhVector[1]
d = dhVector[2]
theta = dhVector[3]
homTransMatrix = [ [math.cos(theta), -math.sin(theta)*math.cos(alpha), math.sin(theta)*math.sin(alpha), a*math.cos(theta)],
[math.sin(theta), math.cos(theta)*math.cos(alpha), -math.cos(theta)*math.sin(alpha), a*math.sin(theta)],
[0, math.sin(alpha), math.cos(alpha), d],
[0, 0, 0, 1] ]
return homTransMatrix
def forwardKinematics(dhTable): # use the dh table to perform forward kinematics - outputs the end position
A1 = np.matrix( homogenousTransform(dhTable[0]) )
A2 = np.matrix( homogenousTransform(dhTable[1]) )
A3 = np.matrix( homogenousTransform(dhTable[2]) )
A4 = np.matrix( homogenousTransform(dhTable[3]) )
A5 = np.matrix( homogenousTransform(dhTable[4]) )
A6 = np.matrix( homogenousTransform(dhTable[5]) )
fullHomTransMatrix = A1*A2*A3*A4*A5*A6
#print( fullHomTransMatrix.tolist() )
return fullHomTransMatrix.tolist()
def inverseKinematics(dhTable, homTransMatrix): # perform inverse kinematics
# take in a input position we want the end effector to be in, calculates the different joint variables q1 to q6 and calculates what those are in order to orient the arm in that position
# updates DH table and sent out as output
# all DH tables are instructions for microcontrollers
# drive motors to exact position that we want
try:
d1 = dhTable[0][2]
a2 = dhTable[1][0]
d4 = dhTable[3][2]
d6 = dhTable[5][2]
#print("HomTransMatrix: ")
#print(homTransMatrix)
Rd = np.matrix( [ homTransMatrix[0][:3], homTransMatrix[1][:3], homTransMatrix[2][:3] ] )
#print("Rd: ")
#print(Rd)
od = np.matrix( [ homTransMatrix[0][3], homTransMatrix[1][3], homTransMatrix[2][3] ] ).transpose()
#print("od: ")
#print(od)
arD6 = np.matrix( [ 0,0,d6] ).transpose()
#print("arD6: ")
#print(arD6)
#print(arD6.transpose())
#print(Rd)
oc = od - Rd * arD6
#print(np.dot(Rd,arD6))
#print(np.dot(Rd,arD6.transpose()))
#print("oc: ")
#print(oc)
xc = oc.tolist()[0][0]
yc = oc.tolist()[1][0]
zc = oc.tolist()[2][0]
q1 = math.atan2(yc, xc)
Dtemp = ( xc**2 + yc**2 + (zc-d1)**2 - a2**2 - d4**2 )/( 2*a2*d4 )
if abs(Dtemp) > 1:
print( 'Can not reach {}, {}, {}'.format( homTransMatrix[0][3], homTransMatrix[1][3], homTransMatrix[2][3] ) )
return dhTable
q3 = math.atan2( Dtemp, math.sqrt(1 - Dtemp**2) ) # assumes we chose to always have 'elbow up' solution
q2 = math.atan2( zc - d1, math.sqrt(xc**2 + yc**2) ) - math.atan2( d4*math.sin(q3-math.pi/2), a2+d4*math.cos(q3-math.pi/2) )
# start updating dhTable. Update with first 3 joints
updatedDHTable = copy.deepcopy(dhTable)
updatedDHTable[0][3] = q1
updatedDHTable[1][3] = q2
updatedDHTable[2][3] = q3
H01 = np.matrix( homogenousTransform(updatedDHTable[0]) )
H12 = np.matrix( homogenousTransform(updatedDHTable[1]) )
H23 = np.matrix( homogenousTransform(updatedDHTable[2]) )
H03 = (H01 * H12 * H23).tolist()
R03 = np.matrix( [H03[0][:3], H03[1][:3], H03[2][:3]] )
#print("R03: ")
#print(R03)
#print(R03)
#print(R03.transpose())
R36 = R03.transpose() * Rd
#print("R36: ")
#print(R36)
#print( np.dot(R03, Rd) )
#print( np.dot(R03.transpose(), Rd) )
q4 = math.atan2( R36.tolist()[1][2], R36.tolist()[0][2] )
q5 = math.atan2( math.sqrt(1 - R36.tolist()[2][2]**2), R36.tolist()[2][2] )
q6 = math.atan2( R36.tolist()[2][1], -R36.tolist()[2][0] )
# updating DH table with the wrist stuff
updatedDHTable[3][3] = q4
updatedDHTable[4][3] = q5
updatedDHTable[5][3] = q6
return updatedDHTable
except:
return dhTable
def inverseKinematicsPositional(dhTable, homTransMatrix, rotationVector):
# keeps arm still
# ex. keep end effector at a position, but just move a few inches
try:
d1 = dhTable[0][2]
a2 = dhTable[1][0]
d4 = dhTable[3][2]
d6 = dhTable[5][2]
#print("HomTransMatrix: ")
#print(homTransMatrix)
Rd = np.matrix( [ homTransMatrix[0][:3], homTransMatrix[1][:3], homTransMatrix[2][:3] ] )
#print("Rd: ")
#print(Rd)
od = np.matrix( [ homTransMatrix[0][3], homTransMatrix[1][3], homTransMatrix[2][3] ] ).transpose()
#print("od: ")
#print(od)
arD6 = np.matrix( [ 0,0,d6] ).transpose()
#print("arD6: ")
#print(arD6)
#print(arD6.transpose())
#print(Rd)
oc = od - Rd * arD6
#print(np.dot(Rd,arD6))
#print(np.dot(Rd,arD6.transpose()))
#print("oc: ")
#print(oc)
xc = oc.tolist()[0][0]
yc = oc.tolist()[1][0]
zc = oc.tolist()[2][0]
q1 = math.atan2(yc, xc)
Dtemp = ( xc**2 + yc**2 + (zc-d1)**2 - a2**2 - d4**2 )/( 2*a2*d4 )
if abs(Dtemp) > 1:
print( 'Can not reach {}, {}, {}'.format( homTransMatrix[0][3], homTransMatrix[1][3], homTransMatrix[2][3] ) )
return dhTable
q3 = math.atan2( Dtemp, math.sqrt(1 - Dtemp**2) ) # assumes we chose to always have 'elbow up' solution
q2 = math.atan2( zc - d1, math.sqrt(xc**2 + yc**2) ) - math.atan2( d4*math.sin(q3-math.pi/2), a2+d4*math.cos(q3-math.pi/2) )
# start updating dhTable. Update with first 3 joints
updatedDHTable = copy.deepcopy(dhTable)
updatedDHTable[0][3] = q1
updatedDHTable[1][3] = q2
updatedDHTable[2][3] = q3
updatedDHTable[3][3] = rotationVector[1]
updatedDHTable[4][3] = rotationVector[0]
updatedDHTable[5][3] = rotationVector[2]
return updatedDHTable
except:
return dhTable
def updateHomTransMatrix(homTransMatrix, DHTable, translationVector, rotationVector):
#updates the homogenous matrix after it gets to its end position
global ikType
updatedHomTransMatrix = copy.deepcopy( homTransMatrix )
global k, t
for ind in range(3):
translationVector[ind] = k * translationVector[ind]
rotationVector[ind] = t * rotationVector[ind]
### TYPE0 fancy motions, relative to the camera reference frame
if ikType == 0:
## update movement in the end effector camera frame
x0 = np.matrix( [1, 0, 0] ).transpose()
y0 = np.matrix( [0, 1, 0] ).transpose()
z0 = np.matrix( [0, 0, 1] ).transpose()
# get z4
A1 = np.matrix( homogenousTransform(DHTable[0]) )
A2 = np.matrix( homogenousTransform(DHTable[1]) )
A3 = np.matrix( homogenousTransform(DHTable[2]) )
A4 = np.matrix( homogenousTransform(DHTable[3]) )
H04 = A1*A2*A3*A4
R04 = H04[:3,:3]
z4 = R04 * z0
#get z6
R06 = np.matrix( [ updatedHomTransMatrix[0][:3], updatedHomTransMatrix[1][:3], updatedHomTransMatrix[2][:3] ] )
z6 = R06 * z0
# define the end effector camera frame
z0_tilda = z6.transpose().tolist()[0]
y0_tilda = z4.transpose().tolist()[0]
x0_tilda = np.cross(y0_tilda,z0_tilda)
x0_tildaNorm = np.linalg.norm(x0_tilda)
for i in range(len(z0_tilda)):
x0_tilda[i] = x0_tilda[i]/x0_tildaNorm
#print(x0_tilda)
#print(y0_tilda)
#print(z0_tilda)
# construct R00_tilda
x0 = x0.transpose().tolist()[0]
y0 = y0.transpose().tolist()[0]
z0 = z0.transpose().tolist()[0]
R00_tilda = np.matrix( [ [np.dot(x0_tilda,x0), np.dot(y0_tilda,x0), np.dot(z0_tilda,x0)],
[np.dot(x0_tilda,y0), np.dot(y0_tilda,y0), np.dot(z0_tilda,y0)],
[np.dot(x0_tilda,z0), np.dot(y0_tilda,z0), np.dot(z0_tilda,z0)] ] )
# update translation
xMovement = R00_tilda * np.matrix( [translationVector[2], 0, 0] ).transpose()
yMovement = R00_tilda * np.matrix( [0, -translationVector[1], 0] ).transpose()
zMovement = R00_tilda * np.matrix( [0, 0, translationVector[0]] ).transpose()
# update rotation
Rx = np.matrix( [ [1, 0, 0],
[0, math.cos(rotationVector[1]), -math.sin(rotationVector[1])],
[0, math.sin(rotationVector[1]), math.cos(rotationVector[1])] ] )
Ry = np.matrix( [ [math.cos(rotationVector[0]), 0, math.sin(rotationVector[0])],
[0, 1, 0],
[-math.sin(rotationVector[0]), 0, math.cos(rotationVector[0])] ] )
Rz = np.matrix( [ [math.cos(rotationVector[2]), -math.sin(rotationVector[2]), 0],
[math.sin(rotationVector[2]), math.cos(rotationVector[2]), 0],
[0, 0, 1] ] )
Rx0_tilda = R00_tilda * Rx * R00_tilda.transpose()
Ry0_tilda = R00_tilda * Ry * R00_tilda.transpose()
Rz0_tilda = R00_tilda * Rz * R00_tilda.transpose()
# update homogenous transform matrix
updatedHomTransMatrix[0][3] += (xMovement.tolist()[0][0] + yMovement.tolist()[0][0] + zMovement.tolist()[0][0])
updatedHomTransMatrix[1][3] += (xMovement.tolist()[1][0] + yMovement.tolist()[1][0] + zMovement.tolist()[1][0])
updatedHomTransMatrix[2][3] += (xMovement.tolist()[2][0] + yMovement.tolist()[2][0] + zMovement.tolist()[2][0])
#rotation is happening in the order: around z -> around y -> around x
R06_updated = (Rx0_tilda * Ry0_tilda * Rz0_tilda * R06).tolist()
#print R06_updated
### TYPE 1 fancy motions (in the tip reference frame)
elif ikType == 1:
# update translation
R06 = np.matrix( [ updatedHomTransMatrix[0][:3], updatedHomTransMatrix[1][:3], updatedHomTransMatrix[2][:3] ] )
# forward-backward movement update
xMovement = R06 * np.matrix( [0, 0, translationVector[0]] ).transpose()
updatedHomTransMatrix[0][3] += xMovement.tolist()[0][0]
updatedHomTransMatrix[1][3] += xMovement.tolist()[1][0]
updatedHomTransMatrix[2][3] += xMovement.tolist()[2][0]
# left-right movement update
yMovement = R06 * np.matrix( [0, -translationVector[1], 0] ).transpose() # put "-" for the right movement direction
updatedHomTransMatrix[0][3] += yMovement.tolist()[0][0]
updatedHomTransMatrix[1][3] += yMovement.tolist()[1][0]
updatedHomTransMatrix[2][3] += yMovement.tolist()[2][0]
# up-down movement update
zMovement = R06 * np.matrix( [translationVector[2], 0, 0] ).transpose()
updatedHomTransMatrix[0][3] += zMovement.tolist()[0][0]
updatedHomTransMatrix[1][3] += zMovement.tolist()[1][0]
updatedHomTransMatrix[2][3] += zMovement.tolist()[2][0]
# update rotation (in the tip reference frame)
# basic rotations
Rx = np.matrix( [ [1, 0, 0],
[0, math.cos(rotationVector[1]), -math.sin(rotationVector[1])],
[0, math.sin(rotationVector[1]), math.cos(rotationVector[1])] ] )
Ry = np.matrix( [ [math.cos(rotationVector[0]), 0, math.sin(rotationVector[0])],
[0, 1, 0],
[-math.sin(rotationVector[0]), 0, math.cos(rotationVector[0])] ] )
Rz = np.matrix( [ [math.cos(rotationVector[2]), -math.sin(rotationVector[2]), 0],
[math.sin(rotationVector[2]), math.cos(rotationVector[2]), 0],
[0, 0, 1] ] )
# update rotation matrix
# rotation is happening in the order: around x -> around y -> around z
R06_updated = (R06 * Rx * Ry * Rz).tolist()
#print R06_updated
# ###!!! move the end effector to the specific predAll DOFs modeefined orientation, based on the predefined rotation matrices
# buttons = getJoystickButtons()
# #print buttons
# turn to "Down" pose
# if buttons[18] == 1:
# R06_updated = np.matrix( [ [1, 0, 0],
# [0, -1, 0],
# [0, 0, -1] ] ).tolist()
# # turn to "Forward" pose
# elif buttons[17] == 1:
# R06_updated = np.matrix( [ [0, 0, 1],
# [0, -1, 0],
# [1, 0, 0] ] ).tolist()
# # turn to "Left" orientation
# elif buttons[21] == 1:
# R06_updated = np.matrix( [ [0, -1, 0],
# [0, 0, -1],
# [1, 0, 0] ] ).tolist()
# # turn to "Right" orientation
# elif buttons[21] == 1:
# R06_updated = np.matrix( [ [0, 1, 0],
# [0, 0, 1],
# [1, 0, 0] ] ).tolist()
# turn to "Left-Forward" orientation
# elif buttons[19] == 1:
# R06_updated = np.matrix( [ [0, -1/math.sqrt(2), 1/math.sqrt(2)],
# [0, -1/math.sqrt(2), -1/math.sqrt(2)],
# [1, 0, 0] ] ).tolist()
# # turn to "Right-Forward" orientation
# elif buttons[20] == 1:
# R06_updated = np.matrix( [ [0, 1/math.sqrt(2), 1/math.sqrt(2)],
# [0, -1/math.sqrt(2), 1/math.sqrt(2)],
# [1, 0, 0] ] ).tolist()
# # turn to "Forward-Down" orientation
# elif buttons[21] == 1:
# R06_updated = np.matrix( [ [1/math.sqrt(2), 0, 1/math.sqrt(2)],
# [0, -1, 0],
# [1/math.sqrt(2), 0, -1/math.sqrt(2)] ] ).tolist()
# # turn to "Forward-Up" orientation
# elif buttons[21] == 1:
# R06_updated = np.matrix( [ [-1/math.sqrt(2), 0, 1/math.sqrt(2)],
# [0, -1, 0],
# [1/math.sqrt(2), 0, 1/math.sqrt(2)] ] ).tolist()
# # turn to "Left-Down" orientation
# elif buttons[21] == 1:
# R06_updated = np.matrix( [ [1, 0, 0],
# [0, -1/math.sqrt(2), -1/math.sqrt(2)],
# [0, 1/math.sqrt(2), -1/math.sqrt(2)] ] ).tolist()
# # turn to "Right-Down" orientation
# elif buttons[21] == 1:
# R06_updated = np.matrix( [ [1, 0, 0],
# [0, -1/math.sqrt(2), 1/math.sqrt(2)],
# [0, -1/math.sqrt(2), -1/math.sqrt(2)] ] ).tolist()
# # turn to "Forward-Up-Left" orientation
# elif buttons[21] == 1:
# R06_updated = np.matrix( [ [-1/math.sqrt(3), -1/math.sqrt(3), 1/math.sqrt(3)],
# [1/math.sqrt(3), -1/math.sqrt(3), -1/math.sqrt(3)],
# [1/math.sqrt(3), -1/math.sqrt(3), 1/math.sqrt(3)] ] ).tolist()
# # turn to "Forward-Up-Right" orientation
# elif buttons[21] == 1:
# R06_updated = np.matrix( [ [-1/math.sqrt(3), 1/math.sqrt(3), 1/math.sqrt(3)],
# [1/math.sqrt(3), -1/math.sqrt(3), 1/math.sqrt(3)],
# [1/math.sqrt(3), 1/math.sqrt(3), 1/math.sqrt(3)] ] ).tolist()
# # turn to "Forward-Down-Left" orientation
# elif buttons[21] == 1:
# R06_updated = np.matrix( [ [1/math.sqrt(3), -1/math.sqrt(3), 1/math.sqrt(3)],
# [-1/math.sqrt(3), -1/math.sqrt(3), -1/math.sqrt(3)],
# [1/math.sqrt(3), 1/math.sqrt(3), -1/math.sqrt(3)] ] ).tolist()
# # turn to "Forward-Down-Right" orientation
# elif buttons[21] == 1:
# R06_updated = np.matrix( [ [1/math.sqrt(3), 1/math.sqrt(3), 1/math.sqrt(3)],
# [1/math.sqrt(3), -1/math.sqrt(3), 1/math.sqrt(3)],
# [1/math.sqrt(3), 1/math.sqrt(3), -1/math.sqrt(3)] ] ).tolist()
# # turn to "Up" orientation
# elif buttons[21] == 1:
# R06_updated = np.matrix( [ [-1, 0, 0],
# [0, -1, 0],
# [0, 0, 1] ] ).tolist()
# # turn to "Left-Up" orientation
# elif buttons[21] == 1:
# R06_updated = np.matrix( [ [-1, 0, 0],
# [0, -1/math.sqrt(2), -1/math.sqrt(2)],
# [0, -1/math.sqrt(2), 1/math.sqrt(2)] ] ).tolist()
# # turn to "Right-Up" orientation
# elif buttons[21] == 1:
# R06_updated = np.matrix( [ [-1, 0, 0],
# [0, -1/math.sqrt(2), 1/math.sqrt(2)],
# [0, 1/math.sqrt(2), 1/math.sqrt(2)] ] ).tolist()
#print R06_updated
# update homTrans matrix
for i in range(3):
for j in range(3):
updatedHomTransMatrix[i][j] = R06_updated[i][j]
#print updatedHomTransMatrix
return updatedHomTransMatrix
def updateHomTransMatrixPositional(homTransMatrix, DHTable, translationVector, rotationVector):
# updates the homogenous matrix after it gets to its end position, positional joints
updatedHomTransMatrix = copy.deepcopy( homTransMatrix )
global k, t
for ind in range(3):
translationVector[ind] = k * translationVector[ind]
rotationVector[ind] = t * rotationVector[ind]
# update translational part
updatedHomTransMatrix[ind][3] += translationVector[ind]
return updatedHomTransMatrix
def initializeJoystick():
# robot operated with a joystick - uses pygame library
pygame.init()
global joystick
joystick = pygame.joystick.Joystick(0)
joystick.init()
print('Initialized joystick: %s' % joystick.get_name())
def setupVisualEnv():
# set up a visual environment that simulates arm in real time to give window that tells you arm is moving correctly
# set up 3d model that moves in real time like the arm and shows us visual of how arm is moving throughout different tasks
env = openravepy.Environment()
env.Load('src/ArmControl/environment.xml')
env.SetViewer('qtcoin')
viewer = env.GetViewer()
global robot
robot = env.GetRobots()[0]
global initAngles
# if want to modify q4 and q6, reverse the sign from "angle" to "-angle"
# needed specifically for visualizer
global savedJointAngles
copySavedJointAngles = savedJointAngles[:]
initAngles = [0,0,-math.pi/2,0,0,0]
setupAngles = []
for i in range(len(initAngles)):
setupAngles.append( copySavedJointAngles[i]+initAngles[i] )
robot.SetActiveDOFValues(setupAngles)
#print( robot.GetActiveDOFValues() )
def getJoystickButtons(): # setting up the buttons
pygame.event.pump() # allow pygame to handle internal actions, keep everything current
buttons = []
for i in range(0, joystick.get_numbuttons()):
button = joystick.get_button(i)
buttons.append(button)
#print(buttons)
return buttons
def sendAngleValues(qVect, start = 0): # sends a message with angle values?
global limitFlag
global modeOfOperation
if modeOfOperation == 4:
# generate messages from qVect here q1String etc correspond to order in message, not exactly in qVect
q1String = str( qVect[0] )
q2String = str( qVect[1] )
q3String = str( qVect[2] )
q4String = str( qVect[3] )
q5String = str( qVect[4] )
q6String = str( qVect[5] )
q7String = str( qVect[6] ) # gripper
command = 'm'
message = command+" "+q1String+" "+q2String+" "+q3String+" "+q4String+" "+q5String+" "+q6String+" "+q7String
#print message
sendMessage(message)
else:
# encoder steps per 2*pi rotation
q1Steps = 1680.0 * 60/24
q2Steps = 2048*4
q3Steps = 2048*4
q4Steps = 1680
q5Steps = 1680
q6Steps = 1680
q7Steps = 1#26.9*64 # gripper
# generate messages from qVect here q1String etc correspond to order in message, not exactly in qVect
q1String = str( int(qVect[0] * q1Steps/(2*math.pi) ) )
q2String = str( int(qVect[1] * q2Steps/(2*math.pi) ) )
q3String = str( int(qVect[2] * q3Steps/(2*math.pi) ) )
q4String = str( int(qVect[3] * q4Steps/(2*math.pi) ) )
q5String = str( int(qVect[4] * q5Steps/(2*math.pi) ) )
q6String = str( int(qVect[5] * q6Steps/(2*math.pi) ) )
if gripper_encoder_missing:
buttons = getJoystickButtons()
if buttons[22] == 1:
gripperSpeed = -255
elif buttons[25] == 1:
gripperSpeed = 255
else:
gripperSpeed = 0
q7String = str (gripperSpeed)
else:
q7String = str( int(qVect[6] * q7Steps ) ) # gripper
if limitFlag == True:
command = 'p'
elif limitFlag == False:
command = 'f'
message = command+" "+q1String+" "+q2String+" "+q3String+" "+q4String+" "+q5String+" "+q6String+" "+q7String
sendMessage(message)
# emergency stop
if buttons[1] == 1:
message = 'e'
sendMessage(message)
# resume from emergency stop
if buttons[23] == 1:
message = 'c'
sendMessage(message)
# starting position calibration
if buttons[9] == 1:
message = 's'
sendMessage(message)
def getJoystickAxes(): # setting up the axes for the control stick
out = [0,0,0,0,0,0]
it = 0 # iterator
pygame.event.pump()
#Read input from the joystick
for i in range(0, joystick.get_numaxes()):
out[i] = joystick.get_axis(i)
return out
def getJoystickDirection(): # read the position of the stick
global modeOfMovement
global savedJointAngles
global modeOfOperation
joystickValues = getJoystickAxes()
#print("Joystick direction values: {}".format(joystickValues))
if modeOfMovement == 0:
print("All DOFs mode")
# mode for all joints being controlled at once
beforeDirectionVector = copy.deepcopy(joystickValues)
#print(beforeDirectionVector)
directionVector = [0,0,0,0,0,0] #beforeDirectionVector
index = -1
for thing in beforeDirectionVector:
index += 1
if abs(thing) > 0.05: # sensitivity "gap", to avoid random movements
directionVector[index] = thing
#print(directionVector)
elif modeOfMovement == 1:
print("One DOF mode")
# mode for only one joint at once rotation
# determine direction
directionVector = [0,0,0,0,0,0]
storedVal = 0
storedInd = 0
ind = -1
absJoystickValues = np.absolute(np.matrix(joystickValues))
storedInd = np.argmax(absJoystickValues)
storedVal = joystickValues[storedInd]
# introduce some "sensitivity gap" to avoid random movement
if abs(storedVal) > 0.05:
# if storedInd == 3 and modeOfOperation == 3:
# if savedJointAngles[5] > 0:
# directionVector[storedInd] = storedVal
# else:on
# directionVector[storedInd] = -storedVal
# else:
directionVector[storedInd] = storedVal
#print(directionVector)
# needed specifically to make thigs coincide with our arm
for i in range( len(directionVector) ):
directionVector[i] = -directionVector[i]
#xyz > yxz > zxy
# swap x with y
tempval = copy.deepcopy( directionVector[0] )
directionVector[0] = copy.deepcopy( directionVector[1] )
directionVector[1] = tempval
# in new translation swap z and y
tempval2 = copy.deepcopy( directionVector[2] )
directionVector[2] = copy.deepcopy( directionVector[0] )
directionVector[0] = tempval2
# swap the z direction
directionVector[0] = -directionVector[0]
# rotations swaps. Remember for positionalIK mode it's rotations above yxz order
directionVector[3] = -directionVector[3]
directionVector[4] = directionVector[4]
directionVector[5] = -directionVector[5]
return directionVector
def updateGripperAngle(localSavedGripperAngle): # updates the gripper condition (open/closed)
buttons = getJoystickButtons()
global limitFlag
if limitFlag == False:
openedLimit = 100000000
closedLimit = -100000000
else:
openedLimit = 21000
closedLimit = 0
# servo moves in the range 0 -1023
updatedGripperAngle = localSavedGripperAngle
step = 200
if buttons[22] == 1:
if updatedGripperAngle+step <= openedLimit:890o
updatedGripperAngle += step
else:
print("Gripper completely open")
elif buttons[25] == 1:
if updatedGripperAngle-step >= closedLimit:
updatedGripperAngle -= step
else:
print("Gripper completely closed")
return updatedGripperAngle
def visualizeArm(jointAngles):
copyJointAngles = copy.deepcopy(jointAngles)
#print("Values on visualization: {}".format(copyJointAngles))
global robot
global initAngles
for i in range(len(copyJointAngles)):
copyJointAngles[i] += initAngles[i]
robot.SetActiveDOFValues(copyJointAngles)
#print("Initial angles: {}".format(initAngles))
def sendMessage(message):
global message_to_send
#global conn
global connFlag
global THREAD_MODE_FLAG
if connFlag == 1:
if THREAD_MODE_FLAG:
message_lock.acquire()
try:
message_to_send = message
finally:
message_lock.release()
else:
put_msg(message)
def makeDHTable(jointAngles): # making a dh table for kinematics, specific for the exact robot
#print("Current joint angles: {}".format(jointAngles))
#print(jointAngles)
# DH Table with entries in the format: [a, alpha, d, theta]
# First links are first entries
DHTable = [ [0, math.pi/2, 5.5, jointAngles[0]],
[36, 0, 0, jointAngles[1]],
[0, math.pi/2, 0, jointAngles[2]],
[0, -math.pi/2, 35.683, jointAngles[3]],
[0, math.pi/2, 0, jointAngles[4]],
[0, 0, 18, jointAngles[5]] ]
return DHTable
'''
👆👆👆👆 ed
DHTable = [ [0, math.pi/2, 6.162, jointAngles[0]],
[36, 0, 0, jointAngles[1]],
[27.94, 0, 0, jointAngles[2]],
[23.682, math.pi/2, 0, jointAngles[3]],
[0, math.pi/2, 0, jointAngles[4]],
[0, 0, 10, jointAngles[5]] ]
#end effector length not determined yet, 10 can change
'''
def updateAngles(DHTable, updatedDHTable, joystickDirection): # update angles during movement
global k
global modeOfOperation
global qlim
global maxRot
if modeOfOperation == 1:
#Manual mode
uq1 = DHTable[0][3] + 0.002 * 2*math.pi * joystickDirection[1]#sr
uq2 = DHTable[1][3] + 0.0006 * 2*math.pi * joystickDirection[2]#sp
uq3 = DHTable[2][3] + 0.001 * 2*math.pi * joystickDirection[0]#eb
uq4 = DHTable[3][3] + 0.005 * 2*math.pi * joystickDirection[4]#w3
uq5 = DHTable[4][3] + 0.005 * 2*math.pi * joystickDirection[3]#w1
uq6 = DHTable[5][3] + 0.005 * 2*math.pi * joystickDirection[5]#w2
elif modeOfOperation == 2:
#Positional IK mode
uq1 = updatedDHTable[0][3]
uq2 = updatedDHTable[1][3]
uq3 = updatedDHTable[2][3]
uq4 = DHTable[3][3] + updatedDHTable[3][3]
uq5 = DHTable[4][3] + updatedDHTable[4][3]
uq6 = DHTable[5][3] + updatedDHTable[5][3]
elif modeOfOperation == 3:
#Full IK mode
uq1 = updatedDHTable[0][3]
uq2 = updatedDHTable[1][3]
uq3 = updatedDHTable[2][3]
uq4 = updatedDHTable[3][3]
uq5 = updatedDHTable[4][3]
uq6 = updatedDHTable[5][3]
uq = [uq1, uq2, uq3, uq4, uq5, uq6]
update = 1
for i in range(6):
if(uq[i] <= qlim[i][0] or uq[i] >= qlim[i][1] or abs(uq[i] - DHTable[i][3]) > maxRot):
update = 0
break
if(update == 0):
for i in range(6):
uq[i] = DHTable[i][3] #Do not change angle if it exceeds the limits.
return uq
def manual(): # manual mode of operating the arm
# get the direction value to move in
joystickDirection = getJoystickDirection()
#print("Current joystick direction:")
#print(joystickDirection)
# get the current joint angles of the arm
global savedJointAngles
global savedGripperAngle
jointAngles = copy.deepcopy(savedJointAngles)
DHTable = makeDHTable(jointAngles)
# do forward kinematics
DHTableCopy = copy.deepcopy(DHTable)
#homTransMatrix = forwardKinematics(DHTableCopy)
#print("Current position: " )
#print([ homTransMatrix[0][3], homTransMatrix[1][3], homTransMatrix[2][3] ])
visualizeArm(jointAngles)
uq = updateAngles(DHTable, 0, joystickDirection)
# update gripper value
gripperAngleNew = updateGripperAngle(savedGripperAngle)
try:
jointAngles = copy.deepcopy( uq )
#print("Updated joint angles: {}".format(jointAngles))
#print(jointAngles)
savedJointAngles = copy.deepcopy(jointAngles)
savedGripperAngle = gripperAngleNew
# MOVE THE ARM TO THE NEW PLACE!!!!!!!!!!
sendAngles = [ savedJointAngles[0], savedJointAngles[1], savedJointAngles[2], savedJointAngles[3], savedJointAngles[4], savedJointAngles[5], savedGripperAngle ]
sendAngleValues(sendAngles)
visualizeArm(savedJointAngles)
print("Joint angles and gripper: \n Shoulder Rotation(q1): {} \n Shoulder Pitch(q2): {} \n Elbow(q3): {} \n W1(q4): {} \n W2(q5): {} \n W3(q6): {} \n Gripper value: {} \n".format( savedJointAngles[0]*180/math.pi, savedJointAngles[1]*180/math.pi, savedJointAngles[2]*180/math.pi, savedJointAngles[3]*180/math.pi, savedJointAngles[4]*180/math.pi, savedJointAngles[5]*180/math.pi, savedGripperAngle ) )
#print( np.array(savedJointAngles) * 180/math.pi )
except:
print("Exception encountered")
# TODO: fix undefined q1, etc here
jointAngles = copy.deepcopy( [q1,q2,q3,q4,q5,q6] )
#print("Updated joint angles: {}".format(jointAngles))
savedJointAngles = copy.deepcopy(jointAngles)
savedGripperAngle = savedGripperAngle
# MOVE THE ARM TO THE NEW PLACE!!!!!!!!!!
sendAngles = [ savedJointAngles[0], savedJointAngles[1], savedJointAngles[2], savedJointAngles[3], savedJointAngles[4], savedJointAngles[5], savedGripperAngle ]
sendAngleValues(sendAngles)
visualizeArm(savedJointAngles)
print("Joint angles and gripper: \n Shoulder Rotation(q1): {} \n Shoulder Pitch(q2): {} \n Elbow(q3): {} \n W1(q4): {} \n W2(q5): {} \n W3(q6): {} \n Gripper value: {} \n".format( savedJointAngles[0]*180/math.pi, savedJointAngles[1]*180/math.pi, savedJointAngles[2]*180/math.pi, savedJointAngles[3]*180/math.pi, savedJointAngles[4]*180/math.pi, savedJointAngles[5]*180/math.pi, savedGripperAngle ) )
#print( np.array(savedJointAngles) * 180/math.pi )
def positionalIK(): # perform inverse kinematics, move the arm to the new position
# get the direction value to move in
joystickDirection = getJoystickDirection()
#print("Current joystick direction:")
#print(joystickDirection)
# get the current joint angles of the arm
global savedJointAngles
global savedGripperAngle
jointAngles = copy.deepcopy(savedJointAngles)
# DH Table with entries in the format: [a, alpha, d, theta]
# First links are first entries
DHTable = makeDHTable(jointAngles)
# do forward kinematics
DHTableCopy = copy.deepcopy(DHTable)
homTransMatrix = forwardKinematics(DHTableCopy)
#print("Current position: " )
#print([ homTransMatrix[0][3], homTransMatrix[1][3], homTransMatrix[2][3] ])
visualizeArm(jointAngles)
# update homogenous transformation matrix based on joystick input
translationVector = joystickDirection[:3]
rotationVector = joystickDirection[3:]
copyHomTransMatrix = copy.deepcopy(homTransMatrix)
DHTableCopy2 = copy.deepcopy(DHTable)
updatedHomTransMatrix = updateHomTransMatrixPositional(copyHomTransMatrix, DHTableCopy2, translationVector, rotationVector)
#print("Updated position: ")
#print([ updatedHomTransMatrix[0][3], updatedHomTransMatrix[1][3], updatedHomTransMatrix[2][3] ])
# solve IK based on the new homTransMatrix
DHTableCopy3 = copy.deepcopy(DHTable)
copyUpdatedHomTransMatrix = copy.deepcopy(updatedHomTransMatrix)
updatedDHTable = inverseKinematicsPositional(DHTableCopy3, copyUpdatedHomTransMatrix, rotationVector)
uq = updateAngles(DHTable, updatedDHTable, joystickDirection)
# update gripper value
gripperAngleNew = updateGripperAngle(savedGripperAngle)
try:
jointAngles = copy.deepcopy( uq )
#print("Updated joint angles: {}".format(jointAngles))
#print(jointAngles)
savedGripperAngle = gripperAngleNew
# MOVE THE ARM TO THE NEW PLACE!!!!!!!!!!
sendAngles = [ savedJointAngles[0], savedJointAngles[1], savedJointAngles[2], savedJointAngles[3], savedJointAngles[4], savedJointAngles[5], savedGripperAngle ]
sendAngleValues(sendAngles)
savedJointAngles = copy.deepcopy(jointAngles)
visualizeArm(savedJointAngles)
print("Joint angles and gripper: \n Shoulder Rotation(q1): {} \n Shoulder Pitch(q2): {} \n Elbow(q3): {} \n W1(q4): {} \n W2(q5): {} \n W3(q6): {} \n Gripper value: {} \n".format( savedJointAngles[0]*180/math.pi, savedJointAngles[1]*180/math.pi, savedJointAngles[2]*180/math.pi, savedJointAngles[3]*180/math.pi, savedJointAngles[4]*180/math.pi, savedJointAngles[5]*180/math.pi, savedGripperAngle ) )
#print( np.array(savedJointAngles) * 180/math.pi )
except:
print("Exception encountered")
jointAngles = copy.deepcopy( [q1,q2,q3,q4,q5,q6] )
#print("Updated joint angles: {}".format(jointAngles))
savedGripperAngle = savedGripperAngle
# MOVE THE ARM TO THE NEW PLACE!!!!!!!!!!
sendAngles = [ savedJointAngles[0], savedJointAngles[1], savedJointAngles[2], savedJointAngles[3], savedJointAngles[4], savedJointAngles[5], savedGripperAngle ]
sendAngleValues(sendAngles)
savedJointAngles = copy.deepcopy(jointAngles)
visualizeArm(savedJointAngles)
print("Joint angles and gripper: \n Shoulder Rotation(q1): {} \n Shoulder Pitch(q2): {} \n Elbow(q3): {} \n W1(q4): {} \n W2(q5): {} \n W3(q6): {} \n Gripper value: {} \n".format( savedJointAngles[0]*180/math.pi, savedJointAngles[1]*180/math.pi, savedJointAngles[2]*180/math.pi, savedJointAngles[3]*180/math.pi, savedJointAngles[4]*180/math.pi, savedJointAngles[5]*180/math.pi, savedGripperAngle ) )
#print( np.array(savedJointAngles) * 180/math.pi )
def fullIK():
# get the direction value to move in
joystickDirection = getJoystickDirection()
#print("Current joystick direction: {}".format(joystickDirection))
# get the current joint angles of the arm
global savedJointAngles
global savedGripperAngle
jointAngles = copy.deepcopy(savedJointAngles)
DHTable = makeDHTable(jointAngles)
#print("Current position: " )
#print([ homTransMatrix[0][3], homTransMatrix[1][3], homTransMatrix[2][3] ])
visualizeArm(jointAngles)
# update homogenous transformation matrix based on joystick input
translationVector = joystickDirection[:3]
rotationVector = joystickDirection[3:]
DHTableCopy = copy.deepcopy(DHTable)
homTransMatrix = forwardKinematics(DHTableCopy)
#print homTransMatrix
copyHomTransMatrix = copy.deepcopy(homTransMatrix)
updatedHomTransMatrix = updateHomTransMatrix(copyHomTransMatrix, DHTableCopy, translationVector, rotationVector)
#print("Updated position: ")
#print updatedHomTransMatrix
# solve IK based on the new homTransMatrix
DHTableCopy2 = copy.deepcopy(DHTable)
#print "DHTable: "
#print DHTableCopy2
copyUpdatedHomTransMatrix = copy.deepcopy(updatedHomTransMatrix)
updatedDHTable = inverseKinematics(DHTableCopy2, copyUpdatedHomTransMatrix)
#print "DHTable updated: "
#print updatedDHTable
uq = updateAngles(DHTable, updatedDHTable, joystickDirection)
# update gripper value
gripperAngleNew = updateGripperAngle(savedGripperAngle)
try:
jointAngles = copy.deepcopy( uq )
#print("Updated joint angles: {}".format(jointAngles))
savedJointAngles = copy.deepcopy(jointAngles)
savedGripperAngle = gripperAngleNew
# MOVE THE ARM TO THE NEW PLACE!!!!!!!!!!
sendAngles = [ savedJointAngles[0], savedJointAngles[1], savedJointAngles[2], savedJointAngles[3], savedJointAngles[4], savedJointAngles[5], savedGripperAngle ]
sendAngleValues(sendAngles)
visualizeArm(savedJointAngles)
print("Joint angles and gripper: \n Shoulder Rotation(q1): {} \n Shoulder Pitch(q2): {} \n Elbow(q3): {} \n W1(q4): {} \n W2(q5): {} \n W3(q6): {} \n Gripper value: {} \n".format( savedJointAngles[0]*180/math.pi, savedJointAngles[1]*180/math.pi, savedJointAngles[2]*180/math.pi, savedJointAngles[3]*180/math.pi, savedJointAngles[4]*180/math.pi, savedJointAngles[5]*180/math.pi, savedGripperAngle ) )
#print( np.array(savedJointAngles) * 180/math.pi )
except:
print("Exception encountered")
jointAngles = copy.deepcopy( [q1,q2,q3,q4,q5,q6] )
#print("Updated joint angles: {}".format(jointAngles))
savedJointAngles = copy.deepcopy(jointAngles)
savedGripperAngle = savedGripperAngle
# MOVE THE ARM TO THE NEW PLACE!!!!!!!!!! or just do nothing?
sendAngles = [ savedJointAngles[0], savedJointAngles[1], savedJointAngles[2], savedJointAngles[3], savedJointAngles[4], savedJointAngles[5], savedGripperAngle ]
sendAngleValues(sendAngles)
visualizeArm(savedJointAngles)
print("Joint angles and gripper: \n Shoulder Rotation(q1): {} \n Shoulder Pitch(q2): {} \n Elbow(q3): {} \n W1(q4): {} \n W2(q5): {} \n W3(q6): {} \n Gripper value: {} \n".format( savedJointAngles[0]*180/math.pi, savedJointAngles[1]*180/math.pi, savedJointAngles[2]*180/math.pi, savedJointAngles[3]*180/math.pi, savedJointAngles[4]*180/math.pi, savedJointAngles[5]*180/math.pi, savedGripperAngle ) )
#print( np.array(savedJointAngles) * 180/math.pi )
def directControl(): # move the arm according to the joystick position
global THREAD_MODE_FLAG
# get the direction value to move in
joystickDirection = getJoystickDirection()
global k
sensitivity = k
i = 0
for elem in joystickDirection:
modElem = elem * sensitivity
if abs(modElem) > 1:
if modElem > 1:
modElem = 1.0
elif modElem < -1:
modElem = -1.0
joystickDirection[i] = modElem
i += 1
# print("Current joystick direction:")
# print(joystickDirection)
# get the current joint angles of the arm
global savedJointAngles
jointAngles = copy.deepcopy(savedJointAngles)
visualizeArm(jointAngles)
buttons = getJoystickButtons()
try:
# MOVE THE ARM TO THE NEW PLACE!!!!!!!!!!
if buttons[22] == 1:
gripperSpeed = -255
elif buttons[25] == 1:
gripperSpeed = 255
else:
gripperSpeed = 0
sendSpeeds = [ int(joystickDirection[1] * 255), int(joystickDirection[2] * 255), int(joystickDirection[0] * 255), int(-joystickDirection[4] * 255), int(joystickDirection[5] * 255), int(joystickDirection[3] * 255), gripperSpeed ]
sendAngleValues(sendSpeeds)
visualizeArm(savedJointAngles)
print("Joint angles and gripper: \n Shoulder Rotation(q1): {} \n Shoulder Pitch(q2): {} \n Elbow(q3): {} \n W1(q4): {} \n W2(q5): {} \n W3(q6): {} \n Gripper value: {} \n".format( savedJointAngles[0]*180/math.pi, savedJointAngles[1]*180/math.pi, savedJointAngles[2]*180/math.pi, savedJointAngles[3]*180/math.pi, savedJointAngles[4]*180/math.pi, savedJointAngles[5]*180/math.pi, savedGripperAngle ) )
#print( np.array(savedJointAngles) * 180/math.pi )
except:
print("Exception encountered")
# MOVE THE ARM TO THE NEW PLACE!!!!!!!!!!