-
Notifications
You must be signed in to change notification settings - Fork 497
/
Copy pathRobot.py
2012 lines (1634 loc) · 64.9 KB
/
Robot.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
@author: Peter Corke
"""
# import sys
from os.path import splitext
from copy import deepcopy
from warnings import warn
from pathlib import PurePosixPath, Path
from typing import (
List,
TypeVar,
Union,
Dict,
Tuple,
overload,
)
from typing_extensions import Literal as L
import numpy as np
import spatialmath.base as smb
from spatialmath.base.argcheck import (
getvector,
getmatrix,
verifymatrix,
)
from spatialgeometry import Shape, CollisionShape, Cylinder
from spatialmath import (
SE3,
SE2,
SpatialAcceleration,
SpatialVelocity,
SpatialInertia,
SpatialForce,
)
import roboticstoolbox as rtb
from roboticstoolbox.robot.BaseRobot import BaseRobot
from roboticstoolbox.robot.RobotKinematics import RobotKinematicsMixin
from roboticstoolbox.robot.Gripper import Gripper
from roboticstoolbox.robot.Link import BaseLink, Link, Link2
from roboticstoolbox.robot.ETS import ETS, ETS2
from roboticstoolbox.tools import xacro
from roboticstoolbox.tools import URDF
from roboticstoolbox.tools.types import ArrayLike, NDArray
from roboticstoolbox.tools.data import rtb_path_to_datafile
# A generic type variable representing any subclass of BaseLink
LinkType = TypeVar("LinkType", bound=BaseLink)
# ==================================================================================== #
# ================= Robot Class ====================================================== #
# ==================================================================================== #
class Robot(BaseRobot[Link], RobotKinematicsMixin):
_color = True
def __init__(
self,
arg: Union[List[Link], ETS, "Robot"],
gripper_links: Union[Link, List[Link], None] = None,
name: str = "",
manufacturer: str = "",
comment: str = "",
base: Union[NDArray, SE3, None] = None,
tool: Union[NDArray, SE3, None] = None,
gravity: ArrayLike = [0, 0, -9.81],
keywords: Union[List[str], Tuple[str]] = [],
symbolic: bool = False,
configs: Union[Dict[str, NDArray], None] = None,
check_jindex: bool = True,
urdf_string: Union[str, None] = None,
urdf_filepath: Union[Path, PurePosixPath, None] = None,
):
# Process links
if isinstance(arg, Robot):
# We're passed a Robot, clone it
# We need to preserve the parent link as we copy
# Copy each link within the robot
links = [deepcopy(link) for link in arg.links]
gripper_links = []
for gripper in arg.grippers:
glinks = []
for link in gripper.links:
glinks.append(deepcopy(link))
gripper_links.append(glinks[0])
links = links + glinks
# Sever parent connection, but save the string
# The constructor will piece this together for us
for link in links:
link._children = []
if link.parent is not None:
link._parent_name = link.parent.name
link._parent = None
super().__init__(links, gripper_links=gripper_links)
for i, gripper in enumerate(self.grippers):
gripper.tool = arg.grippers[i].tool.copy()
self._urdf_string = arg.urdf_string
self._urdf_filepath = arg.urdf_filepath
else:
if isinstance(arg, ETS):
# We're passed an ETS string
links = []
# chop it up into segments, a link frame after every joint
parent = None
for j, ets_j in enumerate(arg.split()):
elink = Link(ETS(ets_j), parent=parent, name=f"link{j:d}")
if (
elink.qlim is None
and elink.v is not None
and elink.v.qlim is not None
):
elink.qlim = elink.v.qlim # pragma nocover
parent = elink
links.append(elink)
elif smb.islistof(arg, Link):
links = arg
else:
raise TypeError("arg was invalid, must be List[Link], ETS, or Robot")
# Initialise Base Robot object
super().__init__(
links=links,
gripper_links=gripper_links,
name=name,
manufacturer=manufacturer,
comment=comment,
base=base,
tool=tool,
gravity=gravity,
keywords=keywords,
symbolic=symbolic,
configs=configs,
check_jindex=check_jindex,
)
# --------------------------------------------------------------------- #
# --------- Swift Methods --------------------------------------------- #
# --------------------------------------------------------------------- #
def _to_dict(self, robot_alpha=1.0, collision_alpha=0.0):
ob = []
for link in self.links:
if robot_alpha > 0:
for gi in link.geometry:
gi.set_alpha(robot_alpha)
ob.append(gi.to_dict())
if collision_alpha > 0:
for gi in link.collision:
gi.set_alpha(collision_alpha)
ob.append(gi.to_dict())
# Do the grippers now
for gripper in self.grippers:
for link in gripper.links:
if robot_alpha > 0:
for gi in link.geometry:
gi.set_alpha(robot_alpha)
ob.append(gi.to_dict())
if collision_alpha > 0:
for gi in link.collision:
gi.set_alpha(collision_alpha)
ob.append(gi.to_dict())
# for o in ob:
# print(o)
return ob
def _fk_dict(self, robot_alpha=1.0, collision_alpha=0.0):
ob = []
# Do the robot
for link in self.links:
if robot_alpha > 0:
for gi in link.geometry:
ob.append(gi.fk_dict())
if collision_alpha > 0:
for gi in link.collision:
ob.append(gi.fk_dict())
# Do the grippers now
for gripper in self.grippers:
for link in gripper.links:
if robot_alpha > 0:
for gi in link.geometry:
ob.append(gi.fk_dict())
if collision_alpha > 0:
for gi in link.collision:
ob.append(gi.fk_dict())
return ob
# --------------------------------------------------------------------- #
# --------- URDF Methods ---------------------------------------------- #
# --------------------------------------------------------------------- #
@staticmethod
def URDF_read(
file_path, tld=None, xacro_tld=None
) -> Tuple[List[Link], str, str, Union[Path, PurePosixPath]]:
"""
Read a URDF file as Links
File should be specified relative to ``RTBDATA/URDF/xacro``
Parameters
----------
file_path
File path relative to the xacro folder
tld
A custom top-level directory which holds the xacro data,
defaults to None
xacro_tld
A custom top-level within the xacro data,
defaults to None
Returns
-------
links
a list of links
name
the name of the robot
urdf
a string representing the URDF
file_path
a path to the original file
Notes
-----
If ``tld`` is not supplied, filepath pointing to xacro data should
be directly under ``RTBDATA/URDF/xacro`` OR under ``./xacro`` relative
to the model file calling this method. If ``tld`` is supplied, then
```file_path``` needs to be relative to ``tld``
"""
# Get the path to the class that defines the robot
if tld is None:
base_path = rtb_path_to_datafile("xacro")
else:
base_path = PurePosixPath(tld)
# Add on relative path to get to the URDF or xacro file
# base_path = PurePath(classpath).parent.parent / 'URDF' / 'xacro'
file_path = base_path / PurePosixPath(file_path)
_, ext = splitext(file_path)
if ext == ".xacro":
# it's a xacro file, preprocess it
if xacro_tld is not None:
xacro_tld = base_path / PurePosixPath(xacro_tld)
urdf_string = xacro.main(file_path, xacro_tld)
try:
urdf = URDF.loadstr(urdf_string, file_path, base_path)
except BaseException as e: # pragma nocover
print("error parsing URDF file", file_path)
raise e
else: # pragma nocover
urdf_string = open(file_path).read()
urdf = URDF.loadstr(urdf_string, file_path, base_path)
if not isinstance(urdf_string, str): # pragma nocover
raise ValueError("Parsing failed, did not get valid URDF string back")
return urdf.elinks, urdf.name, urdf_string, file_path
@classmethod
def URDF(cls, file_path: str, gripper: Union[int, str, None] = None):
"""
Construct a Robot object from URDF file
Parameters
----------
file_path
the path to the URDF
gripper
index or name of the gripper link(s)
Returns
-------
If ``gripper`` is specified, links from that link outward are removed
from the rigid-body tree and folded into a ``Gripper`` object.
"""
links, name, urdf_string, urdf_filepath = Robot.URDF_read(file_path)
gripperLink: Union[Link, None] = None
if gripper is not None:
if isinstance(gripper, int):
gripperLink = links[gripper]
elif isinstance(gripper, str):
for link in links:
if link.name == gripper:
gripperLink = link
break
else: # pragma nocover
raise ValueError(f"no link named {gripper}")
else: # pragma nocover
raise TypeError("bad argument passed as gripper")
# links, name, urdf_string, urdf_filepath = Robot.URDF_read(file_path)
return cls(
links,
name=name,
gripper_links=gripperLink,
urdf_string=urdf_string,
urdf_filepath=urdf_filepath,
)
# # --------------------------------------------------------------------- #
# # --------- Utility Methods ------------------------------------------- #
# # --------------------------------------------------------------------- #
# def showgraph(self, display_graph: bool = True, **kwargs) -> Union[None, str]:
# """
# Display a link transform graph in browser
# ``robot.showgraph()`` displays a graph of the robot's link frames
# and the ETS between them. It uses GraphViz dot.
# The nodes are:
# - Base is shown as a grey square. This is the world frame origin,
# but can be changed using the ``base`` attribute of the robot.
# - Link frames are indicated by circles
# - ETS transforms are indicated by rounded boxes
# The edges are:
# - an arrow if `jtype` is False or the joint is fixed
# - an arrow with a round head if `jtype` is True and the joint is
# revolute
# - an arrow with a box head if `jtype` is True and the joint is
# prismatic
# Edge labels or nodes in blue have a fixed transformation to the
# preceding link.
# Parameters
# ----------
# display_graph
# Open the graph in a browser if True. Otherwise will return the
# file path
# etsbox
# Put the link ETS in a box, otherwise an edge label
# jtype
# Arrowhead to node indicates revolute or prismatic type
# static
# Show static joints in blue and bold
# Examples
# --------
# >>> import roboticstoolbox as rtb
# >>> panda = rtb.models.URDF.Panda()
# >>> panda.showgraph()
# .. image:: ../figs/panda-graph.svg
# :width: 600
# See Also
# --------
# :func:`dotfile`
# """
# # Lazy import
# import tempfile
# import subprocess
# import webbrowser
# # create the temporary dotfile
# dotfile = tempfile.TemporaryFile(mode="w")
# self.dotfile(dotfile, **kwargs)
# # rewind the dot file, create PDF file in the filesystem, run dot
# dotfile.seek(0)
# pdffile = tempfile.NamedTemporaryFile(suffix=".pdf", delete=False)
# subprocess.run("dot -Tpdf", shell=True, stdin=dotfile, stdout=pdffile)
# # open the PDF file in browser (hopefully portable), then cleanup
# if display_graph: # pragma nocover
# webbrowser.open(f"file://{pdffile.name}")
# else:
# return pdffile.name
# def dotfile(
# self,
# filename: Union[str, IO[str]],
# etsbox: bool = False,
# ets: L["full", "brief"] = "full",
# jtype: bool = False,
# static: bool = True,
# ):
# """
# Write a link transform graph as a GraphViz dot file
# The file can be processed using dot:
# % dot -Tpng -o out.png dotfile.dot
# The nodes are:
# - Base is shown as a grey square. This is the world frame origin,
# but can be changed using the ``base`` attribute of the robot.
# - Link frames are indicated by circles
# - ETS transforms are indicated by rounded boxes
# The edges are:
# - an arrow if `jtype` is False or the joint is fixed
# - an arrow with a round head if `jtype` is True and the joint is
# revolute
# - an arrow with a box head if `jtype` is True and the joint is
# prismatic
# Edge labels or nodes in blue have a fixed transformation to the
# preceding link.
# Note
# ----
# If ``filename`` is a file object then the file will *not*
# be closed after the GraphViz model is written.
# Parameters
# ----------
# file
# Name of file to write to
# etsbox
# Put the link ETS in a box, otherwise an edge label
# ets
# Display the full ets with "full" or a brief version with "brief"
# jtype
# Arrowhead to node indicates revolute or prismatic type
# static
# Show static joints in blue and bold
# See Also
# --------
# :func:`showgraph`
# """
# if isinstance(filename, str):
# file = open(filename, "w")
# else:
# file = filename
# header = r"""digraph G {
# graph [rankdir=LR];
# """
# def draw_edge(link, etsbox, jtype, static):
# # draw the edge
# if jtype:
# if link.isprismatic:
# edge_options = 'arrowhead="box", arrowtail="inv", dir="both"'
# elif link.isrevolute:
# edge_options = 'arrowhead="dot", arrowtail="inv", dir="both"'
# else:
# edge_options = 'arrowhead="normal"'
# else:
# edge_options = 'arrowhead="normal"'
# if link.parent is None:
# parent = "BASE"
# else:
# parent = link.parent.name
# if etsbox:
# # put the ets fragment in a box
# if not link.isjoint and static:
# node_options = ', fontcolor="blue"'
# else:
# node_options = ""
# try:
# file.write(
# ' {}_ets [shape=box, style=rounded, label="{}"{}];\n'.format(
# link.name,
# link.ets.__str__(q=f"q{link.jindex}"),
# node_options,
# )
# )
# except UnicodeEncodeError: # pragma nocover
# file.write(
# ' {}_ets [shape=box, style=rounded, label="{}"{}];\n'.format(
# link.name,
# link.ets.__str__(q=f"q{link.jindex}")
# .encode("ascii", "ignore")
# .decode("ascii"),
# node_options,
# )
# )
# file.write(" {} -> {}_ets;\n".format(parent, link.name))
# file.write(
# " {}_ets -> {} [{}];\n".format(link.name, link.name, edge_options)
# )
# else:
# # put the ets fragment as an edge label
# if not link.isjoint and static:
# edge_options += 'fontcolor="blue"'
# if ets == "full":
# estr = link.ets.__str__(q=f"q{link.jindex}")
# elif ets == "brief":
# if link.jindex is None:
# estr = ""
# else:
# estr = f"...q{link.jindex}"
# else:
# return
# try:
# file.write(
# ' {} -> {} [label="{}", {}];\n'.format(
# parent,
# link.name,
# estr,
# edge_options,
# )
# )
# except UnicodeEncodeError: # pragma nocover
# file.write(
# ' {} -> {} [label="{}", {}];\n'.format(
# parent,
# link.name,
# estr.encode("ascii", "ignore").decode("ascii"),
# edge_options,
# )
# )
# file.write(header)
# # add the base link
# file.write(" BASE [shape=square, style=filled, fillcolor=gray]\n")
# # add the links
# for link in self:
# # draw the link frame node (circle) or ee node (doublecircle)
# if link in self.ee_links:
# # end-effector
# node_options = 'shape="doublecircle", color="blue", fontcolor="blue"'
# else:
# node_options = 'shape="circle"'
# file.write(" {} [{}];\n".format(link.name, node_options))
# draw_edge(link, etsbox, jtype, static)
# for gripper in self.grippers:
# for link in gripper.links:
# file.write(" {} [shape=cds];\n".format(link.name))
# draw_edge(link, etsbox, jtype, static)
# file.write("}\n")
# if isinstance(filename, str):
# file.close() # noqa
# --------------------------------------------------------------------- #
# --------- Kinematic Methods ----------------------------------------- #
# --------------------------------------------------------------------- #
@property
def reach(self) -> float:
r"""
Reach of the robot
A conservative estimate of the reach of the robot. It is computed as
the sum of the translational ETs that define the link transform.
Note
----
Computed on the first access. If kinematic parameters
subsequently change this will not be reflected.
Returns
-------
reach
Maximum reach of the robot
Notes
-----
- Probably an overestimate of reach
- Used by numerical inverse kinematics to scale translational
error.
- For a prismatic joint, uses ``qlim`` if it is set
"""
# TODO
# This should be a start, end method and compute the reach based on the
# given ets. Then use an lru_cache to speed up return
if self._reach is None:
d_all = []
for link in self.ee_links:
d = 0
while True:
for et in link.ets:
if et.istranslation:
if et.isjoint:
# the length of a prismatic joint depends on the
# joint limits. They might be set in the ET
# or in the Link depending on how the robot
# was constructed
if link.qlim is not None:
d += max(link.qlim)
elif et.qlim is not None: # pragma nocover
d += max(et.qlim)
else:
d += abs(et.eta)
link = link.parent
if link is None or isinstance(link, str):
d_all.append(d)
break
self._reach = max(d_all)
return self._reach
def fkine_all(self, q: ArrayLike) -> SE3:
"""
Compute the pose of every link frame
``T = robot.fkine_all(q)`` is an SE3 instance with ``robot.nlinks +
1`` values:
- ``T[0]`` is the base transform
- ``T[i]`` is the pose of link whose ``number`` is ``i``
Parameters
----------
q
The joint configuration
Returns
-------
fkine_all
Pose of all links
References
----------
- J. Haviland, and P. Corke. "Manipulator Differential Kinematics Part I:
Kinematics, Velocity, and Applications." arXiv preprint arXiv:2207.01796 (2022).
""" # noqa
q = getvector(q)
Tbase = SE3(self.base) # add base, also sets the type
linkframes = Tbase.__class__.Alloc(self.nlinks + 1)
linkframes[0] = Tbase
def recurse(Tall, Tparent, q, link):
# if joint??
T = Tparent
while True:
T *= SE3(link.A(q[link.jindex]))
Tall[link.number] = T
if link.nchildren == 0:
# no children
return
elif link.nchildren == 1:
# one child
if link in self.ee_links: # pragma nocover
# this link is an end-effector, go no further
return
link = link.children[0]
continue
else:
# multiple children
for child in link.children:
recurse(Tall, T, q, child)
return
recurse(linkframes, Tbase, q, self.links[0])
return linkframes
@overload
def manipulability(
self,
q: ArrayLike = ...,
J: None = None,
end: Union[str, Link, Gripper, None] = None,
start: Union[str, Link, Gripper, None] = None,
method: L["yoshikawa", "asada", "minsingular", "invcondition"] = "yoshikawa",
axes: Union[L["all", "trans", "rot"], List[bool]] = "all",
**kwargs,
) -> Union[float, NDArray]: # pragma nocover
...
@overload
def manipulability(
self,
q: None = None,
J: NDArray = ...,
end: Union[str, Link, Gripper, None] = None,
start: Union[str, Link, Gripper, None] = None,
method: L["yoshikawa", "asada", "minsingular", "invcondition"] = "yoshikawa",
axes: Union[L["all", "trans", "rot"], List[bool]] = "all",
**kwargs,
) -> Union[float, NDArray]: # pragma nocover
...
def manipulability(
self,
q=None,
J=None,
end: Union[str, Link, Gripper, None] = None,
start: Union[str, Link, Gripper, None] = None,
method: L["yoshikawa", "asada", "minsingular", "invcondition"] = "yoshikawa",
axes: Union[L["all", "trans", "rot"], List[bool]] = "all",
**kwargs,
):
"""
Manipulability measure
``manipulability(q)`` is the scalar manipulability index
for the robot at the joint configuration ``q``. It indicates
dexterity, that is, how well conditioned the robot is for motion
with respect to the 6 degrees of Cartesian motion. The values is
zero if the robot is at a singularity.
Parameters
----------
q
Joint coordinates, one of J or q required
J
Jacobian in base frame if already computed, one of J or
q required
method
method to use, "yoshikawa" (default), "invcondition",
"minsingular" or "asada"
axes
Task space axes to consider: "all" [default],
"trans", or "rot"
Returns
-------
manipulability
Synopsis
--------
Various measures are supported:
| Measure | Description |
|-------------------|-------------------------------------------------|
| ``"yoshikawa"`` | Volume of the velocity ellipsoid, *distance* |
| | from singularity [Yoshikawa85]_ |
| ``"invcondition"``| Inverse condition number of Jacobian, isotropy |
| | of the velocity ellipsoid [Klein87]_ |
| ``"minsingular"`` | Minimum singular value of the Jacobian, |
| | *distance* from singularity [Klein87]_ |
| ``"asada"`` | Isotropy of the task-space acceleration |
| | ellipsoid which is a function of the Cartesian |
| | inertia matrix which depends on the inertial |
| | parameters [Asada83]_ |
**Trajectory operation**:
If ``q`` is a matrix (m,n) then the result (m,) is a vector of
manipulability indices for each joint configuration specified by a row
of ``q``.
Notes
-----
- Invokes the ``jacob0`` method of the robot if ``J`` is not passed
- The "all" option includes rotational and translational
dexterity, but this involves adding different units. It can be
more useful to look at the translational and rotational
manipulability separately.
- Examples in the RVC book (1st edition) can be replicated by
using the "all" option
- Asada's measure requires inertial a robot model with inertial
parameters.
References
----------
.. [Yoshikawa85] Manipulability of Robotic Mechanisms. Yoshikawa T.,
The International Journal of Robotics Research.
1985;4(2):3-9. doi:10.1177/027836498500400201
.. [Asada83] A geometrical representation of manipulator dynamics and
its application to arm design, H. Asada,
Journal of Dynamic Systems, Measurement, and Control,
vol. 105, p. 131, 1983.
.. [Klein87] Dexterity Measures for the Design and Control of
Kinematically Redundant Manipulators. Klein CA, Blaho BE.
The International Journal of Robotics Research.
1987;6(2):72-83. doi:10.1177/027836498700600206
- Robotics, Vision & Control, Chap 8, P. Corke, Springer 2011.
.. versionchanged:: 1.0.3
Removed 'both' option for axes, added a custom list option.
"""
ets = self.ets(end, start)
axes_list: List[bool] = []
if isinstance(axes, list):
axes_list = axes
elif axes == "all":
axes_list = [True, True, True, True, True, True]
elif axes.startswith("trans"):
axes_list = [True, True, True, False, False, False]
elif axes.startswith("rot"):
axes_list = [False, False, False, True, True, True]
elif axes == "both":
return (
self.manipulability(
q=q, J=J, end=end, start=start, method=method, axes="trans"
),
self.manipulability(
q=q, J=J, end=end, start=start, method=method, axes="rot"
),
)
else:
raise ValueError("axes must be all, trans, rot or both")
def yoshikawa(robot, J, q, axes_list):
J = J[axes_list, :]
if J.shape[0] == J.shape[1]:
# simplified case for square matrix
return abs(np.linalg.det(J))
else:
m2 = np.linalg.det(J @ J.T)
return np.sqrt(abs(m2))
def condition(robot, J, q, axes_list):
J = J[axes_list, :]
# return 1/cond(J)
return 1 / np.linalg.cond(J)
def minsingular(robot, J, q, axes_list):
J = J[axes_list, :]
s = np.linalg.svd(J, compute_uv=False)
# return last/smallest singular value of J
return s[-1]
def asada(robot, J, q, axes_list):
# dof = np.sum(axes_list)
if np.linalg.matrix_rank(J) < 6:
return 0
Ji = np.linalg.pinv(J)
Mx = Ji.T @ robot.inertia(q) @ Ji
d = np.where(axes_list)[0]
Mx = Mx[d]
Mx = Mx[:, d.tolist()]
e, _ = np.linalg.eig(Mx)
return np.min(e) / np.max(e)
# choose the handler function
if method.lower().startswith("yoshi"):
mfunc = yoshikawa
elif method.lower().startswith("invc"):
mfunc = condition
elif method.lower().startswith("mins"):
mfunc = minsingular
elif method.lower().startswith("asa"):
mfunc = asada
else:
raise ValueError("Invalid method chosen")
# Calculate manipulability based on supplied Jacobian
if J is not None:
w = [mfunc(self, J, q, axes_list)]
# Otherwise use the q vector/matrix
else:
q = np.array(getmatrix(q, (None, self.n)))
w = np.zeros(q.shape[0])
for k, qk in enumerate(q):
Jk = ets.jacob0(qk)
w[k] = mfunc(self, Jk, qk, axes_list)
if len(w) == 1:
return w[0]
else:
return w
def jtraj(
self,
T1: Union[NDArray, SE3],
T2: Union[NDArray, SE3],
t: Union[NDArray, int],
**kwargs,
):
"""
Joint-space trajectory between SE(3) poses
The initial and final poses are mapped to joint space using inverse
kinematics:
- if the object has an analytic solution ``ikine_a`` that will be used,
- otherwise the general numerical algorithm ``ikine_lm`` will be used.
``traj = obot.jtraj(T1, T2, t)`` is a trajectory object whose
attribute ``traj.q`` is a row-wise joint-space trajectory.
Parameters
----------
T1
initial end-effector pose
T2
final end-effector pose
t
time vector or number of steps
kwargs
arguments passed to the IK solver
Returns
-------
trajectory
""" # noqa
if hasattr(self, "ikine_a"):
ik = self.ikine_a # type: ignore
else:
ik = self.ikine_LM
q1 = ik(T1, **kwargs)
q2 = ik(T2, **kwargs)
return rtb.jtraj(q1.q, q2.q, t)
@overload
def jacob0_dot(
self,
q: ArrayLike,
qd: ArrayLike,
J0: None = None,
representation: Union[L["rpy/xyz", "rpy/zyx", "eul", "exp"], None] = None,
) -> NDArray: # pragma no cover
...
@overload
def jacob0_dot(
self,
q: None,
qd: ArrayLike,
J0: NDArray = ...,
representation: Union[L["rpy/xyz", "rpy/zyx", "eul", "exp"], None] = None,
) -> NDArray: # pragma no cover
...
def jacob0_dot(
self,
q,
qd: ArrayLike,
J0=None,
representation: Union[L["rpy/xyz", "rpy/zyx", "eul", "exp"], None] = None,
):
r"""
Derivative of Jacobian
``robot.jacob_dot(q, qd)`` computes the rate of change of the
Jacobian elements
.. math::
\dmat{J} = \frac{d \mat{J}}{d \vec{q}} \frac{d \vec{q}}{dt}
where the first term is the rank-3 Hessian.
Parameters
----------
q
The joint configuration of the robot
qd
The joint velocity of the robot
J0
Jacobian in {0} frame