-
Notifications
You must be signed in to change notification settings - Fork 814
/
core.py
1896 lines (1743 loc) · 72.4 KB
/
core.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
from __future__ import print_function
'''
***************************************************************************
Modern Robotics: Mechanics, Planning, and Control.
Code Library
***************************************************************************
Author: Huan Weng, Bill Hunt, Jarvis Schultz, Mikhail Todes,
Email: huanweng@u.northwestern.edu
Date: July 2018
***************************************************************************
Language: Python
Also available in: MATLAB, Mathematica
Required library: numpy
Optional library: matplotlib
***************************************************************************
'''
'''
*** IMPORTS ***
'''
import numpy as np
'''
*** BASIC HELPER FUNCTIONS ***
'''
def NearZero(z):
"""Determines whether a scalar is small enough to be treated as zero
:param z: A scalar input to check
:return: True if z is close to zero, false otherwise
Example Input:
z = -1e-7
Output:
True
"""
return abs(z) < 1e-6
def Normalize(V):
"""Normalizes a vector
:param V: A vector
:return: A unit vector pointing in the same direction as z
Example Input:
V = np.array([1, 2, 3])
Output:
np.array([0.26726124, 0.53452248, 0.80178373])
"""
return V / np.linalg.norm(V)
'''
*** CHAPTER 3: RIGID-BODY MOTIONS ***
'''
def RotInv(R):
"""Inverts a rotation matrix
:param R: A rotation matrix
:return: The inverse of R
Example Input:
R = np.array([[0, 0, 1],
[1, 0, 0],
[0, 1, 0]])
Output:
np.array([[0, 1, 0],
[0, 0, 1],
[1, 0, 0]])
"""
return np.array(R).T
def VecToso3(omg):
"""Converts a 3-vector to an so(3) representation
:param omg: A 3-vector
:return: The skew symmetric representation of omg
Example Input:
omg = np.array([1, 2, 3])
Output:
np.array([[ 0, -3, 2],
[ 3, 0, -1],
[-2, 1, 0]])
"""
return np.array([[0, -omg[2], omg[1]],
[omg[2], 0, -omg[0]],
[-omg[1], omg[0], 0]])
def so3ToVec(so3mat):
"""Converts an so(3) representation to a 3-vector
:param so3mat: A 3x3 skew-symmetric matrix
:return: The 3-vector corresponding to so3mat
Example Input:
so3mat = np.array([[ 0, -3, 2],
[ 3, 0, -1],
[-2, 1, 0]])
Output:
np.array([1, 2, 3])
"""
return np.array([so3mat[2][1], so3mat[0][2], so3mat[1][0]])
def AxisAng3(expc3):
"""Converts a 3-vector of exponential coordinates for rotation into
axis-angle form
:param expc3: A 3-vector of exponential coordinates for rotation
:return omghat: A unit rotation axis
:return theta: The corresponding rotation angle
Example Input:
expc3 = np.array([1, 2, 3])
Output:
(np.array([0.26726124, 0.53452248, 0.80178373]), 3.7416573867739413)
"""
return (Normalize(expc3), np.linalg.norm(expc3))
def MatrixExp3(so3mat):
"""Computes the matrix exponential of a matrix in so(3)
:param so3mat: A 3x3 skew-symmetric matrix
:return: The matrix exponential of so3mat
Example Input:
so3mat = np.array([[ 0, -3, 2],
[ 3, 0, -1],
[-2, 1, 0]])
Output:
np.array([[-0.69492056, 0.71352099, 0.08929286],
[-0.19200697, -0.30378504, 0.93319235],
[ 0.69297817, 0.6313497 , 0.34810748]])
"""
omgtheta = so3ToVec(so3mat)
if NearZero(np.linalg.norm(omgtheta)):
return np.eye(3)
else:
theta = AxisAng3(omgtheta)[1]
omgmat = so3mat / theta
return np.eye(3) + np.sin(theta) * omgmat \
+ (1 - np.cos(theta)) * np.dot(omgmat, omgmat)
def MatrixLog3(R):
"""Computes the matrix logarithm of a rotation matrix
:param R: A 3x3 rotation matrix
:return: The matrix logarithm of R
Example Input:
R = np.array([[0, 0, 1],
[1, 0, 0],
[0, 1, 0]])
Output:
np.array([[ 0, -1.20919958, 1.20919958],
[ 1.20919958, 0, -1.20919958],
[-1.20919958, 1.20919958, 0]])
"""
if NearZero(np.linalg.norm(R - np.eye(3))):
return np.zeros((3, 3))
elif NearZero(np.trace(R) + 1):
if not NearZero(1 + R[2][2]):
omg = (1.0 / np.sqrt(2 * (1 + R[2][2]))) \
* np.array([R[0][2], R[1][2], 1 + R[2][2]])
elif not NearZero(1 + R[1][1]):
omg = (1.0 / np.sqrt(2 * (1 + R[1][1]))) \
* np.array([R[0][1], 1 + R[1][1], R[2][1]])
else:
omg = (1.0 / np.sqrt(2 * (1 + R[0][0]))) \
* np.array([1 + R[0][0], R[1][0], R[2][0]])
return VecToso3(np.pi * omg)
else:
acosinput = (np.trace(R) - 1) / 2.0
if acosinput > 1:
acosinput = 1
elif acosinput < -1:
acosinput = -1
theta = np.arccos(acosinput)
return theta / 2.0 / np.sin(theta) * (R - np.array(R).T)
def RpToTrans(R, p):
"""Converts a rotation matrix and a position vector into homogeneous
tranformation matrix
:param R: A 3x3 rotation matrix
:param p: A 3-vector
:return: A homogeneous transformation matrix corresponding to the inputs
Example Input:
R = np.array([[1, 0, 0],
[0, 0, -1],
[0, 1, 0]])
p = np.array([1, 2, 5])
Output:
np.array([[1, 0, 0, 1],
[0, 0, -1, 2],
[0, 1, 0, 5],
[0, 0, 0, 1]])
"""
return np.r_[np.c_[R, p], [[0, 0, 0, 1]]]
def TransToRp(T):
"""Converts a homogeneous transformation matrix into a rotation matrix
and position vector
:param T: A homogeneous transformation matrix
:return R: The corresponding rotation matrix,
:return p: The corresponding position vector.
Example Input:
T = np.array([[1, 0, 0, 0],
[0, 0, -1, 0],
[0, 1, 0, 3],
[0, 0, 0, 1]])
Output:
(np.array([[1, 0, 0],
[0, 0, -1],
[0, 1, 0]]),
np.array([0, 0, 3]))
"""
T = np.array(T)
return T[0: 3, 0: 3], T[0: 3, 3]
def TransInv(T):
"""Inverts a homogeneous transformation matrix
:param T: A homogeneous transformation matrix
:return: The inverse of T
Uses the structure of transformation matrices to avoid taking a matrix
inverse, for efficiency.
Example input:
T = np.array([[1, 0, 0, 0],
[0, 0, -1, 0],
[0, 1, 0, 3],
[0, 0, 0, 1]])
Output:
np.array([[1, 0, 0, 0],
[0, 0, 1, -3],
[0, -1, 0, 0],
[0, 0, 0, 1]])
"""
R, p = TransToRp(T)
Rt = np.array(R).T
return np.r_[np.c_[Rt, -np.dot(Rt, p)], [[0, 0, 0, 1]]]
def VecTose3(V):
"""Converts a spatial velocity vector into a 4x4 matrix in se3
:param V: A 6-vector representing a spatial velocity
:return: The 4x4 se3 representation of V
Example Input:
V = np.array([1, 2, 3, 4, 5, 6])
Output:
np.array([[ 0, -3, 2, 4],
[ 3, 0, -1, 5],
[-2, 1, 0, 6],
[ 0, 0, 0, 0]])
"""
return np.r_[np.c_[VecToso3([V[0], V[1], V[2]]), [V[3], V[4], V[5]]],
np.zeros((1, 4))]
def se3ToVec(se3mat):
""" Converts an se3 matrix into a spatial velocity vector
:param se3mat: A 4x4 matrix in se3
:return: The spatial velocity 6-vector corresponding to se3mat
Example Input:
se3mat = np.array([[ 0, -3, 2, 4],
[ 3, 0, -1, 5],
[-2, 1, 0, 6],
[ 0, 0, 0, 0]])
Output:
np.array([1, 2, 3, 4, 5, 6])
"""
return np.r_[[se3mat[2][1], se3mat[0][2], se3mat[1][0]],
[se3mat[0][3], se3mat[1][3], se3mat[2][3]]]
def Adjoint(T):
"""Computes the adjoint representation of a homogeneous transformation
matrix
:param T: A homogeneous transformation matrix
:return: The 6x6 adjoint representation [AdT] of T
Example Input:
T = np.array([[1, 0, 0, 0],
[0, 0, -1, 0],
[0, 1, 0, 3],
[0, 0, 0, 1]])
Output:
np.array([[1, 0, 0, 0, 0, 0],
[0, 0, -1, 0, 0, 0],
[0, 1, 0, 0, 0, 0],
[0, 0, 3, 1, 0, 0],
[3, 0, 0, 0, 0, -1],
[0, 0, 0, 0, 1, 0]])
"""
R, p = TransToRp(T)
return np.r_[np.c_[R, np.zeros((3, 3))],
np.c_[np.dot(VecToso3(p), R), R]]
def ScrewToAxis(q, s, h):
"""Takes a parametric description of a scre axis and converts it to a
normalized screw axis
:param q: A point lying on the screw axis
:param s: A unit vector in the direction of the screw axis
:param h: The pitch of the screw axis
:return: A normalized screw axis described by the inputs
Example Input:
q = np.array([3, 0, 0])
s = np.array([0, 0, 1])
h = 2
Output:
np.array([0, 0, 1, 0, -3, 2])
"""
return np.r_[s, np.cross(q, s) + np.dot(h, s)]
def AxisAng6(expc6):
"""Converts a 6-vector of exponenation coordinates into screw axis-angle
form
:param expc6: A 6-vector of exponential corrdinates for rigid-body motion
S*theta
:return S: The corresponding normalized screw axis
:return theta: The distance traveled along/about S
Example Input:
expc6 = np.array([1, 0, 0, 1, 2, 3])
Output:
(np.array([1.0, 0.0, 0.0, 1.0, 2.0, 3.0]), 1.0)
"""
theta = np.linalg.norm([expc6[0], expc6[1], expc6[2]])
if NearZero(theta):
theta = np.linalg.norm([expc6[3], expc6[4], expc6[5]])
return (np.array(expc6 / theta), theta)
def MatrixExp6(se3mat):
"""Computes the matrix exponential of an se3 representation of
exponential coordinates
:param se3mat: A matrix in se3
:return: The matrix exponential of se3mat
Example Input:
se3mat = np.array([[0, 0, 0, 0],
[0, 0, -1.57079632, 2.35619449],
[0, 1.57079632, 0, 2.35619449],
[0, 0, 0, 0]])
Output:
np.array([[1.0, 0.0, 0.0, 0.0],
[0.0, 0.0, -1.0, 0.0],
[0.0, 1.0, 0.0, 3.0],
[ 0, 0, 0, 1]])
"""
se3mat = np.array(se3mat)
omgtheta = so3ToVec(se3mat[0: 3, 0: 3])
if NearZero(np.linalg.norm(omgtheta)):
return np.r_[np.c_[np.eye(3), se3mat[0: 3, 3]], [[0, 0, 0, 1]]]
else:
theta = AxisAng3(omgtheta)[1]
omgmat = se3mat[0: 3, 0: 3] / theta
return np.r_[np.c_[MatrixExp3(se3mat[0: 3, 0: 3]),
np.dot(np.eye(3) * theta \
+ (1 - np.cos(theta)) * omgmat \
+ (theta - np.sin(theta)) \
* np.dot(omgmat,omgmat),
se3mat[0: 3, 3]) / theta],
[[0, 0, 0, 1]]]
def MatrixLog6(T):
"""Computes the matrix logarithm of a homogeneous transformation matrix
:param R: A matrix in SE3
:return: The matrix logarithm of R
Example Input:
T = np.array([[1, 0, 0, 0], [0, 0, -1, 0], [0, 1, 0, 3],
[0, 0, 0, 1]])
Output:
np.array([[0, 0, 0, 0]
[0, 0, -1.57079633, 2.35619449]
[0, 1.57079633, 0, 2.35619449]
[0, 0, 0, 0]])
"""
R, p = TransToRp(T)
if NearZero(np.linalg.norm(R - np.eye(3))):
return np.r_[np.c_[np.zeros((3, 3)),
[T[0][3], T[1][3], T[2][3]]],
[[0, 0, 0, 0]]]
else:
acosinput = (np.trace(R) - 1) / 2.0
if acosinput > 1:
acosinput = 1
elif acosinput < -1:
acosinput = -1
theta = np.arccos(acosinput)
omgmat = MatrixLog3(R)
return np.r_[np.c_[omgmat,
np.dot(np.eye(3) - omgmat / 2.0 \
+ (1.0 / theta - 1.0 / np.tan(theta / 2.0) / 2) \
* np.dot(omgmat,omgmat) / theta,[T[0][3],
T[1][3],
T[2][3]])],
[[0, 0, 0, 0]]]
def ProjectToSO3(mat):
"""Returns a projection of mat into SO(3)
:param mat: A matrix near SO(3) to project to SO(3)
:return: The closest matrix to R that is in SO(3)
Projects a matrix mat to the closest matrix in SO(3) using singular-value
decomposition (see
http://hades.mech.northwestern.edu/index.php/Modern_Robotics_Linear_Algebra_Review).
This function is only appropriate for matrices close to SO(3).
Example Input:
mat = np.array([[ 0.675, 0.150, 0.720],
[ 0.370, 0.771, -0.511],
[-0.630, 0.619, 0.472]])
Output:
np.array([[ 0.67901136, 0.14894516, 0.71885945],
[ 0.37320708, 0.77319584, -0.51272279],
[-0.63218672, 0.61642804, 0.46942137]])
"""
U, s, Vh = np.linalg.svd(mat)
R = np.dot(U, Vh)
if np.linalg.det(R) < 0:
# In this case the result may be far from mat.
R[:, s[2, 2]] = -R[:, s[2, 2]]
return R
def ProjectToSE3(mat):
"""Returns a projection of mat into SE(3)
:param mat: A 4x4 matrix to project to SE(3)
:return: The closest matrix to T that is in SE(3)
Projects a matrix mat to the closest matrix in SE(3) using singular-value
decomposition (see
http://hades.mech.northwestern.edu/index.php/Modern_Robotics_Linear_Algebra_Review).
This function is only appropriate for matrices close to SE(3).
Example Input:
mat = np.array([[ 0.675, 0.150, 0.720, 1.2],
[ 0.370, 0.771, -0.511, 5.4],
[-0.630, 0.619, 0.472, 3.6],
[ 0.003, 0.002, 0.010, 0.9]])
Output:
np.array([[ 0.67901136, 0.14894516, 0.71885945, 1.2 ],
[ 0.37320708, 0.77319584, -0.51272279, 5.4 ],
[-0.63218672, 0.61642804, 0.46942137, 3.6 ],
[ 0. , 0. , 0. , 1. ]])
"""
mat = np.array(mat)
return RpToTrans(ProjectToSO3(mat[:3, :3]), mat[:3, 3])
def DistanceToSO3(mat):
"""Returns the Frobenius norm to describe the distance of mat from the
SO(3) manifold
:param mat: A 3x3 matrix
:return: A quantity describing the distance of mat from the SO(3)
manifold
Computes the distance from mat to the SO(3) manifold using the following
method:
If det(mat) <= 0, return a large number.
If det(mat) > 0, return norm(mat^T.mat - I).
Example Input:
mat = np.array([[ 1.0, 0.0, 0.0 ],
[ 0.0, 0.1, -0.95],
[ 0.0, 1.0, 0.1 ]])
Output:
0.08835
"""
if np.linalg.det(mat) > 0:
return np.linalg.norm(np.dot(np.array(mat).T, mat) - np.eye(3))
else:
return 1e+9
def DistanceToSE3(mat):
"""Returns the Frobenius norm to describe the distance of mat from the
SE(3) manifold
:param mat: A 4x4 matrix
:return: A quantity describing the distance of mat from the SE(3)
manifold
Computes the distance from mat to the SE(3) manifold using the following
method:
Compute the determinant of matR, the top 3x3 submatrix of mat.
If det(matR) <= 0, return a large number.
If det(matR) > 0, replace the top 3x3 submatrix of mat with matR^T.matR,
and set the first three entries of the fourth column of mat to zero. Then
return norm(mat - I).
Example Input:
mat = np.array([[ 1.0, 0.0, 0.0, 1.2 ],
[ 0.0, 0.1, -0.95, 1.5 ],
[ 0.0, 1.0, 0.1, -0.9 ],
[ 0.0, 0.0, 0.1, 0.98 ]])
Output:
0.134931
"""
matR = np.array(mat)[0: 3, 0: 3]
if np.linalg.det(matR) > 0:
return np.linalg.norm(np.r_[np.c_[np.dot(np.transpose(matR), matR),
np.zeros((3, 1))],
[np.array(mat)[3, :]]] - np.eye(4))
else:
return 1e+9
def TestIfSO3(mat):
"""Returns true if mat is close to or on the manifold SO(3)
:param mat: A 3x3 matrix
:return: True if mat is very close to or in SO(3), false otherwise
Computes the distance d from mat to the SO(3) manifold using the
following method:
If det(mat) <= 0, d = a large number.
If det(mat) > 0, d = norm(mat^T.mat - I).
If d is close to zero, return true. Otherwise, return false.
Example Input:
mat = np.array([[1.0, 0.0, 0.0 ],
[0.0, 0.1, -0.95],
[0.0, 1.0, 0.1 ]])
Output:
False
"""
return abs(DistanceToSO3(mat)) < 1e-3
def TestIfSE3(mat):
"""Returns true if mat is close to or on the manifold SE(3)
:param mat: A 3x3 matrix
:return: True if mat is very close to or in SE(3), false otherwise
Computes the distance d from mat to the SE(3) manifold using the
following method:
Compute the determinant of the top 3x3 submatrix of mat.
If det(mat) <= 0, d = a large number.
If det(mat) > 0, replace the top 3x3 submatrix of mat with mat^T.mat, and
set the first three entries of the fourth column of mat to zero.
Then d = norm(T - I).
If d is close to zero, return true. Otherwise, return false.
Example Input:
mat = np.array([[1.0, 0.0, 0.0, 1.2],
[0.0, 0.1, -0.95, 1.5],
[0.0, 1.0, 0.1, -0.9],
[0.0, 0.0, 0.1, 0.98]])
Output:
False
"""
return abs(DistanceToSE3(mat)) < 1e-3
'''
*** CHAPTER 4: FORWARD KINEMATICS ***
'''
def FKinBody(M, Blist, thetalist):
"""Computes forward kinematics in the body frame for an open chain robot
:param M: The home configuration (position and orientation) of the end-
effector
:param Blist: The joint screw axes in the end-effector frame when the
manipulator is at the home position, in the format of a
matrix with axes as the columns
:param thetalist: A list of joint coordinates
:return: A homogeneous transformation matrix representing the end-
effector frame when the joints are at the specified coordinates
(i.t.o Body Frame)
Example Input:
M = np.array([[-1, 0, 0, 0], [0, 1, 0, 6], [0, 0, -1, 2],
[0, 0, 0, 1]])
Blist = np.array([[0, 0, -1, 2, 0, 0],
[0, 0, 0, 0, 1, 0],
[0, 0, 1, 0, 0, 0.1]]).T
thetalist = np.array([np.pi / 2.0, 3, np.pi])
Output:
np.array([[0, 1, 0, -5],
[1, 0, 0, 4],
[0, 0, -1, 1.68584073],
[0, 0, 0, 1]])
"""
T = np.array(M)
for i in range(len(thetalist)):
T = np.dot(T, MatrixExp6(VecTose3(np.array(Blist)[:, i] \
* thetalist[i])))
return T
def FKinSpace(M, Slist, thetalist):
"""Computes forward kinematics in the space frame for an open chain robot
:param M: The home configuration (position and orientation) of the end-
effector
:param Slist: The joint screw axes in the space frame when the
manipulator is at the home position, in the format of a
matrix with axes as the columns
:param thetalist: A list of joint coordinates
:return: A homogeneous transformation matrix representing the end-
effector frame when the joints are at the specified coordinates
(i.t.o Space Frame)
Example Input:
M = np.array([[-1, 0, 0, 0],
[ 0, 1, 0, 6],
[ 0, 0, -1, 2],
[ 0, 0, 0, 1]])
Slist = np.array([[0, 0, 1, 4, 0, 0],
[0, 0, 0, 0, 1, 0],
[0, 0, -1, -6, 0, -0.1]]).T
thetalist = np.array([np.pi / 2.0, 3, np.pi])
Output:
np.array([[0, 1, 0, -5],
[1, 0, 0, 4],
[0, 0, -1, 1.68584073],
[0, 0, 0, 1]])
"""
T = np.array(M)
for i in range(len(thetalist) - 1, -1, -1):
T = np.dot(MatrixExp6(VecTose3(np.array(Slist)[:, i] \
* thetalist[i])), T)
return T
'''
*** CHAPTER 5: VELOCITY KINEMATICS AND STATICS***
'''
def JacobianBody(Blist, thetalist):
"""Computes the body Jacobian for an open chain robot
:param Blist: The joint screw axes in the end-effector frame when the
manipulator is at the home position, in the format of a
matrix with axes as the columns
:param thetalist: A list of joint coordinates
:return: The body Jacobian corresponding to the inputs (6xn real
numbers)
Example Input:
Blist = np.array([[0, 0, 1, 0, 0.2, 0.2],
[1, 0, 0, 2, 0, 3],
[0, 1, 0, 0, 2, 1],
[1, 0, 0, 0.2, 0.3, 0.4]]).T
thetalist = np.array([0.2, 1.1, 0.1, 1.2])
Output:
np.array([[-0.04528405, 0.99500417, 0, 1]
[ 0.74359313, 0.09304865, 0.36235775, 0]
[-0.66709716, 0.03617541, -0.93203909, 0]
[ 2.32586047, 1.66809, 0.56410831, 0.2]
[-1.44321167, 2.94561275, 1.43306521, 0.3]
[-2.06639565, 1.82881722, -1.58868628, 0.4]])
"""
Jb = np.array(Blist).copy().astype(np.float)
T = np.eye(4)
for i in range(len(thetalist) - 2, -1, -1):
T = np.dot(T,MatrixExp6(VecTose3(np.array(Blist)[:, i + 1] \
* -thetalist[i + 1])))
Jb[:, i] = np.dot(Adjoint(T), np.array(Blist)[:, i])
return Jb
def JacobianSpace(Slist, thetalist):
"""Computes the space Jacobian for an open chain robot
:param Slist: The joint screw axes in the space frame when the
manipulator is at the home position, in the format of a
matrix with axes as the columns
:param thetalist: A list of joint coordinates
:return: The space Jacobian corresponding to the inputs (6xn real
numbers)
Example Input:
Slist = np.array([[0, 0, 1, 0, 0.2, 0.2],
[1, 0, 0, 2, 0, 3],
[0, 1, 0, 0, 2, 1],
[1, 0, 0, 0.2, 0.3, 0.4]]).T
thetalist = np.array([0.2, 1.1, 0.1, 1.2])
Output:
np.array([[ 0, 0.98006658, -0.09011564, 0.95749426]
[ 0, 0.19866933, 0.4445544, 0.28487557]
[ 1, 0, 0.89120736, -0.04528405]
[ 0, 1.95218638, -2.21635216, -0.51161537]
[0.2, 0.43654132, -2.43712573, 2.77535713]
[0.2, 2.96026613, 3.23573065, 2.22512443]])
"""
Js = np.array(Slist).copy().astype(np.float)
T = np.eye(4)
for i in range(1, len(thetalist)):
T = np.dot(T, MatrixExp6(VecTose3(np.array(Slist)[:, i - 1] \
* thetalist[i - 1])))
Js[:, i] = np.dot(Adjoint(T), np.array(Slist)[:, i])
return Js
'''
*** CHAPTER 6: INVERSE KINEMATICS ***
'''
def IKinBody(Blist, M, T, thetalist0, eomg, ev):
"""Computes inverse kinematics in the body frame for an open chain robot
:param Blist: The joint screw axes in the end-effector frame when the
manipulator is at the home position, in the format of a
matrix with axes as the columns
:param M: The home configuration of the end-effector
:param T: The desired end-effector configuration Tsd
:param thetalist0: An initial guess of joint angles that are close to
satisfying Tsd
:param eomg: A small positive tolerance on the end-effector orientation
error. The returned joint angles must give an end-effector
orientation error less than eomg
:param ev: A small positive tolerance on the end-effector linear position
error. The returned joint angles must give an end-effector
position error less than ev
:return thetalist: Joint angles that achieve T within the specified
tolerances,
:return success: A logical value where TRUE means that the function found
a solution and FALSE means that it ran through the set
number of maximum iterations without finding a solution
within the tolerances eomg and ev.
Uses an iterative Newton-Raphson root-finding method.
The maximum number of iterations before the algorithm is terminated has
been hardcoded in as a variable called maxiterations. It is set to 20 at
the start of the function, but can be changed if needed.
Example Input:
Blist = np.array([[0, 0, -1, 2, 0, 0],
[0, 0, 0, 0, 1, 0],
[0, 0, 1, 0, 0, 0.1]]).T
M = np.array([[-1, 0, 0, 0],
[ 0, 1, 0, 6],
[ 0, 0, -1, 2],
[ 0, 0, 0, 1]])
T = np.array([[0, 1, 0, -5],
[1, 0, 0, 4],
[0, 0, -1, 1.6858],
[0, 0, 0, 1]])
thetalist0 = np.array([1.5, 2.5, 3])
eomg = 0.01
ev = 0.001
Output:
(np.array([1.57073819, 2.999667, 3.14153913]), True)
"""
thetalist = np.array(thetalist0).copy()
i = 0
maxiterations = 20
Vb = se3ToVec(MatrixLog6(np.dot(TransInv(FKinBody(M, Blist, \
thetalist)), T)))
err = np.linalg.norm([Vb[0], Vb[1], Vb[2]]) > eomg \
or np.linalg.norm([Vb[3], Vb[4], Vb[5]]) > ev
while err and i < maxiterations:
thetalist = thetalist \
+ np.dot(np.linalg.pinv(JacobianBody(Blist, \
thetalist)), Vb)
i = i + 1
Vb \
= se3ToVec(MatrixLog6(np.dot(TransInv(FKinBody(M, Blist, \
thetalist)), T)))
err = np.linalg.norm([Vb[0], Vb[1], Vb[2]]) > eomg \
or np.linalg.norm([Vb[3], Vb[4], Vb[5]]) > ev
return (thetalist, not err)
def IKinSpace(Slist, M, T, thetalist0, eomg, ev):
"""Computes inverse kinematics in the space frame for an open chain robot
:param Slist: The joint screw axes in the space frame when the
manipulator is at the home position, in the format of a
matrix with axes as the columns
:param M: The home configuration of the end-effector
:param T: The desired end-effector configuration Tsd
:param thetalist0: An initial guess of joint angles that are close to
satisfying Tsd
:param eomg: A small positive tolerance on the end-effector orientation
error. The returned joint angles must give an end-effector
orientation error less than eomg
:param ev: A small positive tolerance on the end-effector linear position
error. The returned joint angles must give an end-effector
position error less than ev
:return thetalist: Joint angles that achieve T within the specified
tolerances,
:return success: A logical value where TRUE means that the function found
a solution and FALSE means that it ran through the set
number of maximum iterations without finding a solution
within the tolerances eomg and ev.
Uses an iterative Newton-Raphson root-finding method.
The maximum number of iterations before the algorithm is terminated has
been hardcoded in as a variable called maxiterations. It is set to 20 at
the start of the function, but can be changed if needed.
Example Input:
Slist = np.array([[0, 0, 1, 4, 0, 0],
[0, 0, 0, 0, 1, 0],
[0, 0, -1, -6, 0, -0.1]]).T
M = np.array([[-1, 0, 0, 0], [0, 1, 0, 6], [0, 0, -1, 2], [0, 0, 0, 1]])
T = np.array([[0, 1, 0, -5],
[1, 0, 0, 4],
[0, 0, -1, 1.6858],
[0, 0, 0, 1]])
thetalist0 = np.array([1.5, 2.5, 3])
eomg = 0.01
ev = 0.001
Output:
(np.array([ 1.57073783, 2.99966384, 3.1415342 ]), True)
"""
thetalist = np.array(thetalist0).copy()
i = 0
maxiterations = 20
Tsb = FKinSpace(M,Slist, thetalist)
Vs = np.dot(Adjoint(Tsb), \
se3ToVec(MatrixLog6(np.dot(TransInv(Tsb), T))))
err = np.linalg.norm([Vs[0], Vs[1], Vs[2]]) > eomg \
or np.linalg.norm([Vs[3], Vs[4], Vs[5]]) > ev
while err and i < maxiterations:
thetalist = thetalist \
+ np.dot(np.linalg.pinv(JacobianSpace(Slist, \
thetalist)), Vs)
i = i + 1
Tsb = FKinSpace(M, Slist, thetalist)
Vs = np.dot(Adjoint(Tsb), \
se3ToVec(MatrixLog6(np.dot(TransInv(Tsb), T))))
err = np.linalg.norm([Vs[0], Vs[1], Vs[2]]) > eomg \
or np.linalg.norm([Vs[3], Vs[4], Vs[5]]) > ev
return (thetalist, not err)
'''
*** CHAPTER 8: DYNAMICS OF OPEN CHAINS ***
'''
def ad(V):
"""Calculate the 6x6 matrix [adV] of the given 6-vector
:param V: A 6-vector spatial velocity
:return: The corresponding 6x6 matrix [adV]
Used to calculate the Lie bracket [V1, V2] = [adV1]V2
Example Input:
V = np.array([1, 2, 3, 4, 5, 6])
Output:
np.array([[ 0, -3, 2, 0, 0, 0],
[ 3, 0, -1, 0, 0, 0],
[-2, 1, 0, 0, 0, 0],
[ 0, -6, 5, 0, -3, 2],
[ 6, 0, -4, 3, 0, -1],
[-5, 4, 0, -2, 1, 0]])
"""
omgmat = VecToso3([V[0], V[1], V[2]])
return np.r_[np.c_[omgmat, np.zeros((3, 3))],
np.c_[VecToso3([V[3], V[4], V[5]]), omgmat]]
def InverseDynamics(thetalist, dthetalist, ddthetalist, g, Ftip, Mlist, \
Glist, Slist):
"""Computes inverse dynamics in the space frame for an open chain robot
:param thetalist: n-vector of joint variables
:param dthetalist: n-vector of joint rates
:param ddthetalist: n-vector of joint accelerations
:param g: Gravity vector g
:param Ftip: Spatial force applied by the end-effector expressed in frame
{n+1}
:param Mlist: List of link frames {i} relative to {i-1} at the home
position
:param Glist: Spatial inertia matrices Gi of the links
:param Slist: Screw axes Si of the joints in a space frame, in the format
of a matrix with axes as the columns
:return: The n-vector of required joint forces/torques
This function uses forward-backward Newton-Euler iterations to solve the
equation:
taulist = Mlist(thetalist)ddthetalist + c(thetalist,dthetalist) \
+ g(thetalist) + Jtr(thetalist)Ftip
Example Input (3 Link Robot):
thetalist = np.array([0.1, 0.1, 0.1])
dthetalist = np.array([0.1, 0.2, 0.3])
ddthetalist = np.array([2, 1.5, 1])
g = np.array([0, 0, -9.8])
Ftip = np.array([1, 1, 1, 1, 1, 1])
M01 = np.array([[1, 0, 0, 0],
[0, 1, 0, 0],
[0, 0, 1, 0.089159],
[0, 0, 0, 1]])
M12 = np.array([[ 0, 0, 1, 0.28],
[ 0, 1, 0, 0.13585],
[-1, 0, 0, 0],
[ 0, 0, 0, 1]])
M23 = np.array([[1, 0, 0, 0],
[0, 1, 0, -0.1197],
[0, 0, 1, 0.395],
[0, 0, 0, 1]])
M34 = np.array([[1, 0, 0, 0],
[0, 1, 0, 0],
[0, 0, 1, 0.14225],
[0, 0, 0, 1]])
G1 = np.diag([0.010267, 0.010267, 0.00666, 3.7, 3.7, 3.7])
G2 = np.diag([0.22689, 0.22689, 0.0151074, 8.393, 8.393, 8.393])
G3 = np.diag([0.0494433, 0.0494433, 0.004095, 2.275, 2.275, 2.275])
Glist = np.array([G1, G2, G3])
Mlist = np.array([M01, M12, M23, M34])
Slist = np.array([[1, 0, 1, 0, 1, 0],
[0, 1, 0, -0.089, 0, 0],
[0, 1, 0, -0.089, 0, 0.425]]).T
Output:
np.array([74.69616155, -33.06766016, -3.23057314])
"""
n = len(thetalist)
Mi = np.eye(4)
Ai = np.zeros((6, n))
AdTi = [[None]] * (n + 1)
Vi = np.zeros((6, n + 1))
Vdi = np.zeros((6, n + 1))
Vdi[:, 0] = np.r_[[0, 0, 0], -np.array(g)]
AdTi[n] = Adjoint(TransInv(Mlist[n]))
Fi = np.array(Ftip).copy()
taulist = np.zeros(n)
for i in range(n):
Mi = np.dot(Mi,Mlist[i])
Ai[:, i] = np.dot(Adjoint(TransInv(Mi)), np.array(Slist)[:, i])
AdTi[i] = Adjoint(np.dot(MatrixExp6(VecTose3(Ai[:, i] * \
-thetalist[i])), \
TransInv(Mlist[i])))
Vi[:, i + 1] = np.dot(AdTi[i], Vi[:,i]) + Ai[:, i] * dthetalist[i]
Vdi[:, i + 1] = np.dot(AdTi[i], Vdi[:, i]) \
+ Ai[:, i] * ddthetalist[i] \
+ np.dot(ad(Vi[:, i + 1]), Ai[:, i]) * dthetalist[i]
for i in range (n - 1, -1, -1):
Fi = np.dot(np.array(AdTi[i + 1]).T, Fi) \
+ np.dot(np.array(Glist[i]), Vdi[:, i + 1]) \
- np.dot(np.array(ad(Vi[:, i + 1])).T, \
np.dot(np.array(Glist[i]), Vi[:, i + 1]))
taulist[i] = np.dot(np.array(Fi).T, Ai[:, i])
return taulist
def MassMatrix(thetalist, Mlist, Glist, Slist):
"""Computes the mass matrix of an open chain robot based on the given
configuration
:param thetalist: A list of joint variables
:param Mlist: List of link frames i relative to i-1 at the home position
:param Glist: Spatial inertia matrices Gi of the links
:param Slist: Screw axes Si of the joints in a space frame, in the format
of a matrix with axes as the columns
:return: The numerical inertia matrix M(thetalist) of an n-joint serial
chain at the given configuration thetalist
This function calls InverseDynamics n times, each time passing a
ddthetalist vector with a single element equal to one and all other
inputs set to zero.
Each call of InverseDynamics generates a single column, and these columns
are assembled to create the inertia matrix.
Example Input (3 Link Robot):
thetalist = np.array([0.1, 0.1, 0.1])
M01 = np.array([[1, 0, 0, 0],
[0, 1, 0, 0],
[0, 0, 1, 0.089159],
[0, 0, 0, 1]])
M12 = np.array([[ 0, 0, 1, 0.28],
[ 0, 1, 0, 0.13585],
[-1, 0, 0, 0],
[ 0, 0, 0, 1]])
M23 = np.array([[1, 0, 0, 0],
[0, 1, 0, -0.1197],
[0, 0, 1, 0.395],
[0, 0, 0, 1]])
M34 = np.array([[1, 0, 0, 0],
[0, 1, 0, 0],
[0, 0, 1, 0.14225],
[0, 0, 0, 1]])
G1 = np.diag([0.010267, 0.010267, 0.00666, 3.7, 3.7, 3.7])
G2 = np.diag([0.22689, 0.22689, 0.0151074, 8.393, 8.393, 8.393])
G3 = np.diag([0.0494433, 0.0494433, 0.004095, 2.275, 2.275, 2.275])
Glist = np.array([G1, G2, G3])
Mlist = np.array([M01, M12, M23, M34])
Slist = np.array([[1, 0, 1, 0, 1, 0],
[0, 1, 0, -0.089, 0, 0],
[0, 1, 0, -0.089, 0, 0.425]]).T
Output:
np.array([[ 2.25433380e+01, -3.07146754e-01, -7.18426391e-03]
[-3.07146754e-01, 1.96850717e+00, 4.32157368e-01]
[-7.18426391e-03, 4.32157368e-01, 1.91630858e-01]])
"""
n = len(thetalist)
M = np.zeros((n, n))
for i in range (n):
ddthetalist = [0] * n
ddthetalist[i] = 1
M[:, i] = InverseDynamics(thetalist, [0] * n, ddthetalist, \
[0, 0, 0], [0, 0, 0, 0, 0, 0], Mlist, \
Glist, Slist)
return M
def VelQuadraticForces(thetalist, dthetalist, Mlist, Glist, Slist):
"""Computes the Coriolis and centripetal terms in the inverse dynamics of
an open chain robot