-
Notifications
You must be signed in to change notification settings - Fork 8
/
firstgen.py
executable file
·2045 lines (1718 loc) · 88.8 KB
/
firstgen.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/python
import sys
import os
import xml.dom.minidom
import lxml.etree
import math
import numpy # for creating matrix to convert to quaternion
import yaml
import urdf_parser_py.urdf
import argparse
import csv
# Conversion Factors
INCH2METER = 0.0254
SLUG2KG = 14.5939029
SLUGININ2KGMM = .009415402
MM2M = .001
# Special Reference Frame(s)
WORLD = "WORLD"
# Arbitrary List of colors to give pieces different looks
COLORS = [("green", (0, 1, 0, 1)), ("black", (0, 0, 0, 1)), ("red", (1, 0, 0, 1)),
("blue", (0, 0, 1, 1)), ("yellow", (1, 1, 0, 1)), ("pink", (1, 0, 1, 1)),
("cyan", (0, 1, 1, 1)), ("green", (0, 1, 0, 1)), ("white", (1, 1, 1, 1)),
("dblue", (0, 0, .8, 1)), ("dgreen", (.1, .8, .1, 1)), ("gray", (.5, .5, .5, 1))]
# List of supported sensor types
SENSOR_TYPES = ["altimeter", "camera", "contact", "depth", "gps", "gpu_ray", "imu", "accelerometer", "gyroscope",
"logical_camera",
"magnetometer", "multicamera", "ray", "rfid", "rfidtag", "sonar", "wireless_receiver",
"wireless_transmitter"]
# List of supported geometric shapes and their properties
GEOMETRIC_SHAPES = {
'box': ['origin', 'size'],
'cylinder': ['origin', 'radius', 'length', ],
'sphere': ['origin', 'radius']}
# epsilon for testing whether a number is close to zero
_EPS = numpy.finfo(float).eps * 4.0
# axis sequences for Euler angles
_NEXT_AXIS = [1, 2, 0, 1]
# map axes strings to/from tuples of inner axis, parity, repetition, frame
_AXES2TUPLE = {
'sxyz': (0, 0, 0, 0), 'sxyx': (0, 0, 1, 0), 'sxzy': (0, 1, 0, 0),
'sxzx': (0, 1, 1, 0), 'syzx': (1, 0, 0, 0), 'syzy': (1, 0, 1, 0),
'syxz': (1, 1, 0, 0), 'syxy': (1, 1, 1, 0), 'szxy': (2, 0, 0, 0),
'szxz': (2, 0, 1, 0), 'szyx': (2, 1, 0, 0), 'szyz': (2, 1, 1, 0),
'rzyx': (0, 0, 0, 1), 'rxyx': (0, 0, 1, 1), 'ryzx': (0, 1, 0, 1),
'rxzx': (0, 1, 1, 1), 'rxzy': (1, 0, 0, 1), 'ryzy': (1, 0, 1, 1),
'rzxy': (1, 1, 0, 1), 'ryxy': (1, 1, 1, 1), 'ryxz': (2, 0, 0, 1),
'rzxz': (2, 0, 1, 1), 'rxyz': (2, 1, 0, 1), 'rzyz': (2, 1, 1, 1)}
_TUPLE2AXES = dict((v, k) for k, v in _AXES2TUPLE.items())
def euler_matrix(ai, aj, ak, axes='sxyz'):
"""Return homogeneous rotation matrix from Euler angles and axis sequence.
ai, aj, ak : Euler's roll, pitch and yaw angles
axes : One of 24 axis sequences as string or encoded tuple
>>> R = euler_matrix(1, 2, 3, 'syxz')
>>> numpy.allclose(numpy.sum(R[0]), -1.34786452)
True
>>> R = euler_matrix(1, 2, 3, (0, 1, 0, 1))
>>> numpy.allclose(numpy.sum(R[0]), -0.383436184)
True
>>> ai, aj, ak = (4*math.pi) * (numpy.random.random(3) - 0.5)
>>> for axes in _AXES2TUPLE.keys():
... R = euler_matrix(ai, aj, ak, axes)
>>> for axes in _TUPLE2AXES.keys():
... R = euler_matrix(ai, aj, ak, axes)
"""
try:
firstaxis, parity, repetition, frame = _AXES2TUPLE[axes]
except (AttributeError, KeyError):
_TUPLE2AXES[axes] # noqa: validation
firstaxis, parity, repetition, frame = axes
i = firstaxis
j = _NEXT_AXIS[i+parity]
k = _NEXT_AXIS[i-parity+1]
if frame:
ai, ak = ak, ai
if parity:
ai, aj, ak = -ai, -aj, -ak
si, sj, sk = math.sin(ai), math.sin(aj), math.sin(ak)
ci, cj, ck = math.cos(ai), math.cos(aj), math.cos(ak)
cc, cs = ci*ck, ci*sk
sc, ss = si*ck, si*sk
M = numpy.identity(4)
if repetition:
M[i, i] = cj
M[i, j] = sj*si
M[i, k] = sj*ci
M[j, i] = sj*sk
M[j, j] = -cj*ss+cc
M[j, k] = -cj*cs-sc
M[k, i] = -sj*ck
M[k, j] = cj*sc+cs
M[k, k] = cj*cc-ss
else:
M[i, i] = cj*ck
M[i, j] = sj*sc-cs
M[i, k] = sj*cc+ss
M[j, i] = cj*sk
M[j, j] = sj*ss+cc
M[j, k] = sj*cs-sc
M[k, i] = -sj
M[k, j] = cj*si
M[k, k] = cj*ci
return M
def euler_from_matrix(matrix, axes='sxyz'):
"""Return Euler angles from rotation matrix for specified axis sequence.
axes : One of 24 axis sequences as string or encoded tuple
Note that many Euler angle triplets can describe one matrix.
>>> R0 = euler_matrix(1, 2, 3, 'syxz')
>>> al, be, ga = euler_from_matrix(R0, 'syxz')
>>> R1 = euler_matrix(al, be, ga, 'syxz')
>>> numpy.allclose(R0, R1)
True
>>> angles = (4.0*math.pi) * (numpy.random.random(3) - 0.5)
>>> for axes in _AXES2TUPLE.keys():
... R0 = euler_matrix(axes=axes, *angles)
... R1 = euler_matrix(axes=axes, *euler_from_matrix(R0, axes))
... if not numpy.allclose(R0, R1): print axes, "failed"
"""
try:
firstaxis, parity, repetition, frame = _AXES2TUPLE[axes.lower()]
except (AttributeError, KeyError):
_ = _TUPLE2AXES[axes]
firstaxis, parity, repetition, frame = axes
i = firstaxis
j = _NEXT_AXIS[i + parity]
k = _NEXT_AXIS[i - parity + 1]
M = numpy.array(matrix, dtype=numpy.float64, copy=False)[:3, :3]
if repetition:
sy = math.sqrt(M[i, j] * M[i, j] + M[i, k] * M[i, k])
if sy > _EPS:
ax = math.atan2(M[i, j], M[i, k])
ay = math.atan2(sy, M[i, i])
az = math.atan2(M[j, i], -M[k, i])
else:
ax = math.atan2(-M[j, k], M[j, j])
ay = math.atan2(sy, M[i, i])
az = 0.0
else:
cy = math.sqrt(M[i, i] * M[i, i] + M[j, i] * M[j, i])
if cy > _EPS:
ax = math.atan2(M[k, j], M[k, k])
ay = math.atan2(-M[k, i], cy)
az = math.atan2(M[j, i], M[i, i])
else:
ax = math.atan2(-M[j, k], M[j, j])
ay = math.atan2(-M[k, i], cy)
az = 0.0
if parity:
ax, ay, az = -ax, -ay, -az
if frame:
ax, az = az, ax
return ax, ay, az
def euler_from_quaternion(quaternion, axes='sxyz'):
"""Return Euler angles from quaternion for specified axis sequence.
>>> angles = euler_from_quaternion([0.06146124, 0, 0, 0.99810947])
>>> numpy.allclose(angles, [0.123, 0, 0])
True
"""
return euler_from_matrix(quaternion_matrix(quaternion), axes)
class Converter:
def __init__(self):
# initialize member variables
self.links = {}
self.frames = {}
self.joints = {}
self.names = {}
self.colormap = {}
self.colorindex = 0
self.ref2nameMap = {}
self.realRootLink = None
self.outputString = "".encode('UTF-8')
self.sensorIsValid = False
self.sensorsDefaultMap = {}
# map mapping USERADDED linkName+displayName to fid of the frame
self.linkNameDisplayName2fid = {}
# Start the Custom Transform Manager
self.tfman = CustomTransformManager()
# Extra Transforms for Debugging
self.tfman.add([0, 0, 0], [0.70682518, 0, 0, 0.70682518], "ROOT", WORLD) # rotate so Z axis is up
# convert sensor type to gazebo respective sensor type
self.sensorTypeUrdf2sdf = {'imu': 'imu', 'accelerometer': 'imu', 'gyroscope': 'imu'}
def convert(self, filename, yaml_configfile, csv_configfile, mode, outputfile_name):
self.mode = mode
# Parse the global YAML configuration file
self.parseYAMLConfig(yaml_configfile)
# Parse the joint CSV configuratio nfile
self.parseJointCSVConfig(csv_configfile)
# Parse the input file
self.parse(xml.dom.minidom.parse(filename))
self.buildTree(self.root)
# Create the output
self.output(self.root)
# output the output
if mode == "xml":
# print("URDF model to print : \n " + str(self.result) + "\n" )
self.generateXML()
addXMLBlobs(self.XMLBlobs, self.urdf_xml)
self.addSensors()
self.addOrigin()
self.outputString = lxml.etree.tostring(self.urdf_xml, pretty_print=True)
if mode == "graph":
self.outputString = self.graph().encode('UTF-8')
if mode == "debug":
self.debugPrints()
# save the output to file or print in the terminal
if (outputfile_name is not None):
f = open(outputfile_name, 'wb')
f.write(self.outputString)
f.close()
else:
print(self.outputString)
def debugPrints(self):
print(
"root_link_T_l_foot_CG :\n " + str(self.tfman.getHomTransform("X" + "root_link", "l_foot" + "CG")[:3, 3]));
print(
"root_link_T_r_foot_CG :\n " + str(self.tfman.getHomTransform("X" + "root_link", "r_foot" + "CG")[:3, 3]));
def generateXML(self):
self.urdf_xml = self.result.to_xml();
def addSensors(self):
generatorGazeboSensors = URDFGazeboSensorsGenerator();
generatorURDFSensors = URDFSensorsGenerator();
# for the ft sensors, load the sensors as described in the YAML without further check
for ftSens in self.forceTorqueSensors:
referenceJoint = ftSens["jointName"];
frame = ftSens.get("frame");
frameName = ftSens.get("frameName");
if ('sensorName' not in ftSens.keys()):
sensorName = referenceJoint
else:
sensorName = ftSens["sensorName"];
sensorBlobs = ftSens.get("sensorBlobs");
if (frameName is None):
# If frame is not specified, the sensor frame is the link frame
offset = [0.0, 0.0, 0.0];
rot = quaternion_from_matrix(numpy.identity(4));
else:
# The default referenceLink is the sensorLink itself
sensorJoint = self.joints[referenceJoint];
for key in self.linkNameDisplayName2fid.keys():
# Since frameName is univoque in the map
if (frameName in key):
referenceLink = key[0];
# Get user added frame
sensor_frame_fid = self.linkNameDisplayName2fid[(referenceLink, frameName)];
(offset, rot) = self.tfman.get("X" + referenceLink, sensor_frame_fid)
pose = toGazeboPose(offset, rot);
# Add sensor in Gazebo format
ft_gazebo_el = generatorGazeboSensors.getURDFForceTorque(referenceJoint, sensorName,
ftSens["directionChildToParent"],
sensorBlobs, frame, pose)
self.urdf_xml.append(ft_gazebo_el);
urdf_origin_el = toURDFOriginXMLElement(offset, rot);
# Add sensor in URDF format
ft_sensor_el = generatorURDFSensors.getURDFForceTorque(referenceJoint, sensorName,
ftSens["directionChildToParent"], frame, urdf_origin_el);
self.urdf_xml.append(ft_sensor_el);
# for the other sensors, we rely on pose given by a USERADDED frame
for sensor in self.sensors:
sensorLink = sensor["linkName"];
frameName = sensor.get("frameName");
referenceLink = sensor.get("frameReferenceLink");
sensorName = sensor.get("sensorName");
sensorType = sensor.get("sensorType");
updateRate = sensor.get("updateRate");
sensorBlobs = sensor.get("sensorBlobs");
self.isValidSensor(sensorType);
if (frameName is None):
# If frame is not specified, the sensor frame is the link frame
offset = [0.0, 0.0, 0.0];
rot = quaternion_from_matrix(numpy.identity(4));
else:
# The default referenceLink is the sensorLink itself
if (referenceLink is None):
referenceLink = sensorLink;
# Get user added frame
sensor_frame_fid = self.linkNameDisplayName2fid[(referenceLink, frameName)];
(offset, rot) = self.tfman.get("X" + sensorLink, sensor_frame_fid)
if (sensorName is None):
sensorName = sensorLink + "_" + frameName;
# Add sensors in Gazebo format
pose = toGazeboPose(offset, rot);
# sys.stderr.write("Processing link " + link['uid'] + "\n")
gazeboSensorType = self.sensorTypeUrdf2sdf.get(sensorType, sensorType);
gazebo_sensor_el = generatorGazeboSensors.getURDFSensor(sensorLink, gazeboSensorType, sensorName, pose,
updateRate, sensorBlobs)
self.urdf_xml.append(gazebo_sensor_el);
urdf_origin_el = toURDFOriginXMLElement(offset, rot);
# Add sensor in URDF format
sensor_el = generatorURDFSensors.getURDFSensor(sensorLink, sensorType, sensorName, urdf_origin_el)
self.urdf_xml.append(sensor_el);
def addOrigin(self):
# Convert the origin element to Gazebo format (pose tag)
gazebo_origin_el = lxml.etree.Element("gazebo", None);
pose = lxml.etree.SubElement(gazebo_origin_el,"pose");
pose.text = toGazeboPoseFromEuler(self.originXYZ, self.originRPY);
# Add it to the URDF
self.urdf_xml.append(gazebo_origin_el);
def addElementToExportedFramesMap(self, key, elem):
# If the key is not in the map, we just add it
if key not in self.exportedFramesMap.keys():
self.exportedFramesMap[key] = {}
# We copy all keys, except for exportedFrameName,
# as in general we instead keep a vector attribute called
# exportedFrameNames to support exporting the same useradded frames
# multiple times with different names
for k in elem.keys():
if k != "exportedFrameName":
self.exportedFramesMap[key][k] = elem[k]
else:
self.exportedFramesMap[key]["exportedFrameNames"] = []
self.exportedFramesMap[key]["exportedFrameNames"].append(elem["exportedFrameName"])
else:
# if the key is already in the map, we just append the exportedFrameName to exportedFrameNames
self.exportedFramesMap[key]["exportedFrameNames"].append(elem["exportedFrameName"])
def parseYAMLConfig(self, configFile):
"""Parse the YAML configuration File, if it exists.
Set the fields the default if the config does
not set them """
if configFile == None:
configuration = {}
else:
configuration = yaml.load(open(configFile, 'r'))
if configuration == None:
configuration = {}
self.freezeList = []
self.redefinedjoints = {}
self.assignedCollisionGeometry = {}
self.root = configuration.get('root', None)
self.extrajoints = configuration.get('extrajoints', {})
self.extraframes = []
self.filenameformat = configuration.get('filenameformat', None)
self.filenameformatchangeext = configuration.get('filenameformatchangeext', None)
if (self.filenameformat is None and self.filenameformatchangeext is None):
# if neither filenameformat nor filenameformatchangeext is defined, use the default
self.filenameformat = '%s'
if (self.filenameformat is not None and self.filenameformatchangeext is not None):
#
print("Error: both filenameformat and filenameformatchangeext are defined")
assert (False)
self.name = configuration.get('robotName', None)
self.originXYZ = configuration.get('originXYZ', [0.0,0.0,0.0])
self.originRPY = configuration.get('originRPY', [0.0,0.0,0.0])
epsilon = configuration.get('epsilon', None)
if (epsilon is not None):
global _EPS
_EPS = float(epsilon)
self.forcelowercase = configuration.get('forcelowercase', True)
self.stringToRemoveFromMeshFileName = configuration.get('stringToRemoveFromMeshFileName', False)
## Frames related options
# If the exportAllUserAdded frame is setted, export all USERADDED frames
self.exportAllUseradded = configuration.get('exportAllUseradded', False)
# Load the linkFrames
self.linkFrames = configuration.get('linkFrames', [])
self.linkFramesMap = {}
for link_frame in self.linkFrames:
# add default frameReferenceLink if not included
if (link_frame.get("frameReferenceLink") is None):
link_frame["frameReferenceLink"] = link_frame["linkName"];
self.linkFramesMap[link_frame["linkName"]] = link_frame;
# Get a list of sensors
self.forceTorqueSensors = configuration.get('forceTorqueSensors', {});
self.sensors = configuration.get('sensors', {});
# Load the exported frames
exportedFrames = configuration.get('exportedFrames', [])
self.exportedFramesMap = {}
for exported_frame in exportedFrames:
if (exported_frame.get("frameReferenceLink") is not None):
self.addElementToExportedFramesMap((exported_frame["frameReferenceLink"], exported_frame["frameName"]), exported_frame)
else:
# if the frameReferenceLink is missing, just add the export_frame dict using only the frameName as key:
# we will add the full tutple (frameReferenceLink,frameName) later
self.addElementToExportedFramesMap(exported_frame["frameName"], exported_frame)
# Augment the exported frames with sensors for which the exportFrameInURDF option is enabled
for ftSens in self.forceTorqueSensors:
if( (ftSens.get("exportFrameInURDF") is not None) and ftSens["exportFrameInURDF"] ):
if ((ftSens.get("frameName") is None) or (ftSens.get("linkName") is None)):
print("Error: missing frameName or linkName")
assert (False)
exported_frame = {}
exported_frame["frameName"] = ftSens["frameName"]
if (ftSens.get("exportedFrameName") is not None):
exported_frame["exportedFrameName"] = ftSens["exportedFrameName"];
elif(ftSens.get("sensorName") is not None):
exported_frame["exportedFrameName"] = ftSens["sensorName"];
else:
exported_frame["exportedFrameName"] = ftSens["jointName"];
if (ftSens.get("frameReferenceLink") is not None):
exported_frame["frameReferenceLink"] = ftSens["frameReferenceLink"];
else:
exported_frame["frameReferenceLink"] = ftSens["linkName"];
map_key = (exported_frame["frameReferenceLink"], exported_frame["frameName"]);
# If the frame has been exported with a transformation, add it to the exported frame on sensor side
if (map_key in self.exportedFramesMap.keys() and ("additionalTransformation" in self.exportedFramesMap[map_key].keys())):
existing_exported_frame = self.exportedFramesMap[map_key];
exported_frame["additionalTransformation"] = existing_exported_frame["additionalTransformation"];
self.addElementToExportedFramesMap((exported_frame["frameReferenceLink"], exported_frame["frameName"]), exported_frame)
# Get default parameters in "sensors" list
# As we build the list of default sensors, we track the
# respective references to remove from self.sensors
sensorsToRemove = [];
for sensor in self.sensors:
if (sensor.get("sensorName") == 'default'):
# for caution, void frame names
sensor["frameName"] = None;
sensor["exportedFrameName"] = None;
# copy parameters
self.sensorsDefaultMap[sensor.get("sensorType")] = sensor.copy();
sensorsToRemove.append(sensor);
# Remove default sensor parameters objects from sensors list
for sensor in sensorsToRemove:
self.sensors.remove(sensor);
# Go again through the "sensors" list and replace unset values by the default ones
for sensor in self.sensors:
defaultSensor = self.sensorsDefaultMap.get(sensor.get("sensorType"));
if (defaultSensor is not None):
mergedSensor = defaultSensor.copy();
mergedSensor.update(sensor);
sensor.update(mergedSensor);
for sensor in self.sensors:
if (sensor["exportFrameInURDF"]):
exported_frame = {}
exported_frame["frameName"] = sensor["frameName"]
if (sensor.get("exportedFrameName") is not None):
exported_frame["exportedFrameName"] = sensor["exportedFrameName"];
else:
exported_frame["exportedFrameName"] = sensor["sensorName"];
if (sensor.get("frameReferenceLink") is not None):
exported_frame["frameReferenceLink"] = sensor["frameReferenceLink"];
else:
exported_frame["frameReferenceLink"] = sensor["linkName"];
map_key = (exported_frame["frameReferenceLink"], exported_frame["frameName"]);
# If the frame has been exported with a transformation, add it to the exported frame on sensor side
if (map_key in self.exportedFramesMap.keys() and ("additionalTransformation" in self.exportedFramesMap[map_key].keys())):
existing_exported_frame = self.exportedFramesMap[map_key];
exported_frame["additionalTransformation"] = existing_exported_frame["additionalTransformation"];
self.addElementToExportedFramesMap((exported_frame["frameReferenceLink"], exported_frame["frameName"]), exported_frame)
# Load scales options
scale_str = configuration.get('scale', None)
if (scale_str is not None):
self.scale = [float(scale_el) for scale_el in scale_str.split()]
else:
self.scale = None
self.freezeAll = configuration.get('freezeAll', False)
self.baseframe = configuration.get('baseframe', WORLD)
self.damping_fallback = configuration.get('damping', 0.1)
self.friction_fallback = configuration.get('friction', None)
self.effort_limit_fallback = configuration.get('effort_limit', 50000)
self.velocity_limit_fallback = configuration.get('velocity_limit', 50000)
self.rename = configuration.get('rename', {})
# Get map of links for which we explicitly assign the mass
self.assignedMasses = configuration.get('assignedMasses', {})
self.assignedColors = configuration.get('assignedColors', {})
# Get map of links for which we explicitly assign the mass
self.assignedInertiasMap = {}
assignedInertiasVector = configuration.get('assignedInertias', {})
for el in assignedInertiasVector:
link = el["linkName"]
self.assignedInertiasMap[link] = el;
# Get map of links for which we explicitly assign the collision geometry
assignedCollisionGeometryVector = configuration.get('assignedCollisionGeometry', {})
for el in assignedCollisionGeometryVector:
link = el["linkName"]
self.assignedCollisionGeometry[link] = el;
# Get lists converted to strings
self.removeList = configuration.get('remove', {})
self.freezeList = [str(e) for e in configuration.get('freeze', [])]
# Get map with key converted to strings
jointmap = configuration.get('redefinedjoints', {})
for x in jointmap.keys():
self.redefinedjoints[str(x)] = jointmap[x]
# Add Extra Frames
for frame in configuration.get('moreframes', []):
self.tfman.add(frame['offset'], frame['orientation'], frame['parent'], frame['child'])
# SimMechanics bug inertia workaround
mirroredInertia = configuration.get('mirroredInertia', [])
self.mirroredInertiaMap = {}
for mirrored_link_dict in mirroredInertia:
mirroredLink = mirrored_link_dict["mirroredLink"]
self.mirroredInertiaMap[mirroredLink] = mirrored_link_dict;
self.inertiaWorkaround = configuration.get('inertiaWorkaround', None);
if (self.inertiaWorkaround is not None):
self.mirroredLinks = self.inertiaWorkaround["mirroredLinks"].split()
else:
self.mirroredLinks = None;
# Get a list of joints for which we want to invert the rotation axis direction
self.reverseRotationAxis = configuration.get('reverseRotationAxis', []);
# Get a list of blob of XML tags to add to the URDF
self.XMLBlobs = configuration.get("XMLBlobs", [])
def parseJointCSVConfig(self, configFile):
"""Parse the CSV configuration File, if it exists."""
self.joint_configuration = {}
if configFile is not None:
with open(configFile, 'r') as csvfile:
my_dialect = csv.Sniffer().sniff(csvfile.read(1024))
csvfile.seek(0)
reader = csv.DictReader(csvfile, dialect=my_dialect)
for row in reader:
self.joint_configuration[row["joint_name"]] = row
def parse(self, element):
"""Recursively goes through all XML elements
and branches off for important elements"""
name = element.localName
# Grab name from root element AND recursively parse
if name == "PhysicalModelingXMLFile":
dict = getDictionary(element)
if (self.name is None):
self.name = dict['name']
if name == "Body":
self.parseLink(element)
elif name == "SimpleJoint":
self.parseJoint(element)
elif name == "Ground":
dict = getDictionary(element)
self.parseFrames(dict['frame'], "GROUND")
else:
for child in element.childNodes:
self.parse(child)
def parseLink(self, link):
"""Parse the important bits of a link element"""
linkdict = getDictionary(link)
uid = self.getName(linkdict['name'])
linkdict['uid'] = uid;
linkdict['neighbors'] = []
linkdict['children'] = []
linkdict['jointmap'] = {}
# Save the frames for separate parsing
frames = linkdict['frames']
linkdict['frames'] = None
# Save the color if it exists
if 'MaterialProp' in linkdict:
# color
colorelement = linkdict['MaterialProp'][1]
color = colorelement.childNodes[0].data
# ambient
ambientelement = linkdict['MaterialProp'][3]
ambient = ambientelement.childNodes[0].data
linkdict['ambient'] = float(ambient);
# diffuse
diffuseelement = linkdict['MaterialProp'][5]
diffuse = diffuseelement.childNodes[0].data
linkdict['diffuse'] = float(diffuse);
# specular
specularelement = linkdict['MaterialProp'][7]
specular = specularelement.childNodes[0].data
linkdict['specular'] = float(specular);
# transparency
transparencyelement = linkdict['MaterialProp'][11]
transparency = transparencyelement.childNodes[0].data
linkdict['color'] = list(map(float, color.split(","))) + [1.0 - float(transparency)]
linkdict['MaterialProp'] = None
self.links[uid] = linkdict
self.parseFrames(frames, uid)
# Save First Actual Element as Root, if not defined already
if self.root == None and "geometryFileName" in linkdict:
self.root = uid
def parseFrames(self, frames, parent_link):
"""Parse the frames from xml"""
for frame in frames:
if frame.nodeType is frame.TEXT_NODE:
continue
fdict = getDictionary(frame)
# We don't identify frames with ref attribute because USERADDED
# frames don't have ref attributes. We always use instead the
# urdf_link + name scheme (note that for added frames simmechanics link
# is different from urdf_link
fid = parent_link + fdict['name']
# for using the ref numbers of the frame we build a map from the ref numbers
# to the names
# fid = str(frame.getAttribute("ref"))
ref = str(frame.getAttribute("ref"))
self.ref2nameMap[ref] = fid;
fdict['parent'] = parent_link
offset = getlist(fdict['position'])
# for models mirrored in Creo there is a strange bug
# in SimMechanics Link that causes the inertia of the
# mirrored links to be wrongly placed. We add here
# some specific workaround for those link, if this
# is requested in the YAML file
if (self.mirroredLinks is not None):
if (fdict['name'] == 'CG' and parent_link in self.mirroredLinks):
offset[2] = -offset[2];
units = fdict['positionUnits']
for i in range(0, len(offset)):
offset[i] = convert(offset[i], units)
orientation = getlist(fdict['orientation'])
quat = matrixToQuaternion(orientation)
# If the frame does not have a reference number,
# use the name plus a suffix (for CG or CS1...
# If the frame does not have a reference number,
# but it is a USERADDED frame (frame added on the CAD
# for export in simmechanics) and the exportAllUserAdded
# option is set to True, export the frame using the displayName tag
# otherwise ignore the frame
if fdict['nodeID'].endswith('(USERADDED)'):
useradded_frame_name = fdict['displayName']
# clean all possible exportedFrames that were missing the frameReferenceLink option
if useradded_frame_name in self.exportedFramesMap.keys():
buf_export_frame = self.exportedFramesMap[useradded_frame_name]
buf_export_frame["frameRefenceLink"] = parent_link;
self.exportedFramesMap[(parent_link, useradded_frame_name)] = buf_export_frame;
# Frame is added if exportAllUseradded is setted or
# if frame is part of exportedFrames structure
if self.exportAllUseradded or () or (
(parent_link, useradded_frame_name) in self.exportedFramesMap.keys()):
map_key = (parent_link, useradded_frame_name);
if (map_key in self.exportedFramesMap.keys()):
if ("additionalTransformation" in self.exportedFramesMap[map_key].keys()):
addTransform = self.exportedFramesMap[map_key]["additionalTransformation"];
if (addTransform is not None):
assert(len(addTransform) is 6)
sensorOriginal_R_sensorModifed = euler_matrix(addTransform[3], addTransform[4], addTransform[5])
link_R_sensorOriginal = quaternion_matrix(quat)
offset = numpy.add(offset, numpy.matmul(link_R_sensorOriginal[0:3,0:3], addTransform[0:3]))
quat = quaternion_from_matrix(numpy.matmul(link_R_sensorOriginal, sensorOriginal_R_sensorModifed))
if ("exportedFrameNames" not in self.exportedFramesMap[map_key].keys()):
fid = useradded_frame_name + "CS1"
extraframe = {'parentlink': parent_link, 'framename': useradded_frame_name}
self.extraframes = self.extraframes + [extraframe]
# add link to self.links structure
linkdict = {}
linkdict['name'] = useradded_frame_name
fdict['parent'] = useradded_frame_name
linkdict['neighbors'] = []
linkdict['children'] = []
linkdict['jointmap'] = {}
linkdict['frames'] = None
linkdict['uid'] = linkdict['name']
self.links[useradded_frame_name] = linkdict
# Storing the displayName to the fid of the frame, to retrive the USERADDED frame when assigning link frames
self.linkNameDisplayName2fid[(parent_link, fdict['displayName'])] = fid
self.tfman.add(offset, quat, WORLD, fid)
self.frames[fid] = fdict
else:
for exported_frame in self.exportedFramesMap[map_key]["exportedFrameNames"]:
new_fdict = fdict.copy()
fid = exported_frame + "CS1"
extraframe = {'parentlink': parent_link, 'framename': exported_frame}
self.extraframes = self.extraframes + [extraframe]
# add link to self.links structure
linkdict = {}
linkdict['name'] = exported_frame
new_fdict['parent'] = exported_frame
linkdict['neighbors'] = []
linkdict['children'] = []
linkdict['jointmap'] = {}
linkdict['frames'] = None
linkdict['uid'] = linkdict['name']
self.links[exported_frame] = linkdict
self.linkNameDisplayName2fid[(parent_link, fdict['displayName'])] = fid
self.tfman.add(offset, quat, WORLD, fid)
self.frames[fid] = new_fdict
else:
self.linkNameDisplayName2fid[(parent_link, fdict['displayName'])] = fid
self.tfman.add(offset, quat, WORLD, fid)
self.frames[fid] = fdict
else:
self.tfman.add(offset, quat, WORLD, fid)
self.frames[fid] = fdict
def parseJoint(self, element):
"""Parse the joint from xml"""
dict = getDictionary(element)
joint = {}
joint['name'] = dict['name']
uid = self.getName(joint['name'])
frames = element.getElementsByTagName("Frame")
ref_parent = str(frames[0].getAttribute("ref"))
ref_child = str(frames[1].getAttribute("ref"))
joint['ref_parent'] = ref_parent
joint['ref_child'] = ref_child
type = element.getElementsByTagName("Primitive")
# If there multiple elements, assume a fixed joint
# \todo TODO fix and remove this assumption
if len(type) == 1:
pdict = getDictionary(type[0])
joint['type'] = pdict['name']
joint['axis'] = pdict['axis']
joint['axisReferenceFrame'] = pdict['referenceFrame']
if joint['type'] == 'weld':
joint['type'] = 'fixed'
else:
joint['type'] = 'fixed'
# Ignore joints on the remove list
# print("Parsing joint " + joint['name'])
# print("Removelist: ")
# print(self.removeList)
if (uid in self.removeList) or (joint['name'] in self.removeList):
# print(joint['name']+" is in removelist")
return
# Force joints to be fixed on the freezeList
if (uid in self.freezeList) or (joint['name'] in self.freezeList) or self.freezeAll:
joint['type'] = 'fixed'
# Redefine specified joints on redefined list
if joint['ref_parent'] in self.redefinedjoints.keys():
jdict = self.redefinedjoints[joint['ref_parent']]
if 'name' in jdict:
uid = jdict['name']
# Default to continuous joints
joint['type'] = jdict.get('type', 'continuous')
if 'axis' in jdict:
# print("axis" + str(jdict['axis']))
joint['axis'] = jdict['axis']
joint['axisReferenceFrame'] = jdict['referenceFrame']
if 'limits' in jdict:
joint['limits'] = jdict['limits']
# If some limits are defined in the CSV joint configuration file load them
# if the joint is revolute but no limits are defined, switch to continuous
if 'limits' not in joint.keys() and joint['type'] == "revolute":
joint['type'] = "continuous";
self.joints[uid] = joint
def buildTree(self, root):
"""Reduce the graph structure of links and joints to a tree
by breadth first search. Then construct new coordinate frames
from new tree structure"""
# resolve the undefined reference for all the joints
for jid in self.joints:
jointdict = self.joints[jid]
if ('parent' not in jointdict.keys()):
jointdict['parent'] = self.ref2nameMap[jointdict['ref_parent']]
if ('child' not in jointdict.keys()):
jointdict['child'] = self.ref2nameMap[jointdict['ref_child']]
# Find the real rootLink
if (jointdict['parent'].startswith('RootPart') and jointdict['type'] == 'fixed'):
if (self.realRootLink is not None):
pass
# print("[WARN] multiple links attached to the RootPart, please open an issue with your model")
# print(" at https://github.com/robotology-playground/simmechanics-to-urdf/issues/new")
else:
self.realRootLink = self.getLinkNameByFrame(jointdict['child'])
# Some postprocessing that was not possible to do while parsing
for extraframe in self.extraframes:
pid = extraframe['parentlink']
# Some USERADDED frames could be attached to the dummy root RootPart
# In this case substitute the dummy root with the real first link
# attached to the RootPart with a fixed link
if pid == 'RootPart':
extraframe['parentlink'] = self.realRootLink
# notice that we can disregard the original parent frame
# of the joint because it is a fixed joint
# Add necessary information for any frame in the SimMechanics XML
# file that we want to save to URDF. Given that URDF does not
# have a frame concept at all, we are bound to create "dummy"
# links and joints to express the notion of frames
for extraframe in self.extraframes:
pid = extraframe['parentlink']
cid = extraframe['framename']
joint_name = cid + "_fixed_joint";
self.links[pid]['neighbors'].append(cid)
self.links[pid]['jointmap'][cid] = joint_name
self.links[cid]['neighbors'].append(pid)
self.links[cid]['jointmap'][pid] = joint_name
self.joints[joint_name] = {'name': joint_name, 'parent': pid + 'CS1', 'child': cid + 'CS1', 'type': 'fixed'}
# for (k,v) in extraframe['attributes'].items():
# self.links[cid][k] = v
# Create a list of all neighboring links at each link
for jid in self.joints:
jointdict = self.joints[jid]
if "Root" in jointdict['name']:
continue
pid = self.getLinkNameByFrame(jointdict['parent'])
cid = self.getLinkNameByFrame(jointdict['child'])
parent = self.links[pid]
child = self.links[cid]
parent['neighbors'].append(cid)
parent['jointmap'][cid] = jid
child['neighbors'].append(pid)
child['jointmap'][pid] = jid
# import pprint
# pp = pprint.PrettyPrinter(indent=4)
# pp.pprint(self.joints)
# Add necessary information for any user-defined joints
for (name, extrajoint) in self.extrajoints.items():
pid = extrajoint['pid']
cid = extrajoint['cid']
jorigin = extrajoint['jorigin']
newframe = name + "_frame"
self.links[pid]['neighbors'].append(cid)
self.links[pid]['jointmap'][cid] = name
self.links[cid]['neighbors'].append(pid)
self.links[cid]['jointmap'][pid] = name
self.joints[name] = {'name': name, 'parent': jorigin, 'child': newframe}
for (k, v) in extrajoint['attributes'].items():
self.joints[name][k] = v
self.frames[jorigin] = {'parent': pid}
self.frames[newframe] = {'parent': cid}
# Starting with designated root node, perform BFS to
# create the tree
queue = [root]
self.links[root]['parent'] = "GROUND"
while len(queue) > 0:
id = queue.pop(0)
link = self.links[id]
for n in link['neighbors']:
nbor = self.links[n]
# if a neighbor has not been visited yet,
# add it as a child node
if not 'parent' in nbor:
nbor['parent'] = id
queue.append(n)
link['children'].append(n)
# build new link coordinate frames
# URDF has the unconvenient requirement that the link frame
# origin should be placed in the axis of the parent joint,
# so we have to place special care in
for id in self.links:
link = self.links[id]
if not 'parent' in link:
continue
parentid = link['parent']
jointIsNotFixed = True
if parentid == "GROUND":
ref = self.baseframe
else:
joint = self.joints[link['jointmap'][parentid]]
ref = joint['parent']
if (joint['type'] == 'fixed'):
jointIsNotFixed = False
# If a frame is not fixed, then the default link frame
# has the orientation of the link "CS1" frame and the origin
# of the joint.
# However using the linkFrames options is possible to use an
# USERADDED frame as the linkFrame. Given that the URDF enforces
# the link frame origin to lay on the axis of parent joint, the USERADDED
# frame is used unmodified only if its origin lays on joint axis.
# If the USERADDED frame origin doesn't lay on the joint axis, an exception is thrown.
if (jointIsNotFixed and not (parentid == "GROUND")):
if (self.linkFramesMap.get(link['uid']) is None):
# no frame redefinition
(off1, rot1) = self.tfman.get(WORLD, ref)
(off2, rot2) = self.tfman.get(WORLD, id + "CS1")
self.tfman.add(off1, rot2, WORLD, "X" + id)
else:
# using a useradded frame
new_link_frame_fid = self.linkNameDisplayName2fid[(
self.linkFramesMap[link['uid']]["frameReferenceLink"],
self.linkFramesMap[link['uid']]["frameName"])];
(new_link_frame_off, new_link_frame_rot) = self.tfman.get(WORLD, new_link_frame_fid)
(joint_offset, joint_rot) = self.tfman.get(WORLD, ref)
# get axis for the parent joint
jointdict = self.joints[link['jointmap'][parentid]]
jointdict_axis = jointdict['axis'];
axis_string = jointdict_axis.replace(',', ' ')
axis = [float(axis_el) for axis_el in axis_string.split()]
axis_np = numpy.array(axis)
joint_offset_np = numpy.array(joint_offset)
new_link_frame_off_np = numpy.array(new_link_frame_off);
axis_normalized = axis_np / numpy.linalg.norm(axis_np);