-
-
Notifications
You must be signed in to change notification settings - Fork 42
/
parserURDF.py
1012 lines (895 loc) · 45.2 KB
/
parserURDF.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
"""Import modules."""
import os
import sys
import struct
import numpy
try:
from PIL import Image
except ImportError as e:
if sys.platform == 'linux2':
sys.stderr.write("PIL module not found, please install it with:\n")
sys.stderr.write("apt-get install python-pip\n")
sys.stderr.write("pip install pillow\n")
raise e
import numbers
from urdf2webots.gazebo_materials import materials
from urdf2webots.math_utils import convertRPYtoEulerAxis
try:
from collada import Collada, lineset
colladaIsAvailable = True
except ImportError:
colladaIsAvailable = False
counter = 0
# to pass from external
robotName = ''
disableMeshOptimization = False
class Trimesh():
"""Define triangular mesh object."""
def __init__(self):
"""Initializatization."""
self.coord = [] # list of coordinate points
self.coordIndex = [] # list of index of points
self.texCoord = [] # list of coordinate points for texture
self.texCoordIndex = [] # list of index for texture
self.normal = [] # list of normals
self.normalIndex = [] # list of index of normals
class Inertia():
"""Define inertia object."""
def __init__(self):
"""Initializatization."""
self.position = [0.0, 0.0, 0.0]
self.rotation = [1.0, 0.0, 0.0, 0.0]
self.mass = None
self.ixx = 1.0
self.ixy = 0.0
self.ixz = 0.0
self.iyy = 1.0
self.iyz = 0.0
self.izz = 1.0
class Box():
"""Define box object."""
def __init__(self):
"""Initializatization."""
self.x = 0.0
self.y = 0.0
self.z = 0.0
class Cylinder():
"""Define cylinder object."""
def __init__(self):
"""Initializatization."""
self.radius = 0.0
self.length = 0.0
class Sphere():
"""Define sphere object."""
def __init__(self):
"""Initializatization."""
self.radius = 0.0
class Geometry():
"""Define geometry object."""
reference = {}
def __init__(self):
"""Initializatization."""
self.box = Box()
self.cylinder = Cylinder()
self.sphere = Sphere()
self.trimesh = Trimesh()
self.scale = [1.0, 1.0, 1.0]
self.name = None
self.defName = None
self.lineset = False
class Color():
"""Define color object."""
def __init__(self, red=0.5, green=0.0, blue=0.0, alpha=1.0):
"""Initializatization."""
self.red = red
self.green = green
self.blue = blue
self.alpha = alpha
class Material():
"""Define material object."""
namedMaterial = {}
def __init__(self):
"""Initializatization."""
self.emission = Color(0.0, 0.0, 0.0, 1.0)
self.ambient = Color(0.0, 0.0, 0.0, 0.0)
self.diffuse = Color(0.5, 0.5, 0.5, 1.0)
self.specular = Color(0.0, 0.0, 0.0, 1.0)
self.shininess = None
self.index_of_refraction = 1.0
self.texture = ""
self.name = None
self.defName = None
def parseFromMaterialNode(self, node):
"""Parse a material node."""
if hasElement(node, 'color'):
colorElement = node.getElementsByTagName('color')[0]
colors = colorElement.getAttribute('rgba').split()
self.diffuse.r = float(colors[0])
self.diffuse.g = float(colors[1])
self.diffuse.b = float(colors[2])
self.diffuse.alpha = float(colors[3])
if node.hasAttribute('name'):
self.name = node.getAttribute('name')
if self.name not in Material.namedMaterial:
Material.namedMaterial[self.name] = self
else:
assert False
class Visual():
"""Define visual object."""
def __init__(self):
"""Initializatization."""
self.position = [0.0, 0.0, 0.0]
self.rotation = [1.0, 0.0, 0.0, 0.0]
self.geometry = Geometry()
self.material = Material()
class Collision():
"""Define collision object."""
def __init__(self):
"""Initializatization."""
self.position = [0.0, 0.0, 0.0]
self.rotation = [1.0, 0.0, 0.0, 0.0]
self.geometry = Geometry()
class Calibration():
"""Define calibration object."""
def __init__(self):
"""Initializatization."""
self.limit = 0.0
self.rising = True
class Dynamics():
"""Define dynamics object."""
def __init__(self):
"""Initializatization."""
self.damping = 0.0
self.friction = 0.0
class Limit():
"""Define joint limit object."""
def __init__(self):
"""Initializatization."""
self.lower = 0.0
self.upper = 0.0
self.effort = 10000 # if not specified in the URDF, there is no limit
self.velocity = 0.0
class Safety():
"""Define joint safety object."""
def __init__(self):
"""Initializatization."""
self.lower = 0.0
self.upper = 0.0
self.kPosition = 0.0
self.kVelocity = 0.0
class Link():
"""Define link object."""
def __init__(self):
"""Initializatization."""
self.name = 'default'
self.inertia = Inertia()
self.visual = []
self.collision = []
self.forceSensor = False
class Joint():
"""Define joint object."""
def __init__(self):
"""Initializatization."""
self.name = 'default'
self.type = 'default'
self.position = [0.0, 0.0, 0.0]
self.rotation = [1.0, 0.0, 0.0, 0.0]
self.parent = 'default'
self.child = 'default'
self.axis = []
self.calibration = Calibration()
self.dynamics = Dynamics()
self.limit = Limit()
self.safety = Safety()
class IMU():
"""Define an IMU sensor."""
list = []
def __init__(self):
"""Initializatization."""
self.name = 'imu'
self.gaussianNoise = 0
self.parentLink = None
def export(self, file, indentationLevel):
"""Export this IMU."""
indent = ' '
file.write(indentationLevel * indent + 'Accelerometer {\n')
file.write(indentationLevel * indent + ' name "%s accelerometer"\n' % self.name)
if self.gaussianNoise > 0:
file.write(indentationLevel * indent + ' lookupTable [-100 -100 %lf, 100 100 %lf]\n' %
(-self.gaussianNoise / 100.0, self.gaussianNoise / 100.0))
file.write(indentationLevel * indent + '}\n')
file.write(indentationLevel * indent + 'Gyro {\n')
file.write(indentationLevel * indent + ' name "%s gyro"\n' % self.name)
if self.gaussianNoise > 0:
file.write(indentationLevel * indent + ' lookupTable [-100 -100 %lf, 100 100 %lf]\n' %
(-self.gaussianNoise / 100.0, self.gaussianNoise / 100.0))
file.write(indentationLevel * indent + '}\n')
file.write(indentationLevel * indent + 'Compass {\n')
file.write(indentationLevel * indent + ' name "%s compass"\n' % self.name)
if self.gaussianNoise > 0:
file.write(indentationLevel * indent + ' lookupTable [-1 -1 %lf, 1 1 %lf]\n' %
(-self.gaussianNoise, self.gaussianNoise))
file.write(indentationLevel * indent + '}\n')
class Camera():
"""Define a camera sensor."""
list = []
def __init__(self):
"""Initializatization."""
self.name = 'camera'
self.fov = None
self.width = None
self.height = None
self.noise = None
def export(self, file, indentationLevel):
"""Export this camera."""
indent = ' '
file.write(indentationLevel * indent + 'Camera {\n')
# rotation to convert from REP103 to webots viewport
file.write(indentationLevel * indent + ' rotation 1.0 0.0 0.0 3.141591\n')
file.write(indentationLevel * indent + ' name "%s"\n' % self.name)
if self.fov:
file.write(indentationLevel * indent + ' fieldOfView %lf\n' % self.fov)
if self.width:
file.write(indentationLevel * indent + ' width %d\n' % self.width)
if self.height:
file.write(indentationLevel * indent + ' height %d\n' % self.height)
if self.noise:
file.write(indentationLevel * indent + ' noise %lf\n' % self.noise)
file.write(indentationLevel * indent + '}\n')
class Lidar():
"""Define a lidar sensor."""
list = []
def __init__(self):
"""Initializatization."""
self.name = 'lidar'
self.fov = None
self.verticalFieldOfView = None
self.horizontalResolution = None
self.numberOfLayers = 1
self.minRange = None
self.maxRange = None
self.resolution = None
self.noise = None
def export(self, file, indentationLevel):
"""Export this camera."""
indent = ' '
file.write(indentationLevel * indent + 'Lidar {\n')
file.write(indentationLevel * indent + ' name "%s"\n' % self.name)
if self.fov:
file.write(indentationLevel * indent + ' fieldOfView %lf\n' % self.fov)
if self.verticalFieldOfView:
file.write(indentationLevel * indent + ' verticalFieldOfView %lf\n' % self.verticalFieldOfView)
if self.horizontalResolution:
file.write(indentationLevel * indent + ' horizontalResolution %d\n' % self.horizontalResolution)
if self.numberOfLayers:
file.write(indentationLevel * indent + ' numberOfLayers %d\n' % self.numberOfLayers)
if self.minRange:
if self.minRange < 0.01:
file.write(indentationLevel * indent + ' near %lf\n' % self.minRange)
file.write(indentationLevel * indent + ' minRange %lf\n' % self.minRange)
if self.maxRange:
file.write(indentationLevel * indent + ' maxRange %lf\n' % self.maxRange)
if self.noise:
file.write(indentationLevel * indent + ' noise %lf\n' % self.noise)
if self.resolution:
file.write(indentationLevel * indent + ' resolution %lf\n' % self.resolution)
file.write(indentationLevel * indent + '}\n')
def colorVector2Instance(cv, alpha_last=True):
"""Eval color object from a vector."""
c = Color()
if alpha_last:
c.red = cv[0]
c.green = cv[1]
c.blue = cv[2]
c.alpha = cv[3]
else:
c.red = cv[1]
c.green = cv[2]
c.blue = cv[3]
c.alpha = cv[0]
return c
def getRobotName(node):
"""Parse robot name."""
name = node.getAttribute('name')
print('Robot name: ' + name)
return name
def hasElement(node, element):
"""Check if exlement existing in a tag."""
if node.getElementsByTagName(element).length > 0:
return True
else:
return False
def getSTLMesh(filename, node):
"""Read stl file."""
print('Parsing Mesh: ' + filename)
stlFile = open(filename, 'rb')
stlFile.read(80)
numTriangles = struct.unpack("@i", stlFile.read(4))[0]
struct.unpack("<3f", stlFile.read(12))
a = struct.unpack("<3f", stlFile.read(12))
b = struct.unpack("<3f", stlFile.read(12))
c = struct.unpack("<3f", stlFile.read(12))
struct.unpack("H", stlFile.read(2))
trimesh = node.geometry.trimesh
trimesh.coord.append(a)
trimesh.coord.append(b)
trimesh.coord.append(c)
if numTriangles > 50000 and not disableMeshOptimization:
print('Warning: This mesh has a lot of triangles!')
print('Warning: It is recommended to use the script with the \'--disable-mesh-optimization\' argument.')
for i in range(1, numTriangles):
if i % 100 == 0:
sys.stdout.write('%d / %d\r' % (i, numTriangles))
struct.unpack("<3f", stlFile.read(12))
a = struct.unpack("<3f", stlFile.read(12))
indexA = None
if disableMeshOptimization or a not in trimesh.coord:
indexA = len(trimesh.coord)
trimesh.coord.append(a)
b = struct.unpack("<3f", stlFile.read(12))
indexB = None
if disableMeshOptimization or b not in trimesh.coord:
indexB = len(trimesh.coord)
trimesh.coord.append(b)
c = struct.unpack("<3f", stlFile.read(12))
indexC = None
if disableMeshOptimization or c not in trimesh.coord:
indexC = len(trimesh.coord)
trimesh.coord.append(c)
struct.unpack("H", stlFile.read(2))
trimesh.coordIndex.append([indexA if indexA is not None else trimesh.coord.index(a),
indexB if indexB is not None else trimesh.coord.index(b),
indexC if indexC is not None else trimesh.coord.index(c)])
stlFile.close()
return node
def getOBJMesh(filename, node, link):
"""read obj file."""
print('Parsing Mesh: ' + filename)
if hasattr(node, 'material') and node.material:
isVisual = True
else:
isVisual = False
with open(filename, 'r') as file:
counter = 0
indexOffset = 0
collision = None
for line in file:
header, body = line.split(' ', 1)
if header == '#':
continue
elif header == 'o':
if counter != 0:
if isVisual:
link.visual.append(collision)
else:
link.collision.append(collision)
indexOffset += len(collision.geometry.trimesh.coord)
if isVisual:
collision = Visual()
collision.material = node.material
else:
collision = Collision()
collision.position = node.position
collision.rotation = node.rotation
collision.geometry.scale = node.geometry.scale
extSring = '_%d' % (counter) if counter != 0 else ''
collision.geometry.name = '%s%s' % (os.path.splitext(os.path.basename(filename))[0], extSring)
counter += 1
elif header == 'f': # face
vertices = body.split()
coordIndex = []
texCoordIndex = []
normalIndex = []
for vertex in vertices:
indices = vertex.split('/')
coordIndex.append(int(indices[0]) - indexOffset - 1) # vertex coordinates
length = len(indices)
if length > 1 and indices[1]: # texture coordinates
texCoordIndex.append(int(indices[1]) - indexOffset - 1)
if length > 2 and indices[2]: # normal coordinates
normalIndex.append(int(indices[2]) - indexOffset - 1)
collision.geometry.trimesh.coordIndex.append(coordIndex)
if texCoordIndex:
collision.geometry.trimesh.texCoordIndex.append(texCoordIndex)
if normalIndex:
collision.geometry.trimesh.normalIndex.append(normalIndex)
elif header == 'l': # line, ignored
continue
elif header == 'v': # vertex
x, y, z = body.split()
collision.geometry.trimesh.coord.append([float(x), float(y), float(z)])
elif header == 'vn': # normals
x, y, z = body.split()
collision.geometry.trimesh.normal.append([float(x), float(y), float(z)])
elif header == 'vp': # parameters, ignored
continue
elif header == 'vt': # texture coordinate
texCoord = body.split()
if len(texCoord) < 1: # v argument is optional and defaults to 0
texCoord.append('0')
collision.geometry.trimesh.texCoord.append([float(texCoord[0]), float(texCoord[1])])
continue
if isVisual:
link.visual.append(collision)
else:
link.collision.append(collision)
def getColladaMesh(filename, node, link):
"""Read collada file."""
if not colladaIsAvailable:
sys.stderr.write('Collada module not found, please install it with:\n')
sys.stderr.write(' python -m pip install pycollada\n')
sys.stderr.write('Skipping "%s"\n' % filename)
return
print('Parsing Mesh: ' + filename)
colladaMesh = Collada(filename)
index = -1
if hasattr(node, 'material') and node.material:
for geometry in list(colladaMesh.scene.objects('geometry')):
for data in list(geometry.primitives()):
visual = Visual()
index += 1
visual.position = node.position
visual.rotation = node.rotation
visual.material.diffuse.red = node.material.diffuse.red
visual.material.diffuse.green = node.material.diffuse.green
visual.material.diffuse.blue = node.material.diffuse.blue
visual.material.diffuse.alpha = node.material.diffuse.alpha
visual.material.texture = node.material.texture
name = '%s_%d' % (os.path.splitext(os.path.basename(filename))[0], index)
if type(data.original) is lineset.LineSet:
visual.geometry.lineset = True
if name in Geometry.reference:
visual.geometry = Geometry.reference[name]
else:
Geometry.reference[name] = visual.geometry
visual.geometry.name = name
visual.geometry.scale = node.geometry.scale
for val in data.vertex:
visual.geometry.trimesh.coord.append(numpy.array(val))
for val in data.vertex_index:
visual.geometry.trimesh.coordIndex.append(val)
if data.texcoordset: # non-empty
for val in data.texcoordset[0]:
visual.geometry.trimesh.texCoord.append(val)
if data.texcoord_indexset: # non-empty
for val in data.texcoord_indexset[0]:
visual.geometry.trimesh.texCoordIndex.append(val)
if hasattr(data, '_normal') and data._normal is not None and data._normal.size > 0:
for val in data._normal:
visual.geometry.trimesh.normal.append(numpy.array(val))
if hasattr(data, '_normal_index') and data._normal_index is not None and data._normal_index.size > 0:
for val in data._normal_index:
visual.geometry.trimesh.normalIndex.append(val)
if data.material and data.material.effect:
if data.material.effect.emission and isinstance(data.material.effect.emission, tuple):
visual.material.emission = colorVector2Instance(data.material.effect.emission)
if data.material.effect.ambient and isinstance(data.material.effect.ambient, tuple):
visual.material.ambient = colorVector2Instance(data.material.effect.ambient)
if data.material.effect.specular and isinstance(data.material.effect.specular, tuple):
visual.material.specular = colorVector2Instance(data.material.effect.specular)
if data.material.effect.shininess:
visual.material.shininess = data.material.effect.shininess
if data.material.effect.index_of_refraction:
visual.material.index_of_refraction = data.material.effect.index_of_refraction
if data.material.effect.diffuse:
if numpy.size(data.material.effect.diffuse) > 1\
and all([isinstance(x, numbers.Number) for x in data.material.effect.diffuse]):
# diffuse is defined by values
visual.material.diffuse = colorVector2Instance(data.material.effect.diffuse)
else:
# diffuse is defined by *.tif files
visual.material.texture = 'textures/' + \
data.material.effect.diffuse.sampler.surface.image.path.split('/')[-1]
txt = os.path.splitext(visual.material.texture)[1]
if txt == '.tiff' or txt == '.tif':
for dirname, dirnames, filenames in os.walk('.'):
for file in filenames:
if file == str(visual.material.texture.split('/')[-1]):
try:
tifImage = Image.open(os.path.join(dirname, file))
img = './' + robotName + '_textures'
tifImage.save(os.path.splitext(os.path.join(img, file))[0] + '.png')
visual.material.texture = (robotName +
'_textures/' + os.path.splitext(file)[0] + '.png')
print('translated image ' + visual.material.texture)
except IOError:
visual.material.texture = ""
print('failed to open ' + os.path.join(dirname, file))
link.visual.append(visual)
else:
for geometry in list(colladaMesh.scene.objects('geometry')):
for data in list(geometry.primitives()):
collision = Collision()
collision.position = node.position
collision.rotation = node.rotation
collision.geometry.scale = node.geometry.scale
for value in data.vertex:
collision.geometry.trimesh.coord.append(numpy.array(value))
for value in data.vertex_index:
collision.geometry.trimesh.coordIndex.append(value)
link.collision.append(collision)
def getPosition(node):
"""Read position of a phsical or visual object."""
position = [0.0, 0.0, 0.0]
positionString = node.getElementsByTagName('origin')[0].getAttribute('xyz').split()
position[0] = float(positionString[0])
position[1] = float(positionString[1])
position[2] = float(positionString[2])
return position
def getRotation(node, isCylinder=False):
"""Read rotation of a phsical or visual object."""
rotation = [0.0, 0.0, 0.0]
if hasElement(node, 'origin'):
orientationString = node.getElementsByTagName('origin')[0].getAttribute('rpy').split()
rotation[0] = float(orientationString[0])
rotation[1] = float(orientationString[1])
rotation[2] = float(orientationString[2])
if isCylinder:
return convertRPYtoEulerAxis(rotation, True)
else:
return convertRPYtoEulerAxis(rotation, False)
def getInertia(node):
"""Parse inertia of a link."""
inertia = Inertia()
inertialElement = node.getElementsByTagName('inertial')[0]
if hasElement(inertialElement, 'origin'):
if inertialElement.getElementsByTagName('origin')[0].getAttribute('xyz'):
inertia.position = getPosition(inertialElement)
if inertialElement.getElementsByTagName('origin')[0].getAttribute('rpy'):
inertia.rotation = getRotation(inertialElement)
if hasElement(inertialElement, 'mass'):
inertia.mass = float(inertialElement.getElementsByTagName('mass')[0].getAttribute('value'))
if hasElement(inertialElement, 'inertia'):
matrixNode = inertialElement.getElementsByTagName('inertia')[0]
inertia.ixx = float(matrixNode.getAttribute('ixx'))
inertia.ixy = float(matrixNode.getAttribute('ixy'))
inertia.ixz = float(matrixNode.getAttribute('ixz'))
inertia.iyy = float(matrixNode.getAttribute('iyy'))
inertia.iyz = float(matrixNode.getAttribute('iyz'))
inertia.izz = float(matrixNode.getAttribute('izz'))
return inertia
def getVisual(link, node, path):
"""Parse visual data of a link."""
for index in range(0, len(node.getElementsByTagName('visual'))):
visual = Visual()
visualElement = node.getElementsByTagName('visual')[index]
if hasElement(visualElement, 'origin'):
if visualElement.getElementsByTagName('origin')[0].getAttribute('xyz'):
visual.position = getPosition(visualElement)
if visualElement.getElementsByTagName('origin')[0].getAttribute('rpy'):
if hasElement(visualElement.getElementsByTagName('geometry')[0], 'cylinder'):
visual.rotation = getRotation(visualElement, True)
else:
visual.rotation = getRotation(visualElement)
elif hasElement(visualElement.getElementsByTagName('geometry')[0], 'cylinder'):
visual.rotation = getRotation(visualElement, True)
geometryElement = visualElement.getElementsByTagName('geometry')[0]
if hasElement(visualElement, 'material'):
material = visualElement.getElementsByTagName('material')[0]
if material.hasAttribute('name') and material.getAttribute('name') in Material.namedMaterial:
visual.material = Material.namedMaterial[material.getAttribute('name')]
elif hasElement(material, 'color'):
colorElement = material.getElementsByTagName('color')[0].getAttribute('rgba').split()
visual.material.diffuse.red = float(colorElement[0])
visual.material.diffuse.green = float(colorElement[1])
visual.material.diffuse.blue = float(colorElement[2])
visual.material.diffuse.alpha = float(colorElement[3])
if material.hasAttribute('name'):
if material.getAttribute('name'):
visual.material.name = material.getAttribute('name')
else:
visual.material.name = node.getAttribute('name') + '_material'
Material.namedMaterial[visual.material.name] = visual.material
elif material.firstChild and material.firstChild.nodeValue in materials:
materialName = material.firstChild.nodeValue
visual.material.diffuse.red = float(materials[materialName]['diffuse'][0])
visual.material.diffuse.green = float(materials[materialName]['diffuse'][1])
visual.material.diffuse.blue = float(materials[materialName]['diffuse'][2])
visual.material.diffuse.alpha = float(materials[materialName]['diffuse'][3])
visual.material.ambient.red = float(materials[materialName]['ambient'][0])
visual.material.ambient.green = float(materials[materialName]['ambient'][1])
visual.material.ambient.blue = float(materials[materialName]['ambient'][2])
visual.material.ambient.alpha = float(materials[materialName]['ambient'][3])
visual.material.specular.red = float(materials[materialName]['specular'][0])
visual.material.specular.green = float(materials[materialName]['specular'][1])
visual.material.specular.blue = float(materials[materialName]['specular'][2])
visual.material.specular.alpha = float(materials[materialName]['specular'][3])
visual.material.name = materialName
Material.namedMaterial[materialName] = visual.material
if hasElement(material, 'texture'):
visual.material.texture = material.getElementsByTagName('texture')[0].getAttribute('filename')
if os.path.splitext(visual.material.texture)[1] == '.tiff' \
or os.path.splitext(visual.material.texture)[1] == '.tif':
for dirname, dirnames, filenames in os.walk('.'):
for filename in filenames:
if filename == str(visual.material.texture.split('/')[-1]):
print('try to translate image ' + filename)
try:
tifImage = Image.open(os.path.join(dirname, filename))
tifImage.save(os.path.splitext(os.path.join('./' + robotName + '_' + 'textures',
filename))[0] + '.png')
visual.material.texture = (robotName + '_' + 'textures/' +
os.path.splitext(filename)[0] + '.png')
except IOError:
visual.material.texture = ""
print('failed to open ' + os.path.join(dirname, filename))
if hasElement(geometryElement, 'box'):
visual.geometry.box.x = float(geometryElement.getElementsByTagName('box')[0].getAttribute('size').split()[0])
visual.geometry.box.y = float(geometryElement.getElementsByTagName('box')[0].getAttribute('size').split()[1])
visual.geometry.box.z = float(geometryElement.getElementsByTagName('box')[0].getAttribute('size').split()[2])
link.visual.append(visual)
elif hasElement(geometryElement, 'cylinder'):
visual.geometry.cylinder.radius = float(geometryElement.getElementsByTagName('cylinder')[0].getAttribute('radius'))
visual.geometry.cylinder.length = float(geometryElement.getElementsByTagName('cylinder')[0].getAttribute('length'))
link.visual.append(visual)
elif hasElement(geometryElement, 'sphere'):
visual.geometry.sphere.radius = float(geometryElement.getElementsByTagName('sphere')[0].getAttribute('radius'))
link.visual.append(visual)
elif hasElement(geometryElement, 'mesh'):
meshfile = geometryElement.getElementsByTagName('mesh')[0].getAttribute('filename')
if not os.path.isabs(meshfile):
meshfile = os.path.normpath(os.path.join(path, meshfile))
# hack for gazebo mesh database
if meshfile.count('package'):
idx0 = meshfile.find('package://')
meshfile = meshfile[idx0 + len('package://'):]
if geometryElement.getElementsByTagName('mesh')[0].getAttribute('scale'):
meshScale = geometryElement.getElementsByTagName('mesh')[0].getAttribute('scale').split()
visual.geometry.scale[0] = float(meshScale[0])
visual.geometry.scale[1] = float(meshScale[1])
visual.geometry.scale[2] = float(meshScale[2])
extension = os.path.splitext(meshfile)[1].lower()
if extension == '.dae':
getColladaMesh(meshfile, visual, link)
elif extension == '.obj':
getOBJMesh(meshfile, visual, link)
elif extension == '.stl':
name = os.path.splitext(os.path.basename(meshfile))[0]
if name in Geometry.reference:
visual.geometry = Geometry.reference[name]
else:
if extension == '.stl':
visual = getSTLMesh(meshfile, visual)
visual.geometry.name = name
Geometry.reference[name] = visual.geometry
link.visual.append(visual)
else:
print('Unsupported mesh format: \"' + extension + '\"')
def getCollision(link, node, path):
"""Parse collision of a link."""
for index in range(0, len(node.getElementsByTagName('collision'))):
collision = Collision()
collisionElement = node.getElementsByTagName('collision')[index]
if hasElement(collisionElement, 'origin'):
if collisionElement.getElementsByTagName('origin')[0].getAttribute('xyz'):
collision.position = getPosition(collisionElement)
if collisionElement.getElementsByTagName('origin')[0].getAttribute('rpy'):
if hasElement(collisionElement.getElementsByTagName('geometry')[0], 'cylinder'):
collision.rotation = getRotation(collisionElement, True)
else:
collision.rotation = getRotation(collisionElement)
elif hasElement(collisionElement.getElementsByTagName('geometry')[0], 'cylinder'):
collision.rotation = getRotation(collisionElement, True)
geometryElement = collisionElement.getElementsByTagName('geometry')[0]
if hasElement(geometryElement, 'box'):
size = geometryElement.getElementsByTagName('box')[0].getAttribute('size').split()
collision.geometry.box.x = float(size[0])
collision.geometry.box.y = float(size[1])
collision.geometry.box.z = float(size[2])
link.collision.append(collision)
elif hasElement(geometryElement, 'cylinder'):
element = geometryElement.getElementsByTagName('cylinder')[0]
collision.geometry.cylinder.radius = float(element.getAttribute('radius'))
collision.geometry.cylinder.length = float(element.getAttribute('length'))
link.collision.append(collision)
elif hasElement(geometryElement, 'sphere'):
collision.geometry.sphere.radius = float(geometryElement.getElementsByTagName('sphere')[0].getAttribute('radius'))
link.collision.append(collision)
elif hasElement(geometryElement, 'mesh'):
meshfile = os.path.normpath(os.path.join(path,
geometryElement.getElementsByTagName('mesh')[0].getAttribute('filename')))
if geometryElement.getElementsByTagName('mesh')[0].getAttribute('scale'):
meshScale = geometryElement.getElementsByTagName('mesh')[0].getAttribute('scale').split()
collision.geometry.scale[0] = float(meshScale[0])
collision.geometry.scale[1] = float(meshScale[1])
collision.geometry.scale[2] = float(meshScale[2])
# hack for gazebo mesh database
if meshfile.count('package'):
idx0 = meshfile.find('package://')
meshfile = meshfile[idx0 + len('package://'):]
extension = os.path.splitext(meshfile)[1].lower()
if extension == '.dae':
getColladaMesh(meshfile, collision, link)
elif extension == '.obj':
getOBJMesh(meshfile, collision, link)
elif extension == '.stl':
name = os.path.splitext(os.path.basename(meshfile))[0]
if name in Geometry.reference:
collision.geometry = Geometry.reference[name]
else:
if extension == '.stl':
collision.geometry.stl = getSTLMesh(meshfile, collision)
collision.geometry.name = name
Geometry.reference[name] = collision.geometry
link.collision.append(collision)
else:
print('Unsupported mesh format for collision: \"' + extension + '\"')
def getAxis(node):
"""Parse rotation axis of a joint."""
axis = [0.0, 0.0, 0.0]
axisElement = node.getElementsByTagName('axis')[0].getAttribute('xyz').split()
axis[0] = float(axisElement[0])
axis[1] = float(axisElement[1])
axis[2] = float(axisElement[2])
return axis
def getCalibration(node):
"""Get the URDF calibration tag."""
calibration = Calibration()
calibrationElement = node.getElementsByTagName('calibration')[0]
if hasElement(calibrationElement, 'rising'):
calibration.limit = calibrationElement.getAttribute('rising')
calibration.rising = True
else:
calibration.limit = calibrationElement.getAttribute('falling')
calibration.rising = False
return calibration
def getDynamics(node):
"""Parse dynamics parameters of a joint."""
dynamics = Dynamics()
dynamicsElement = node.getElementsByTagName('dynamics')[0]
if dynamicsElement.getAttribute('damping'):
dynamics.damping = float(dynamicsElement.getAttribute('damping'))
if dynamicsElement.getAttribute('friction'):
dynamics.friction = float(dynamicsElement.getAttribute('friction'))
return dynamics
def getLimit(node):
"""Get limits of a joint."""
limit = Limit()
limitElement = node.getElementsByTagName('limit')[0]
if limitElement.getAttribute('lower'):
limit.lower = float(limitElement.getAttribute('lower'))
if limitElement.getAttribute('upper'):
limit.upper = float(limitElement.getAttribute('upper'))
if float(limitElement.getAttribute('effort')) != 0:
limit.effort = float(limitElement.getAttribute('effort'))
limit.velocity = float(limitElement.getAttribute('velocity'))
return limit
def getSafety(node):
"""Get safety controller of a joint."""
safety = Safety()
if node.getElementsByTagName('safety_controller')[0].getAttribute('soft_lower_limit'):
safety.lower = float(node.getElementsByTagName('safety_controller')[0].getAttribute('soft_lower_limit'))
if node.getElementsByTagName('safety_controller')[0].getAttribute('soft_upper_limit'):
safety.upper = float(node.getElementsByTagName('safety_controller')[0].getAttribute('soft_upper_limit'))
if node.getElementsByTagName('safety_controller')[0].getAttribute('k_position'):
safety.kPosition = float(node.getElementsByTagName('safety_controller')[0].getAttribute('k_position'))
safety.kVelocity = float(node.getElementsByTagName('safety_controller')[0].getAttribute('k_velocity'))
return safety
def getLink(node, path):
"""Parse a link."""
link = Link()
link.name = node.getAttribute('name')
if hasElement(node, 'inertial'):
link.inertia = getInertia(node)
if hasElement(node, 'visual'):
getVisual(link, node, path)
if hasElement(node, 'collision'):
getCollision(link, node, path)
if not any([hasElement(node, 'inertial'), hasElement(node, 'visual'), hasElement(node, 'collision')]):
link.inertia.mass = None
return link
def getJoint(node):
"""Parse a joint."""
joint = Joint()
joint.name = node.getAttribute('name')
joint.type = node.getAttribute('type')
if hasElement(node, 'origin'):
if node.getElementsByTagName('origin')[0].getAttribute('xyz'):
joint.position = getPosition(node)
if node.getElementsByTagName('origin')[0].getAttribute('rpy'):
joint.rotation = getRotation(node)
joint.parent = node.getElementsByTagName('parent')[0].getAttribute('link')
joint.child = node.getElementsByTagName('child')[0].getAttribute('link')
if hasElement(node, 'axis'):
joint.axis = getAxis(node)
if hasElement(node, 'calibration'):
joint.calibration = getCalibration(node)
if hasElement(node, 'dynamics'):
joint.dynamics = getDynamics(node)
if hasElement(node, 'limit'):
joint.limit = getLimit(node)
if hasElement(node, 'safety_controller'):
joint.safety = getSafety(node)
return joint
def isRootLink(link, childList):
"""Check if a link is root link."""
for child in childList:
if link == child:
return False
return True
def parseGazeboElement(element, parentLink, linkList):
"""Parse a Gazebo element."""
if element.hasAttribute("reference") and any([link.name == element.getAttribute('reference') for link in linkList]):
parentLink = element.getAttribute("reference")
for plugin in element.getElementsByTagName('plugin'):
if plugin.hasAttribute('filename') and plugin.getAttribute('filename').startswith('libgazebo_ros_imu'):
imu = IMU()
imu.parentLink = parentLink
if hasElement(plugin, 'topicName'):
imu.name = plugin.getElementsByTagName('topicName')[0].firstChild.nodeValue
if hasElement(plugin, 'gaussianNoise'):
imu.gaussianNoise = float(plugin.getElementsByTagName('gaussianNoise')[0].firstChild.nodeValue)
IMU.list.append(imu)
elif plugin.hasAttribute('filename') and plugin.getAttribute('filename').startswith('libgazebo_ros_f3d'):
if hasElement(plugin, "bodyName"):
name = plugin.getElementsByTagName('bodyName')[0].firstChild.nodeValue
for link in linkList:
if link.name == name:
link.forceSensor = True
break
for sensorElement in element.getElementsByTagName('sensor'):
sensorElement = element.getElementsByTagName('sensor')[0]
if sensorElement.getAttribute('type') == 'camera':
camera = Camera()
camera.parentLink = parentLink
camera.name = sensorElement.getAttribute('name')
if hasElement(sensorElement, 'camera'):
cameraElement = sensorElement.getElementsByTagName('camera')[0]
if hasElement(cameraElement, 'horizontal_fov'):
camera.fov = float(cameraElement.getElementsByTagName('horizontal_fov')[0].firstChild.nodeValue)
if hasElement(cameraElement, 'image'):
imageElement = cameraElement.getElementsByTagName('image')[0]
if hasElement(imageElement, 'width'):
camera.width = int(imageElement.getElementsByTagName('width')[0].firstChild.nodeValue)
if hasElement(imageElement, 'height'):
camera.height = int(imageElement.getElementsByTagName('height')[0].firstChild.nodeValue)
if hasElement(imageElement, 'format') \
and imageElement.getElementsByTagName('format')[0].firstChild.nodeValue != 'R8G8B8A8':
print('Unsupported "%s" image format, using "R8G8B8A8" instead.' %
str(imageElement.getElementsByTagName('format')[0].firstChild.nodeValue))
if hasElement(sensorElement, 'noise'):
noiseElement = sensorElement.getElementsByTagName('noise')[0]
if hasElement(noiseElement, 'stddev'):
camera.noise = float(noiseElement.getElementsByTagName('stddev')[0].firstChild.nodeValue)
Camera.list.append(camera)
elif sensorElement.getAttribute('type') == 'ray' or sensorElement.getAttribute('type') == 'gpu_ray':
lidar = Lidar()
lidar.parentLink = parentLink
lidar.name = sensorElement.getAttribute('name')
if hasElement(sensorElement, 'ray'):
rayElement = sensorElement.getElementsByTagName('ray')[0]
if hasElement(rayElement, 'scan'):
scanElement = rayElement.getElementsByTagName('scan')[0]
if hasElement(scanElement, 'horizontal'):
horizontalElement = scanElement.getElementsByTagName('horizontal')[0]
if hasElement(horizontalElement, 'samples'):
lidar.horizontalResolution = \
int(float(horizontalElement.getElementsByTagName('samples')[0].firstChild.nodeValue))
if hasElement(horizontalElement, 'min_angle') and hasElement(horizontalElement, 'max_angle'):
minAngle = float(horizontalElement.getElementsByTagName('min_angle')[0].firstChild.nodeValue)
maxAngle = float(horizontalElement.getElementsByTagName('max_angle')[0].firstChild.nodeValue)
lidar.fov = maxAngle - minAngle
if hasElement(scanElement, 'vertical'):
horizontalElement = scanElement.getElementsByTagName('horizontal')[0]
if hasElement(horizontalElement, 'samples'):
lidar.numberOfLayers = \
int(horizontalElement.getElementsByTagName('samples')[0].firstChild.nodeValue)
if hasElement(horizontalElement, 'min_angle') and hasElement(horizontalElement, 'max_angle'):
minAngle = float(horizontalElement.getElementsByTagName('min_angle')[0].firstChild.nodeValue)
maxAngle = float(horizontalElement.getElementsByTagName('max_angle')[0].firstChild.nodeValue)
lidar.verticalFieldOfView = maxAngle - minAngle
if hasElement(rayElement, 'range'):
rangeElement = rayElement.getElementsByTagName('range')[0]
if hasElement(rangeElement, 'min'):