forked from petercorke/robotics-toolbox-python
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathDHRobot.py
1776 lines (1406 loc) · 53.5 KB
/
DHRobot.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
#!/usr/bin/env python
"""
@author Jesse Haviland
"""
from collections import namedtuple
from roboticstoolbox.tools.data import rtb_path_to_datafile
import warnings
import copy
import numpy as np
from roboticstoolbox.robot.Robot import Robot # DHLink
from roboticstoolbox.robot.ETS import ETS
from roboticstoolbox.robot.DHLink import DHLink # HACK
from spatialmath.base.argcheck import getvector, isscalar, verifymatrix, getmatrix
# from spatialmath import base
from spatialmath.base import tr2jac, tr2eul, tr2rpy, t2r, eul2jac, rpy2jac
from spatialmath import SE3, Twist3
import spatialmath.base.symbolic as sym
# from scipy.optimize import minimize, Bounds
from ansitable import ANSITable, Column
from scipy.linalg import block_diag
from roboticstoolbox.robot.DHLink import _check_rne
from frne import init, frne, delete
iksol = namedtuple("IKsolution", "q, success, reason")
class DHRobot(Robot):
"""
Class for robots defined using Denavit-Hartenberg notation
:param L: List of links which define the robot
:type L: list(n)
:param name: Name of the robot
:type name: str
:param manufacturer: Manufacturer of the robot
:type manufacturer: str
:param base: Location of the base
:type base: SE3
:param tool: Location of the tool
:type tool: SE3
:param gravity: Gravitational acceleration vector
:type gravity: ndarray(3)
A concrete superclass for arm type robots defined using Denavit-Hartenberg
notation, that represents a serial-link arm-type robot. Each link and
joint in the chain is described by a DHLink-class object using
Denavit-Hartenberg parameters (standard or modified).
.. note:: Link subclass elements passed in must be all standard, or all
modified, DH parameters.
:reference:
- Robotics, Vision & Control, Chaps 7-9,
P. Corke, Springer 2011.
- Robot, Modeling & Control,
M.Spong, S. Hutchinson & M. Vidyasagar, Wiley 2006.
"""
def __init__(self, links, meshdir=None, **kwargs):
# Verify L
if not isinstance(links, list):
raise TypeError("The links must be stored in a list.")
all_links = []
self._n = 0
for link in links:
if isinstance(link, DHLink):
# got a link
all_links.append(link)
link.number = self._n + 1
link.jindex = self._n
self._n += 1
link.name = f"link{self._n}"
elif isinstance(link, DHRobot):
# link is actually a robot
# copy the links
rlinks = copy.copy(link.links)
for rlink in rlinks:
all_links.append(rlink)
rlink.number = self._n
rlink.jindex = self._n
self._n += 1
rlink.name = f"link{self._n}"
else:
raise TypeError("Input can be only DHLink or DHRobot")
super().__init__(all_links, **kwargs)
self.ee_links = [self.links[-1]]
# Check the DH convention
self._mdh = self.links[0].mdh
if not all([link.mdh == self.mdh for link in self.links]):
raise ValueError("Robot has mixed D&H link conventions")
# load meshes if required
if meshdir is not None:
self.meshdir = rtb_path_to_datafile(meshdir)
self.basemesh = self.meshdir / "link0.stl"
for j, link in enumerate(self._links, start=1):
link.mesh = self.meshdir / "link{:d}.stl".format(j)
self._hasgeometry = True
else:
self.basemesh = None
# rne parameters
self._rne_ob = None
def __str__(self):
"""
Pretty prints the DH Model of the robot. Will output angles in degrees
:return: Pretty print of the robot model
:rtype: str
"""
s = f"DHRobot: {self.name}"
if self.manufacturer is not None and len(self.manufacturer) > 0:
s += f" (by {self.manufacturer})"
s += f", {self.n} joints ({self.structure})"
deg = 180 / np.pi
if self._hasdynamics:
s += ", dynamics"
if any([link.mesh is not None for link in self.links]):
s += ", geometry"
if self.mdh:
dh = "modified"
else:
dh = "standard"
s += f", {dh} DH parameters\n"
def qstr(j, link):
j += 1
if link.flip:
s = f"-q{j:d}"
else:
s = f" q{j:d}"
if L.offset != 0:
sign = "+" if L.offset > 0 else "-"
offset = abs(L.offset)
if link.isprismatic:
s += f" {sign} {offset:}"
else:
s += f" {sign} {offset * deg:.3g}\u00b0"
return s
def angle(theta, fmt=None):
if sym.issymbol(theta): # pragma nocover
return "<<red>>" + str(theta)
else:
if fmt is not None:
return fmt.format(theta * deg) + "\u00b0"
else:
return str(theta * deg) + "\u00b0"
has_qlim = any([link._qlim is not None for link in self])
if has_qlim:
qlim_columns = [
Column("q⁻", headalign="^"),
Column("q⁺", headalign="^"),
]
qlim = self.qlim
else:
qlim_columns = []
if self.mdh:
# MDH format
table = ANSITable(
Column("aⱼ₋₁", headalign="^"),
Column("⍺ⱼ₋₁", headalign="^"),
Column("θⱼ", headalign="^"),
Column("dⱼ", headalign="^"),
*qlim_columns,
border="thick",
)
for j, L in enumerate(self):
if has_qlim:
if L.isprismatic:
ql = [qlim[0, j], qlim[1, j]]
else:
ql = [angle(qlim[k, j], "{:.1f}") for k in [0, 1]]
else:
ql = []
if L.isprismatic:
table.row(L.a, angle(L.alpha), angle(L.theta), qstr(j, L), *ql)
else:
table.row(L.a, angle(L.alpha), qstr(j, L), L.d, *ql)
else:
# DH format
table = ANSITable(
Column("θⱼ", headalign="^", colalign="<"),
Column("dⱼ", headalign="^"),
Column("aⱼ", headalign="^"),
Column("⍺ⱼ", headalign="^"),
*qlim_columns,
border="thick",
)
for j, L in enumerate(self):
if has_qlim:
if L.isprismatic:
ql = [qlim[0, j], qlim[1, j]]
else:
ql = [angle(qlim[k, j], "{:.1f}") for k in [0, 1]]
else:
ql = []
if L.isprismatic:
table.row(
angle(L.theta), qstr(j, L), f"{L.a:.4g}", angle(L.alpha), *ql
)
else:
table.row(
qstr(j, L), f"{L.d:.4g}", f"{L.a:.4g}", angle(L.alpha), *ql
)
s += str(table)
# show tool and base
if self._tool is not None or self._tool is not None:
table = ANSITable(
Column("", colalign=">"),
Column("", colalign="<"),
border="thin",
header=False,
)
if self._base is not None:
table.row(
"base",
self._base.printline(orient="rpy/xyz", fmt="{:.2g}", file=None),
)
if self._tool is not None:
table.row(
"tool",
self._tool.printline(orient="rpy/xyz", fmt="{:.2g}", file=None),
)
s += "\n" + str(table)
# show named configurations
s += self.configurations_str()
return s
def __add__(self, L):
nlinks = []
# TODO - Should I do a deep copy here a physically copy the DHLinks
# and not just the references?
# Copy DHLink references to new list
for i in range(self.n):
nlinks.append(self.links[i])
if isinstance(L, DHLink):
nlinks.append(L)
elif isinstance(L, DHRobot):
for j in range(L.n):
nlinks.append(L.links[j])
else:
raise TypeError(
"Can only combine DHRobots with other " "DHRobots or DHLinks"
)
return DHRobot(
nlinks,
name=self.name,
manufacturer=self.manufacturer,
base=self.base,
tool=self.tool,
gravity=self.gravity,
)
# def copy(self):
# """
# Copy a robot
# :return: A deepish copy of the robot
# :rtype: Robot subclass instance
# """
# L = [link.copy() for link in self]
# new = DHRobot(
# L,
# name=self.name,
# manufacturer=self.manufacturer,
# base=self.base,
# tool=self.tool,
# gravity=self.gravity)
# new.q = self.q
# new.qd = self.qd
# new.qdd = self.qdd
# return new
# --------------------------------------------------------------------- #
def _set_link_fk(self, q):
"""
robot._set_link_fk(q) evaluates fkine for each link within a
robot and stores that pose in a private variable within the link.
This method is not for general use.
:param q: The joint angles/configuration of the robot
:type q: float ndarray(n)
.. note::
- The robot's base transform, if present, are incorporated
into the result.
"""
q = getvector(q, self.n)
# t = self.base
tall = self.fkine_all(q, old=True)
for i, link in enumerate(self.links):
# Update the link model transforms
for col in link.collision:
col.wT = tall[i]
for gi in link.geometry:
gi.wT = tall[i]
# --------------------------------------------------------------------- #
@property
def mdh(self):
"""
Modified Denavit-Hartenberg status
:return: whether robot is defined using modified Denavit-Hartenberg
notation
:rtype: bool
Example:
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> puma = rtb.models.DH.Puma560()
>>> puma.mdh
>>> panda = rtb.models.DH.Panda()
>>> panda.mdh
"""
return self._mdh
@property
def d(self):
r"""
Link offset values
:return: List of link offset values :math:`d_j`.
:rtype: ndarray(n,)
The following are equivalent::
robot.links[j].d
robot.d[j]
Example:
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> robot = rtb.models.DH.Puma560()
>>> robot.d
"""
v = []
for i in range(self.n):
v.append(self.links[i].d)
return v
@property
def a(self):
r"""
Link length values
:return: List of link length values :math:`a_j`.
:rtype: ndarray(n,)
The following are equivalent::
robot.links[j].a
robot.a[j]
Example:
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> robot = rtb.models.DH.Puma560()
>>> robot.a
"""
v = []
for i in range(self.n):
v.append(self.links[i].a)
return v
@property
def theta(self):
r"""
Joint angle values
:return: List of joint angle values :math:`\theta_j`.
:rtype: ndarray(n,)
The following are equivalent::
robot.links[j].theta
robot.theta[j]
Example:
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> robot = rtb.models.DH.Puma560()
>>> robot.theta
"""
v = []
for i in range(self.n):
v.append(self.links[i].theta)
return v
@property
def alpha(self):
r"""
Link twist values
:return: List of link twist values :math:`\alpha_j`.
:rtype: ndarray(n,)
The following are equivalent::
robot.links[j].alpha
robot.alpha[j]
Example:
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> robot = rtb.models.DH.Puma560()
>>> robot.alpha
"""
v = []
for i in range(self.n):
v.append(self.links[i].alpha)
return v
@property
def r(self):
r"""
Link centre of mass values
:return: Array of link centre of mass values :math:`r_j`.
:rtype: ndarray(3,n)
Example:
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> robot = rtb.models.DH.Puma560()
>>> robot.r
"""
# TODO tidyup
v = np.copy(self.links[0].r)
for i in range(1, self.n):
v = np.c_[v, self.links[i].r]
return v
@property
def offset(self):
r"""
Joint offset values
:return: List of joint offset values :math:`\bar{q}_j`.
:rtype: ndarray(n,)
Example:
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> robot = rtb.models.DH.Puma560()
>>> robot.offset
"""
v = []
for i in range(self.n):
v.append(self.links[i].offset)
return v
@property
def reach(self):
r"""
Reach of the robot
:return: Maximum reach of the robot
:rtype: float
A conservative estimate of the reach of the robot. It is computed as
:math:`\sum_j |a_j| + |d_j|` where :math:`d_j` is taken as the maximum
joint coordinate (``qlim``) if the joint is primsmatic.
.. note::
- This is the *length sum* referred to in Craig's book
- Probably an overestimate of the actual reach
- Used by numerical inverse kinematics to scale translational
error.
- For a prismatic joint, uses ``qlim`` if it is set
.. warning:: Computed on the first access. If kinematic parameters
subsequently change this will not be reflected.
"""
if self._reach is None:
d = 0
for link in self:
d += abs(link.a) + (link.d)
if link.isprismatic and link.qlim is not None:
d += link.qlim[1]
self._reach = d
return self._reach
@property
def nbranches(self):
"""
Number of branches
:return: number of branches in the robot's kinematic tree
:rtype: int
Number of branches in this robot.
Example:
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> robot = rtb.models.DH.Panda()
>>> robot.nbranches
:seealso: :func:`n`, :func:`nlinks`
"""
return 1
def A(self, j, q=None):
"""
Link forward kinematics
:param j: Joints to compute link transform for
:type j: int, 2-tuple
:param q: The joint configuration of the robot (Optional,
if not supplied will use the stored q values)
:type q: float ndarray(1,n)
:return T: The transform between link frames
:rtype T: SE3
- ``robot.A(j, q)`` transform between link frames {0} and {j}. ``q``
is a vector (n) of joint variables.
- ``robot.A([j1, j2], q)`` as above between link frames {j1} and {j2}.
- ``robot.A(j)`` as above except uses the stored q value of the
robot object.
.. note:: Base and tool transforms are not applied.
"""
if isscalar(j):
j0 = 0
jn = int(j)
else:
j = getvector(j, 2)
j0 = int(j[0])
jn = int(j[1])
jn += 1
if jn > self.n:
raise ValueError("The joints value out of range")
q = getvector(q)
T = SE3()
for i in range(j0, jn):
T *= self.links[i].A(q[i])
return T
def islimit(self, q=None):
"""
Joint limit test
:param q: The joint configuration of the robot (Optional,
if not supplied will use the stored q values)
:type q: ndarray(n
:return v: is a vector of boolean values, one per joint, False if
``q[j]`` is within the joint limits, else True
:rtype v: bool list
- ``robot.islimit(q)`` is a list of boolean values indicating if the
joint configuration ``q`` is in violation of the joint limits.
- ``robot.jointlimit()`` as above except uses the stored q value of the
robot object.
Example:
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> robot = rtb.models.DH.Puma560()
>>> robot.islimit([0, 0, -4, 4, 0, 0])
"""
q = self._getq(q)
return [link.islimit(qk) for (link, qk) in zip(self, q)]
def isspherical(self):
"""
Test for spherical wrist
:return: True if spherical wrist
:rtype: bool
Tests if the robot has a spherical wrist, that is, the last 3 axes are
revolute and their axes intersect at a point.
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> robot = rtb.models.DH.Puma560()
>>> robot.isspherical()
"""
if self.n < 3:
return False
L = self.links[self.n - 3 : self.n]
alpha = [-np.pi / 2, np.pi / 2]
return (
L[0].a == 0
and L[1].a == 0
and L[1].d == 0
and (
(L[0].alpha == alpha[0] and L[1].alpha == alpha[1])
or (L[0].alpha == alpha[1] and L[1].alpha == alpha[0])
)
and L[0].sigma == 0
and L[1].sigma == 0
and L[2].sigma == 0
)
def dhunique(self):
"""
Print the unique DH parameters
Print a table showing all the non-zero DH parameters, and their
values. This is the minimum set of kinematic parameters required
to describe the robot.
Example:
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> puma = rtb.models.DH.Puma560()
>>> puma.dhunique()
"""
table = ANSITable(
Column("param"),
Column("value", headalign="^", colalign="<", fmt="{:.4g}"),
border="thin",
)
for j, link in enumerate(self):
if link.isprismatic:
if link.theta != 0:
table.row(f"θ{j}", link.theta)
elif link.isrevolute:
if link.d != 0:
table.row(f"d{j}", link.d)
if link.a != 0:
table.row(f"a{j}", link.a)
if link.alpha != 0:
table.row(f"⍺{j}", link.alpha)
table.print()
def twists(self, q=None):
"""
Joint axes as twists
:param q: The joint configuration of the robot
:type q: array_like (n)
:return: a vector of Twist objects
:rtype: float ndarray(n,)
:return: Represents the pose of the tool
:rtype: SE3 instance
- ``tw, T0 = twists(q)`` calculates a vector of Twist objects (n) that
represent the axes of the joints for the robot with joint coordinates
``q`` (n). Also returns T0 which is an SE3 object representing the
pose of the tool.
- ``tw, T0 = twists()`` as above but the joint coordinates are taken
to be zero.
Example:
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> robot = rtb.models.DH.Puma560()
>>> tw, T0 = robot.twists(robot.qz)
>>> tw
>>> T0
"""
if q is None:
q = np.zeros((self.n))
T = self.fkine_all(q)
tw = Twist3.Alloc(self.n)
if self.mdh:
# MDH case
for j, link in enumerate(self):
if link.sigma == 0:
tw[j] = Twist3.UnitRevolute(T[j].a, T[j].t)
else:
tw[j] = Twist3.UnitPrismatic(T[j].a)
else:
# DH case
for j, link in enumerate(self):
if j == 0:
# first link case
if link.sigma == 0:
# revolute
tw[j] = Twist3.UnitRevolute([0, 0, 1], [0, 0, 0])
else:
tw[j] = Twist3.UnitPrismatic([0, 0, 1]) # prismatic
else:
# subsequent links
if link.sigma == 0:
tw[j] = Twist3.UnitRevolute(T[j - 1].a, T[j - 1].t) # revolute
else:
tw[j] = Twist3.UnitPrismatic(T[j - 1].a) # prismatic
return tw, T[-1]
def ets(self):
"""
Robot kinematics as an elemenary transform sequence
:return: elementary transform sequence
:rtype: ETS
Example:
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> puma = rtb.models.DH.Puma560()
>>> puma.ets()
"""
# optionally start with the base transform
if self._base is None:
ets = ETS()
else:
ets = ETS.SE3(self._base)
# add the links
for link in self:
ets *= link.ets()
# optionally add the base transform
if self._tool is not None:
ets *= ETS.SE3(self._tool)
return ets
def fkine(self, q, **kwargs):
"""
Forward kinematics
:param q: The joint configuration
:type q: ndarray(n) or ndarray(m,n)
:return: Forward kinematics as an SE(3) matrix
:rtype: SE3 instance
- ``robot.fkine(q)`` computes the forward kinematics for the robot at
joint configuration ``q``.
If q is a 2D array, the rows are interpreted as the generalized joint
coordinates for a sequence of points along a trajectory. ``q[k,j]`` is
the j'th joint coordinate for the k'th trajectory configuration, and
the returned ``SE3`` instance contains ``n`` values.
Example:
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> puma = rtb.models.DH.Puma560()
>>> puma.fkine([0, 0, 0, 0, 0, 0])
.. note::
- The robot's base or tool transform, if present, are incorporated
into the result.
- Joint offsets, if defined, are added to ``q`` before the forward
kinematics are computed.
"""
T = SE3.Empty()
for qr in getmatrix(q, (None, self.n)):
first = True
for q, L in zip(qr, self.links):
if first:
Tr = L.A(q)
first = False
else:
Tr *= L.A(q)
if self._base is not None:
Tr = self._base * Tr
if self._tool is not None:
Tr = Tr * self._tool
T.append(Tr)
return T
def fkine_path(self, q, old=None):
"""
Compute the pose of every link frame
:param q: The joint configuration
:type q: darray(n)
:return: Pose of all links
:rtype: SE3 instance
``T = robot.fkine_path(q)`` is an SE3 instance with ``robot.nlinks +
1`` values:
- ``T[0]`` is the base transform
- ``T[i+1]`` is the pose of link whose ``number`` is ``i``
:references:
- Kinematic Derivatives using the Elementary Transform
Sequence, J. Haviland and P. Corke
"""
T = self.base
q = getvector(q)
Tj = T
for q, L in zip(q, self.links):
Tj *= L.A(q)
T.append(Tj)
if self._tool is not None:
T[-1] *= self._tool
return T
def segments(self):
segments = [None]
segments.extend(self.links)
return [segments]
def fkine_all(self, q=None, old=True):
"""
Forward kinematics for all link frames
:param q: The joint configuration of the robot (Optional,
if not supplied will use the stored q values).
:type q: ndarray(n) or ndarray(m,n)
:param old: "old" behaviour, defaults to True
:type old: bool, optional
:return: Forward kinematics as an SE(3) matrix
:rtype: SE3 instance with ``n`` values
- ``fkine_all(q)`` evaluates fkine for each joint within a robot and
returns a sequence of link frame poses.
- ``fkine_all()`` as above except uses the stored q value of the
robot object.
Example:
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> puma = rtb.models.DH.Puma560()
>>> T = puma.fkine_all([0, 0, 0, 0, 0, 0])
>>> len(T)
.. note::
- Old behaviour is to return a list of ``n`` frames {1} to {n}, but
if ``old=False`` it returns ``n``+1 frames {0} to {n}, ie. it
includes the base frame.
- The robot's base or tool transform, if present, are incorporated
into the result.
- Joint offsets, if defined, are added to q before the forward
kinematics are computed.
"""
q = self._getq(q)
Tj = self.base.copy()
Tall = Tj
for q, L in zip(q, self.links):
Tj *= L.A(q)
Tall.append(Tj)
return Tall
def jacobe(self, q, half=None, **kwargs):
r"""
Manipulator Jacobian in end-effector frame
:param q: Joint coordinate vector
:type q: ndarray(n)
:param half: return half Jacobian: 'trans' or 'rot'
:type half: str
:return J: The manipulator Jacobian in the end-effector frame
:rtype: ndarray(6,n)
- ``robot.jacobe(q)`` is the manipulator Jacobian matrix which maps
joint velocity to end-effector spatial velocity.
End-effector spatial velocity :math:`\nu = (v_x, v_y, v_z, \omega_x, \omega_y, \omega_z)^T`
is related to joint velocity by :math:`{}^{E}\!\nu = \mathbf{J}_m(q) \dot{q}`.
Example:
.. runblock:: pycon
>>> import roboticstoolbox as rtb
>>> puma = rtb.models.DH.Puma560()
>>> puma.jacobe([0, 0, 0, 0, 0, 0])
.. warning:: This is the **geometric Jacobian** as described in texts by
Corke, Spong etal., Siciliano etal. The end-effector velocity is
described in terms of translational and angular velocity, not a
velocity twist as per the text by Lynch & Park.
""" # noqa
q = getvector(q, self.n)
n = self.n
L = self.links
J = np.zeros((6, self.n), dtype=q.dtype)
U = self.tool.A
for j in range(n - 1, -1, -1):
if self.mdh == 0:
# standard DH convention
U = L[j].A(q[j]).A @ U
if not L[j].sigma:
# revolute axis
d = np.array(
[
-U[0, 0] * U[1, 3] + U[1, 0] * U[0, 3],
-U[0, 1] * U[1, 3] + U[1, 1] * U[0, 3],
-U[0, 2] * U[1, 3] + U[1, 2] * U[0, 3],
]
)
delta = U[2, :3] # nz oz az
else:
# prismatic axis
d = U[2, :3] # nz oz az
delta = np.zeros((3,))