forked from mmatl/urdfpy
-
Notifications
You must be signed in to change notification settings - Fork 16
/
urdf.py
4053 lines (3463 loc) · 129 KB
/
urdf.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 collections import OrderedDict
import copy
import os
import time
from lxml import etree as ET
import networkx as nx
import numpy as np
import PIL
import trimesh
import six
from .utils import (
parse_origin,
unparse_origin,
get_filename,
load_meshes,
configure_origin,
)
class URDFType(object):
"""Abstract base class for all URDF types.
This has useful class methods for automatic parsing/unparsing
of XML trees.
There are three overridable class variables:
- ``_ATTRIBS`` - This is a dictionary mapping attribute names to a tuple,
``(type, required)`` where ``type`` is the Python type for the
attribute and ``required`` is a boolean stating whether the attribute
is required to be present.
- ``_ELEMENTS`` - This is a dictionary mapping element names to a tuple,
``(type, required, multiple)`` where ``type`` is the Python type for the
element, ``required`` is a boolean stating whether the element
is required to be present, and ``multiple`` is a boolean indicating
whether multiple elements of this type could be present.
Elements are child nodes in the XML tree, and their type must be a
subclass of :class:`.URDFType`.
- ``_TAG`` - This is a string that represents the XML tag for the node
containing this type of object.
"""
_ATTRIBS = {} # Map from attrib name to (type, required)
_ELEMENTS = {} # Map from element name to (type, required, multiple)
_TAG = "" # XML tag for this element
def __init__(self):
pass
@classmethod
def _parse_attrib(cls, val_type, val):
"""Parse an XML attribute into a python value.
Parameters
----------
val_type : :class:`type`
The type of value to create.
val : :class:`object`
The value to parse.
Returns
-------
val : :class:`object`
The parsed attribute.
"""
if val_type == np.ndarray:
val = np.fromstring(val, sep=" ")
else:
val = val_type(val)
return val
@classmethod
def _parse_simple_attribs(cls, node):
"""Parse all attributes in the _ATTRIBS array for this class.
Parameters
----------
node : :class:`lxml.etree.Element`
The node to parse attributes for.
Returns
-------
kwargs : dict
Map from attribute name to value. If the attribute is not
required and is not present, that attribute's name will map to
``None``.
"""
kwargs = {}
for a in cls._ATTRIBS:
t, r = cls._ATTRIBS[a] # t = type, r = required (bool)
if r:
try:
v = cls._parse_attrib(t, node.attrib[a])
except Exception:
raise ValueError(
"Missing required attribute {} when parsing an object "
"of type {}".format(a, cls.__name__)
)
else:
v = None
if a in node.attrib:
v = cls._parse_attrib(t, node.attrib[a])
kwargs[a] = v
return kwargs
@classmethod
def _parse_simple_elements(cls, node, path):
"""Parse all elements in the _ELEMENTS array from the children of
this node.
Parameters
----------
node : :class:`lxml.etree.Element`
The node to parse children for.
path : str
The string path where the XML file is located (used for resolving
the location of mesh or image files).
lazy_load_meshes : bool
Whether a mesh element should be immediately loaded or loaded when
needed
Returns
-------
kwargs : dict
Map from element names to the :class:`URDFType` subclass (or list,
if ``multiple`` was set) created for that element.
"""
kwargs = {}
for a in cls._ELEMENTS:
t, r, m = cls._ELEMENTS[a]
if not m:
v = node.find(t._TAG)
if r or v is not None:
v = t._from_xml(v, path)
else:
vs = node.findall(t._TAG)
if len(vs) == 0 and r:
raise ValueError(
"Missing required subelement(s) of type {} when "
"parsing an object of type {}".format(t.__name__, cls.__name__)
)
v = [t._from_xml(n, path) for n in vs]
kwargs[a] = v
return kwargs
@classmethod
def _parse(cls, node, path):
"""Parse all elements and attributes in the _ELEMENTS and _ATTRIBS
arrays for a node.
Parameters
----------
node : :class:`lxml.etree.Element`
The node to parse.
path : str
The string path where the XML file is located (used for resolving
the location of mesh or image files).
Returns
-------
kwargs : dict
Map from names to Python classes created from the attributes
and elements in the class arrays.
"""
kwargs = cls._parse_simple_attribs(node)
kwargs.update(cls._parse_simple_elements(node, path))
return kwargs
@classmethod
def _from_xml(cls, node, path):
"""Create an instance of this class from an XML node.
Parameters
----------
node : :class:`lxml.etree.Element`
The node to parse.
path : str
The string path where the XML file is located (used for resolving
the location of mesh or image files).
Returns
-------
obj : :class:`URDFType`
An instance of this class parsed from the node.
"""
return cls(**cls._parse(node, path))
def _unparse_attrib(self, val_type, val):
"""Convert a Python value into a string for storage in an
XML attribute.
Parameters
----------
val_type : :class:`type`
The type of the Python object.
val : :class:`object`
The actual value.
Returns
-------
s : str
The attribute string.
"""
if val_type == np.ndarray:
val = np.array2string(val)[1:-1]
else:
val = str(val)
return val
def _unparse_simple_attribs(self, node):
"""Convert all Python types from the _ATTRIBS array back into attributes
for an XML node.
Parameters
----------
node : :class:`object`
The XML node to add the attributes to.
"""
for a in self._ATTRIBS:
t, r = self._ATTRIBS[a]
v = getattr(self, a, None)
if r or v is not None:
node.attrib[a] = self._unparse_attrib(t, v)
def _unparse_simple_elements(self, node, path):
"""Unparse all Python types from the _ELEMENTS array back into child
nodes of an XML node.
Parameters
----------
node : :class:`object`
The XML node for this object. Elements will be added as children
of this node.
path : str
The string path where the XML file is being written to (used for
writing out meshes and image files).
"""
for a in self._ELEMENTS:
t, r, m = self._ELEMENTS[a]
v = getattr(self, a, None)
if not m:
if r or v is not None:
node.append(v._to_xml(node, path))
else:
vs = v
for v in vs:
node.append(v._to_xml(node, path))
def _unparse(self, path):
"""Create a node for this object and unparse all elements and
attributes in the class arrays.
Parameters
----------
path : str
The string path where the XML file is being written to (used for
writing out meshes and image files).
Returns
-------
node : :class:`lxml.etree.Element`
The newly-created node.
"""
node = ET.Element(self._TAG)
self._unparse_simple_attribs(node)
self._unparse_simple_elements(node, path)
return node
def _to_xml(self, parent, path):
"""Create and return an XML node for this object.
Parameters
----------
parent : :class:`lxml.etree.Element`
The parent node that this element will eventually be added to.
This base implementation doesn't use this information, but
classes that override this function may use it.
path : str
The string path where the XML file is being written to (used for
writing out meshes and image files).
Returns
-------
node : :class:`lxml.etree.Element`
The newly-created node.
"""
return self._unparse(path)
class URDFTypeWithMesh(URDFType):
@classmethod
def _parse_simple_elements(cls, node, path, lazy_load_meshes):
"""Parse all elements in the _ELEMENTS array from the children of
this node.
Parameters
----------
node : :class:`lxml.etree.Element`
The node to parse children for.
path : str
The string path where the XML file is located (used for resolving
the location of mesh or image files).
lazy_load_meshes : bool
Whether a mesh element should be immediately loaded or loaded when
needed
Returns
-------
kwargs : dict
Map from element names to the :class:`URDFType` subclass (or list,
if ``multiple`` was set) created for that element.
"""
kwargs = {}
for a in cls._ELEMENTS:
t, r, m = cls._ELEMENTS[a]
if not m:
v = node.find(t._TAG)
if r or v is not None:
if issubclass(t, URDFTypeWithMesh):
v = t._from_xml(v, path, lazy_load_meshes)
else:
v = t._from_xml(v, path)
else:
vs = node.findall(t._TAG)
if len(vs) == 0 and r:
raise ValueError(
"Missing required subelement(s) of type {} when "
"parsing an object of type {}".format(t.__name__, cls.__name__)
)
if issubclass(t, URDFTypeWithMesh):
v = [t._from_xml(n, path, lazy_load_meshes) for n in vs]
else:
v = [t._from_xml(n, path) for n in vs]
kwargs[a] = v
return kwargs
@classmethod
def _parse(cls, node, path, lazy_load_meshes):
"""Parse all elements and attributes in the _ELEMENTS and _ATTRIBS
arrays for a node.
Parameters
----------
node : :class:`lxml.etree.Element`
The node to parse.
path : str
The string path where the XML file is located (used for resolving
the location of mesh or image files).
lazy_load_meshes : bool
Whether meshes should be loaded immediately or upon their first use
Returns
-------
kwargs : dict
Map from names to Python classes created from the attributes
and elements in the class arrays.
"""
kwargs = cls._parse_simple_attribs(node)
kwargs.update(cls._parse_simple_elements(node, path, lazy_load_meshes))
return kwargs
@classmethod
def _from_xml(cls, node, path, lazy_load_meshes):
"""Create an instance of this class from an XML node.
Parameters
----------
node : :class:`lxml.etree.Element`
The node to parse.
path : str
The string path where the XML file is located (used for resolving
the location of mesh or image files).
lazy_load_meshes : bool
Whether meshes should be loaded immediately or upon their first use
Returns
-------
obj : :class:`URDFType`
An instance of this class parsed from the node.
"""
return cls(**cls._parse(node, path, lazy_load_meshes))
###############################################################################
# Link types
###############################################################################
class Box(URDFType):
"""A rectangular prism whose center is at the local origin.
Parameters
----------
size : (3,) float
The length, width, and height of the box in meters.
"""
_ATTRIBS = {"size": (np.ndarray, True)}
_TAG = "box"
def __init__(self, size):
self.size = size
self._meshes = []
@property
def size(self):
"""(3,) float : The length, width, and height of the box in meters."""
return self._size
@size.setter
def size(self, value):
self._size = np.asanyarray(value).astype(np.float64)
self._meshes = []
@property
def meshes(self):
"""list of :class:`~trimesh.base.Trimesh` : The triangular meshes
that represent this object.
"""
if len(self._meshes) == 0:
self._meshes = [trimesh.creation.box(extents=self.size)]
return self._meshes
def copy(self, prefix="", scale=None):
"""Create a deep copy with the prefix applied to all names.
Parameters
----------
prefix : str
A prefix to apply to all names.
Returns
-------
:class:`.Box`
A deep copy.
"""
if scale is None:
scale = 1.0
b = Box(
size=self.size.copy() * scale,
)
return b
class Cylinder(URDFType):
"""A cylinder whose center is at the local origin.
Parameters
----------
radius : float
The radius of the cylinder in meters.
length : float
The length of the cylinder in meters.
"""
_ATTRIBS = {
"radius": (float, True),
"length": (float, True),
}
_TAG = "cylinder"
def __init__(self, radius, length):
self.radius = radius
self.length = length
self._meshes = []
@property
def radius(self):
"""float : The radius of the cylinder in meters."""
return self._radius
@radius.setter
def radius(self, value):
self._radius = float(value)
self._meshes = []
@property
def length(self):
"""float : The length of the cylinder in meters."""
return self._length
@length.setter
def length(self, value):
self._length = float(value)
self._meshes = []
@property
def meshes(self):
"""list of :class:`~trimesh.base.Trimesh` : The triangular meshes
that represent this object.
"""
if len(self._meshes) == 0:
self._meshes = [
trimesh.creation.cylinder(radius=self.radius, height=self.length)
]
return self._meshes
def copy(self, prefix="", scale=None):
"""Create a deep copy with the prefix applied to all names.
Parameters
----------
prefix : str
A prefix to apply to all names.
Returns
-------
:class:`.Cylinder`
A deep copy.
"""
if scale is None:
scale = 1.0
if isinstance(scale, (list, np.ndarray)):
if scale[0] != scale[1]:
raise ValueError(
"Cannot rescale cylinder geometry with asymmetry in x/y"
)
c = Cylinder(
radius=self.radius * scale[0],
length=self.length * scale[2],
)
else:
c = Cylinder(
radius=self.radius * scale,
length=self.length * scale,
)
return c
class Sphere(URDFType):
"""A sphere whose center is at the local origin.
Parameters
----------
radius : float
The radius of the sphere in meters.
"""
_ATTRIBS = {
"radius": (float, True),
}
_TAG = "sphere"
def __init__(self, radius):
self.radius = radius
self._meshes = []
@property
def radius(self):
"""float : The radius of the sphere in meters."""
return self._radius
@radius.setter
def radius(self, value):
self._radius = float(value)
self._meshes = []
@property
def meshes(self):
"""list of :class:`~trimesh.base.Trimesh` : The triangular meshes
that represent this object.
"""
if len(self._meshes) == 0:
self._meshes = [trimesh.creation.icosphere(radius=self.radius)]
return self._meshes
def copy(self, prefix="", scale=None):
"""Create a deep copy with the prefix applied to all names.
Parameters
----------
prefix : str
A prefix to apply to all names.
Returns
-------
:class:`.Sphere`
A deep copy.
"""
if scale is None:
scale = 1.0
if isinstance(scale, (list, np.ndarray)):
if scale[0] != scale[1] or scale[0] != scale[2]:
raise ValueError("Spheres do not support non-uniform scaling!")
scale = scale[0]
s = Sphere(
radius=self.radius * scale,
)
return s
class Mesh(URDFTypeWithMesh):
"""A triangular mesh object.
Parameters
----------
filename : str
The path to the mesh that contains this object. This can be
relative to the top-level URDF or an absolute path.
scale : (3,) float, optional
The scaling value for the mesh along the XYZ axes.
If ``None``, assumes no scale is applied.
meshes : list of :class:`~trimesh.base.Trimesh`
A list of meshes that compose this mesh.
The list of meshes is useful for visual geometries that
might be composed of separate trimesh objects.
If not specified, the mesh is loaded from the file using trimesh.
"""
_ATTRIBS = {"filename": (str, True), "scale": (np.ndarray, False)}
_TAG = "mesh"
def __init__(self, filename, combine, scale=None, meshes=None, lazy_filename=None):
if meshes is None:
if lazy_filename is None:
meshes = load_meshes(filename)
else:
meshes = None
self.filename = filename
self.scale = scale
self.lazy_filename = lazy_filename
self.combine = combine
self.meshes = meshes
@property
def filename(self):
"""str : The path to the mesh file for this object."""
return self._filename
@filename.setter
def filename(self, value):
self._filename = value
@property
def scale(self):
"""(3,) float : A scaling for the mesh along its local XYZ axes."""
return self._scale
@scale.setter
def scale(self, value):
if value is not None:
value = np.asanyarray(value).astype(np.float64)
self._scale = value
@property
def meshes(self):
"""list of :class:`~trimesh.base.Trimesh` : The triangular meshes
that represent this object.
"""
if self.lazy_filename is not None and self._meshes is None:
self.meshes = self._load_and_combine_meshes(
self.lazy_filename, self.combine
)
return self._meshes
@meshes.setter
def meshes(self, value):
if self.lazy_filename is not None and value is None:
self._meshes = None
elif isinstance(value, six.string_types):
value = load_meshes(value)
elif isinstance(value, (list, tuple, set, np.ndarray)):
value = list(value)
if len(value) == 0:
raise ValueError("Mesh must have at least one trimesh.Trimesh")
for m in value:
if not isinstance(m, trimesh.Trimesh):
raise TypeError(
"Mesh requires a trimesh.Trimesh or a " "list of them"
)
elif isinstance(value, trimesh.Trimesh):
value = [value]
else:
raise TypeError("Mesh requires a trimesh.Trimesh")
self._meshes = value
@staticmethod
def _load_and_combine_meshes(fn, combine):
meshes = load_meshes(fn)
if combine:
# Delete visuals for simplicity
for m in meshes:
m.visual = trimesh.visual.ColorVisuals(mesh=m)
meshes = [meshes[0] + meshes[1:]]
return meshes
@classmethod
def _from_xml(cls, node, path, lazy_load_meshes):
kwargs = cls._parse(node, path, lazy_load_meshes)
# Load the mesh, combining collision geometry meshes but keeping
# visual ones separate to preserve colors and textures
fn = get_filename(path, kwargs["filename"])
combine = node.getparent().getparent().tag == Collision._TAG
if not lazy_load_meshes:
meshes = cls._load_and_combine_meshes(fn, combine)
kwargs["lazy_filename"] = None
else:
meshes = None
kwargs["lazy_filename"] = fn
kwargs["meshes"] = meshes
kwargs["combine"] = combine
return Mesh(**kwargs)
def _to_xml(self, parent, path):
# Get the filename
fn = get_filename(path, self.filename, makedirs=True)
# Export the meshes as a single file
if self._meshes is not None:
meshes = self.meshes
if len(meshes) == 1:
meshes = meshes[0]
elif os.path.splitext(fn)[1] == ".glb":
meshes = trimesh.scene.Scene(geometry=meshes)
trimesh.exchange.export.export_mesh(meshes, fn)
# Unparse the node
node = self._unparse(path)
return node
def copy(self, prefix="", scale=None):
"""Create a deep copy with the prefix applied to all names.
Parameters
----------
prefix : str
A prefix to apply to all names.
Returns
-------
:class:`.Sphere`
A deep copy.
"""
meshes = [m.copy() for m in self.meshes]
if scale is not None:
sm = np.eye(4)
if isinstance(scale, (list, np.ndarray)):
sm[:3, :3] = np.diag(scale)
else:
sm[:3, :3] = np.diag(np.repeat(scale, 3))
for i, m in enumerate(meshes):
meshes[i] = m.apply_transform(sm)
base, fn = os.path.split(self.filename)
fn = "{}{}".format(prefix, self.filename)
m = Mesh(
filename=os.path.join(base, fn),
combine=self.combine,
scale=(self.scale.copy() if self.scale is not None else None),
meshes=meshes,
lazy_filename=self.lazy_filename,
)
return m
class Geometry(URDFTypeWithMesh):
"""A wrapper for all geometry types.
Only one of the following values can be set, all others should be set
to ``None``.
Parameters
----------
box : :class:`.Box`, optional
Box geometry.
cylinder : :class:`.Cylinder`
Cylindrical geometry.
sphere : :class:`.Sphere`
Spherical geometry.
mesh : :class:`.Mesh`
Mesh geometry.
"""
_ELEMENTS = {
"box": (Box, False, False),
"cylinder": (Cylinder, False, False),
"sphere": (Sphere, False, False),
"mesh": (Mesh, False, False),
}
_TAG = "geometry"
def __init__(self, box=None, cylinder=None, sphere=None, mesh=None):
if box is None and cylinder is None and sphere is None and mesh is None:
raise ValueError("At least one geometry element must be set")
self.box = box
self.cylinder = cylinder
self.sphere = sphere
self.mesh = mesh
@property
def box(self):
""":class:`.Box` : Box geometry."""
return self._box
@box.setter
def box(self, value):
if value is not None and not isinstance(value, Box):
raise TypeError("Expected Box type")
self._box = value
@property
def cylinder(self):
""":class:`.Cylinder` : Cylinder geometry."""
return self._cylinder
@cylinder.setter
def cylinder(self, value):
if value is not None and not isinstance(value, Cylinder):
raise TypeError("Expected Cylinder type")
self._cylinder = value
@property
def sphere(self):
""":class:`.Sphere` : Spherical geometry."""
return self._sphere
@sphere.setter
def sphere(self, value):
if value is not None and not isinstance(value, Sphere):
raise TypeError("Expected Sphere type")
self._sphere = value
@property
def mesh(self):
""":class:`.Mesh` : Mesh geometry."""
return self._mesh
@mesh.setter
def mesh(self, value):
if value is not None and not isinstance(value, Mesh):
raise TypeError("Expected Mesh type")
self._mesh = value
@property
def geometry(self):
""":class:`.Box`, :class:`.Cylinder`, :class:`.Sphere`, or
:class:`.Mesh` : The valid geometry element.
"""
if self.box is not None:
return self.box
if self.cylinder is not None:
return self.cylinder
if self.sphere is not None:
return self.sphere
if self.mesh is not None:
return self.mesh
return None
@property
def meshes(self):
"""list of :class:`~trimesh.base.Trimesh` : The geometry's triangular
mesh representation(s).
"""
return self.geometry.meshes
def copy(self, prefix="", scale=None):
"""Create a deep copy with the prefix applied to all names.
Parameters
----------
prefix : str
A prefix to apply to all names.
Returns
-------
:class:`.Geometry`
A deep copy.
"""
v = Geometry(
box=(self.box.copy(prefix=prefix, scale=scale) if self.box else None),
cylinder=(
self.cylinder.copy(prefix=prefix, scale=scale)
if self.cylinder
else None
),
sphere=(
self.sphere.copy(prefix=prefix, scale=scale) if self.sphere else None
),
mesh=(self.mesh.copy(prefix=prefix, scale=scale) if self.mesh else None),
)
return v
class Texture(URDFType):
"""An image-based texture.
Parameters
----------
filename : str
The path to the image that contains this texture. This can be
relative to the top-level URDF or an absolute path.
image : :class:`PIL.Image.Image`, optional
The image for the texture.
If not specified, it is loaded automatically from the filename.
"""
_ATTRIBS = {"filename": (str, True)}
_TAG = "texture"
def __init__(self, filename, image=None):
if image is None:
image = PIL.image.open(filename)
self.filename = filename
self.image = image
@property
def filename(self):
"""str : Path to the image for this texture."""
return self._filename
@filename.setter
def filename(self, value):
self._filename = str(value)
@property
def image(self):
""":class:`PIL.Image.Image` : The image for this texture."""
return self._image
@image.setter
def image(self, value):
if isinstance(value, str):
value = PIL.Image.open(value)
if isinstance(value, np.ndarray):
value = PIL.Image.fromarray(value)
elif not isinstance(value, PIL.Image.Image):
raise ValueError("Texture only supports numpy arrays " "or PIL images")
self._image = value
@classmethod
def _from_xml(cls, node, path):
kwargs = cls._parse(node, path)
# Load image
fn = get_filename(path, kwargs["filename"])
kwargs["image"] = PIL.Image.open(fn)
return Texture(**kwargs)
def _to_xml(self, parent, path):
# Save the image
filepath = get_filename(path, self.filename, makedirs=True)
self.image.save(filepath)
return self._unparse(path)
def copy(self, prefix="", scale=None):
"""Create a deep copy with the prefix applied to all names.
Parameters
----------
prefix : str
A prefix to apply to all names.
Returns
-------
:class:`.Texture`
A deep copy.
"""
v = Texture(filename=self.filename, image=self.image.copy())
return v
class Material(URDFType):
"""A material for some geometry.
Parameters
----------
name : str
The name of the material.
color : (4,) float, optional
The RGBA color of the material in the range [0,1].
texture : :class:`.Texture`, optional
A texture for the material.
"""
_ATTRIBS = {"name": (str, True)}
_ELEMENTS = {
"texture": (Texture, False, False),
}
_TAG = "material"
def __init__(self, name, color=None, texture=None):
self.name = name
self.color = color
self.texture = texture
@property
def name(self):
"""str : The name of the material."""
return self._name
@name.setter
def name(self, value):
self._name = str(value)
@property