ggc_dae_to_urdf.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright (c) 2016, 2017, 2018 Kei Okada
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions are met:
8 #
9 # 1. Redistributions of source code must retain the above copyright notice,
10 # this list of conditions and the following disclaimer.
11 # 2. Redistributions in binary form must reproduce the above copyright
12 # notice, this list of conditions and the following disclaimer in the
13 # documentation and/or other materials provided with the distribution.
14 # 3. Neither the name of the Kei Okada nor the names of its
15 # contributors may be used to endorse or promote products derived from
16 # this software without specific prior written permission.
17 #
18 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28 # POSSIBILITY OF SUCH DAMAGE.
29 
30 from collada import * # Do not use "pip install pycollada". Use "apt install python-collada".
31 from urdf_parser_py.urdf import *
32 from tf.transformations import *
33 import copy
34 import os
35 import sys
36 import math
37 import numpy
38 import argparse
39 import trimesh # Use "pip install --user trimesh".
40 from simplify_collada import simplify_collada
41 from mergenode_collada import mergenode_collada
42 from scale_collada import scale_collada
43 from scipy.spatial.transform import Rotation # Do not use "apt install python-scipy". Use "pip install --user scipy==1.2.2".
44 # xmlutil.COLLADA_NS = 'http://www.collada.org/2008/03/COLLADASchema'
45 
46 depth_ = 0
47 scale_ = 0.1 # original file uses cm unit
48 density = 1.22e2
49 all_weight_ = 0.0
50 root_offset = numpy.array([[0, 0, 1, 0], [1, 0, 0, 0], [0, 1, 0, 0], [0, 0, 0, 1]], dtype=numpy.float32) # original file is Y_UP
51 
52 zero_pid = {'p': 0.0, 'i': 0.0, 'd': 0.0}
53 default_pid = {'p': 10000000.0, 'i': 500.0, 'd': 200000.0}
54 head_pid = {'p': 1000000.0, 'i': 500.0, 'd': 200000.0}
55 torso_pid = {'p': 20000000.0, 'i': 10000.0, 'd': 1000000.0}
56 elbow_p_pid = {'p': 20000000.0, 'i': 1000.0, 'd': 40000.0}
57 wrist_pid = {'p': 100000.0, 'i': 50.0, 'd': 20000.0}
58 gripper_pid = {'p': 100000.0, 'i': 100.0, 'd': 100.0}
59 finger_pid = {'p': 100000.000000, 'i': 100.000000, 'd': 100.000000}
60 crotch_p_pid = {'p': 400000000.0, 'i': 4000000.0, 'd': 500000.0}
61 crotch_r_pid = {'p': 200000000.0, 'i': 1000000.0, 'd': 500000.0}
62 crotch_y_pid = {'p': 200000000.0, 'i': 1000000.0, 'd': 500000.0}
63 knee_p_pid = {'p': 200000000.0, 'i': 1000000.0, 'd': 100000.0}
64 knee_p_mimic_pid = {'p': 200000000.0, 'i': 1000000.0, 'd': 100000.0}
65 ankle_pid = {'p': 100000000.0, 'i': 5000.0, 'd': 500000.0}
66 ankle_r_mimic_pid = {'p': 100000000.0, 'i': 1000000.0, 'd': 50000.0}
67 ankle_p_mimic_pid = {'p': 500000.0, 'i': 500.0, 'd': 50000.0}
68 cover_pid = {'p': 50000.0, 'i': 500.0, 'd': 5000.0}
69 thrust_pid = {'p': 10000000.0, 'i': 500.0, 'd': 20000.0}
70 
71 joints_ = [
72  # axis [pitch, roll, yaw]
73  # backpack
74  ['rx78_Null_013', {'joint_type': 'fixed'}],
75  ['rx78_Null_012', {'joint_type': 'fixed'}], # sword
76  ['rx78_Null_011', {'joint_type': 'fixed'}],
77  ['rx78_Null_010', {'joint_type': 'fixed'}],
78  ['rx78_Null_009', {'joint_type': 'fixed'}], # sword
79  ['rx78_Null_008', {'joint_type': 'fixed'}],
80  ['rx78_Null_007', {'joint_type': 'fixed'}],
81  ['rx78_Null_005', {'name': 'torso_rthrust_p', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 4, 'limit_upper': math.pi / 2, 'pid': thrust_pid}], # jet
82  ['rx78_Null_005', {'name': 'torso_rthrust_r', 'axis': [0, 1, 0], 'limit_lower': -math.pi / 4, 'limit_upper': math.pi / 4, 'pid': thrust_pid}],
83  ['rx78_Null_006', {'name': 'torso_lthrust_p', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 4, 'limit_upper': math.pi / 2, 'pid': thrust_pid}],
84  ['rx78_Null_006', {'name': 'torso_lthrust_r', 'axis': [0, 1, 0], 'limit_lower': -math.pi / 4, 'limit_upper': math.pi / 4, 'pid': thrust_pid}],
85  ['rx78_Null_082', {'joint_type': 'fixed'}], # skip torso parts, which is also has another joint
86  ['rx78_Null_083', {'joint_type': 'fixed'}], # torso?
87 
88  # torso
89  ['rx78_Null_018', {'name': 'torso_waist_y', 'axis': [0, 0, 1], 'limit_lower': -math.pi / 12, 'limit_upper': math.pi / 12, 'pid': torso_pid}],
90  ['rx78_Null_017', {'name': 'torso_waist_p', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 4, 'limit_upper': math.pi / 4, 'pid': torso_pid}],
91  ['rx78_Null_016', {'name': 'torso_waist_p2', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 4, 'limit_upper': math.pi / 4, 'axis': [1, 0, 0], 'pid': torso_pid}],
92 
93  # head
94  ['rx78_Null_015', {'name': 'head_neck_y', 'axis': [0, 0, 1], 'limit_lower': -math.pi / 2, 'limit_upper': math.pi / 2, 'pid': head_pid}],
95  ['rx78_Null_014', {'name': 'head_neck_p', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 5, 'limit_upper': math.pi / 4, 'pid': head_pid}],
96 
97  # larm
98  ['rx78_Null_004', {'name': 'larm_shoulder_p', 'axis': [1, 0, 0], 'limit_lower': -math.pi, 'limit_upper': math.pi / 2}],
99  ['rx78_Null_001', {'name': 'larm_shoulder_r', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 6, 'limit_upper': math.pi / 2}],
100  ['rx78_Null_002', {'name': 'larm_shoulder_y', 'axis': [0, 0, 1], 'limit_lower': -math.pi / 2, 'limit_upper': math.pi / 2}],
101  ['rx78_Null_003', {'name': 'larm_elbow_p', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 3, 'limit_upper': math.pi / 24, 'pid': elbow_p_pid}],
102  ['rx78_Null_066', {'name': 'larm_elbow_p2', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 3, 'limit_upper': math.pi / 24, 'pid': elbow_p_pid}],
103  ['rx78_Null_067', {'name': 'larm_wrist_y', 'axis': [0, 0, 1], 'limit_lower': -math.pi / 2, 'limit_upper': math.pi / 2, 'pid': wrist_pid}],
104  ['rx78_Null_069', {'name': 'larm_wrist_r', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 2, 'limit_upper': math.pi / 2, 'pid': wrist_pid}],
105  ['rx78_Null_048', {'joint_type': 'fixed'}], # shoulder-p cover
106  ['rx78_Null_065', {'joint_type': 'fixed'}], # elbow-p internal
107  # left hand
108  ['rx78_Null_059', {'name': 'larm_gripper_index0_mimic', 'axis': [0, 1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'larm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}], # index
109  ['rx78_Null_060', {'name': 'larm_gripper_index1_mimic', 'axis': [0, 1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'larm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
110  ['rx78_Null_061', {'name': 'larm_gripper_index2_mimic', 'axis': [0, 1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'larm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
111  ['rx78_Null_062', {'name': 'larm_gripper', 'axis': [0, 1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'pid': gripper_pid}], # thumb
112  ['rx78_Null_063', {'name': 'larm_gripper_thumb1_mimic', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 5, 'limit_upper': math.pi / 4,
113  'mimic': 'larm_gripper', 'mimic_multiplier': 1.0, 'mimic_offset': -math.pi / 4, 'pid': finger_pid}],
114  ['rx78_Null_064', {'name': 'larm_gripper_thumb2_mimic', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'larm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
115  ['rx78_Null_068', {'name': 'larm_gripper_middle0_mimic', 'axis': [0, 1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'larm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
116  ['rx78_Null_070', {'name': 'larm_gripper_middle1_mimic', 'axis': [0, 1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'larm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
117  ['rx78_Null_071', {'name': 'larm_gripper_middle2_mimic', 'axis': [0, 1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'larm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
118  ['rx78_Null_072', {'name': 'larm_gripper_ring0_mimic', 'axis': [0, 1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'larm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
119  ['rx78_Null_073', {'name': 'larm_gripper_ring1_mimic', 'axis': [0, 1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'larm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
120  ['rx78_Null_074', {'name': 'larm_gripper_ring2_mimic', 'axis': [0, 1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'larm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
121  ['rx78_Null_075', {'name': 'larm_gripper_little0_mimic', 'axis': [0, 1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'larm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
122  ['rx78_Null_076', {'name': 'larm_gripper_little1_mimic', 'axis': [0, 1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'larm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
123  ['rx78_Null_077', {'name': 'larm_gripper_little2_mimic', 'axis': [0, 1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'larm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
124 
125  # rarm
126  ['rx78_Null_049', {'name': 'rarm_shoulder_p', 'axis': [1, 0, 0], 'limit_lower': -math.pi, 'limit_upper': math.pi / 2}],
127  ['rx78_Null_050', {'name': 'rarm_shoulder_r', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 2, 'limit_upper': math.pi / 6}],
128  ['rx78_Null_051', {'name': 'rarm_shoulder_y', 'axis': [0, 0, 1], 'limit_lower': -math.pi / 2, 'limit_upper': math.pi / 2}],
129  ['rx78_Null_052', {'name': 'rarm_elbow_p', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 3, 'limit_upper': math.pi / 24, 'pid': elbow_p_pid}],
130  ['rx78_Null_053', {'name': 'rarm_elbow_p2', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 3, 'limit_upper': math.pi / 24, 'pid': elbow_p_pid}],
131  ['rx78_Null_054', {'name': 'rarm_wrist_y', 'axis': [0, 0, 1], 'limit_lower': -math.pi / 2, 'limit_upper': math.pi / 2, 'pid': wrist_pid}],
132  ['rx78_Null_055', {'name': 'rarm_wrist_r', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 2, 'limit_upper': math.pi / 2, 'pid': wrist_pid}],
133  ['rx78_Null_081', {'joint_type': 'fixed'}], # shoulder-p cover
134  # right hand
135  ['rx78_Null_021', {'name': 'rarm_gripper_middle0_mimic', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'rarm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
136  ['rx78_Null_022', {'name': 'rarm_gripper_middle1_mimic', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'rarm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
137  ['rx78_Null_023', {'name': 'rarm_gripper_middle2_mimic', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'rarm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
138  ['rx78_Null_024', {'name': 'rarm_gripper_index0_mimic', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'rarm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}], # index
139  ['rx78_Null_025', {'name': 'rarm_gripper_index1_mimic', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'rarm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
140  ['rx78_Null_026', {'name': 'rarm_gripper_index2_mimic', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'rarm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
141  ['rx78_Null_027', {'name': 'rarm_gripper_little0_mimic', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'rarm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
142  ['rx78_Null_028', {'name': 'rarm_gripper_little1_mimic', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'rarm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
143  ['rx78_Null_029', {'name': 'rarm_gripper_little2_mimic', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'rarm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
144  ['rx78_Null_056', {'name': 'rarm_gripper', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'pid': gripper_pid}], # thumb
145  ['rx78_Null_057', {'name': 'rarm_gripper_thumb1_mimic', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 5, 'limit_upper': math.pi / 4,
146  'mimic': 'rarm_gripper', 'mimic_multiplier': 1.0, 'mimic_offset': -math.pi / 4, 'pid': finger_pid}],
147  ['rx78_Null_058', {'name': 'rarm_gripper_thumb2_mimic', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'rarm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
148  ['rx78_Null_078', {'name': 'rarm_gripper_ring0_mimic', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'rarm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
149  ['rx78_Null_079', {'name': 'rarm_gripper_ring1_mimic', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'rarm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
150  ['rx78_Null_080', {'name': 'rarm_gripper_ring2_mimic', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 2, 'mimic': 'rarm_gripper', 'mimic_multiplier': 1.0, 'pid': finger_pid}],
151 
152  # lleg
153  ['rx78_Null_033', {'name': 'lleg_crotch_p_back_mimic', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 4, 'limit_upper': math.pi / 6,
154  'mimic': 'lleg_crotch_p', 'mimic_multiplier': 0.5, 'pid': cover_pid}], # back cover
155  ['rx78_Null_034', {'name': 'lleg_crotch_p_front_mimic', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 4, 'limit_upper': math.pi / 6,
156  'mimic': 'lleg_crotch_p', 'mimic_multiplier': 0.5, 'pid': cover_pid}], # front cover
157  ['rx78_Null_047', {'name': 'lleg_crotch_r_mimic', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 4 * 0.6, 'limit_upper': math.pi / 9 * 0.6,
158  'mimic': 'lleg_crotch_r', 'mimic_multiplier': -0.6, 'axis': [0, 1, 0], 'pid': cover_pid}], # side cover
159  ['rx78_Null_035', {'name': 'lleg_crotch_p', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 2, 'limit_upper': math.pi / 3, 'pid': crotch_p_pid}],
160  ['rx78_Null_035', {'name': 'lleg_crotch_r', 'joint_type': 'revolute', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 9, 'limit_upper': math.pi / 4, 'pid': crotch_r_pid}], # hack for crotch-r _035->_029->_036
161  ['rx78_Null_036', {'name': 'lleg_crotch_y', 'axis': [0, 0, 1], 'limit_lower': -math.pi / 4, 'limit_upper': math.pi / 4, 'pid': crotch_y_pid}],
162  ['rx78_Null_037', {'name': 'lleg_knee_p', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 3, 'pid': knee_p_pid}],
163  ['rx78_Null_038', {'name': 'lleg_knee_p2', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 3, 'pid': knee_p_mimic_pid}],
164  ['rx78_Null_039', {'name': 'lleg_ankle_p', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 3, 'limit_upper': math.pi / 3, 'pid': ankle_pid}],
165  ['rx78_Null_041', {'name': 'lleg_ankle_r', 'axis': [-1, 0, 0], 'limit_lower': -math.pi / 6, 'limit_upper': math.pi / 6, 'pid': ankle_pid}],
166 
167  ['rx78_Null_040', {'name': 'lleg_ankle_r_mimic', 'axis': [-1, 0, 0], 'limit_lower': -math.pi / 6, 'limit_upper': math.pi / 6,
168  'mimic': 'lleg_ankle_r', 'mimic_multiplier': 1.0, 'pid': ankle_r_mimic_pid}], # ankle back
169  ['rx78_Null_042', {'joint_type': 'fixed'}], # sole
170  ['rx78_Null_043', {'joint_type': 'fixed'}], # sole
171  ['rx78_Null_044', {'joint_type': 'fixed'}], # sole
172  ['rx78_Null_045', {'joint_type': 'fixed'}], # sole
173  ['rx78_Null_046', {'name': 'lleg_ankle_p_mimic', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 6, 'limit_upper': math.pi / 6,
174  'mimic': 'lleg_ankle_p', 'mimic_multiplier': -0.5, 'pid': ankle_p_mimic_pid}], # ankle cover
175 
176  # rleg
177  ['rx78_Null_084', {'name': 'rleg_crotch_p_front_mimic', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 4, 'limit_upper': math.pi / 6,
178  'mimic': 'rleg_crotch_p', 'mimic_multiplier': 0.5, 'pid': cover_pid}], # front cover
179  ['rx78_Null_031', {'name': 'rleg_crotch_p_back_mimic', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 4, 'limit_upper': math.pi / 6,
180  'mimic': 'rleg_crotch_p', 'mimic_multiplier': 0.5, 'pid': cover_pid}], # back cover
181  ['rx78_Null_032', {'name': 'rleg_crotch_r_mimic', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 4 * 0.6, 'limit_upper': math.pi / 9 * 0.6,
182  'mimic': 'rleg_crotch_r', 'mimic_multiplier': 0.6, 'pid': cover_pid}], # side cover
183  ['rx78_Null_085', {'name': 'rleg_crotch_p', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 2, 'limit_upper': math.pi / 3, 'pid': crotch_p_pid}],
184  ['rx78_Null_085', {'name': 'rleg_crotch_r', 'axis': [0, -1, 0], 'limit_lower': -math.pi / 4, 'limit_upper': math.pi / 9, 'pid': crotch_r_pid}], # hack for crotch-r _085->_086->_086
185  ['rx78_Null_086', {'name': 'rleg_crotch_y', 'axis': [0, 0, 1], 'limit_lower': -math.pi / 4, 'limit_upper': math.pi / 4, 'pid': crotch_y_pid}],
186  ['rx78_Null_087', {'name': 'rleg_knee_p', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 3, 'pid': knee_p_pid}],
187  ['rx78_Null_088', {'name': 'rleg_knee_p2', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 24, 'limit_upper': math.pi / 3, 'pid': knee_p_mimic_pid}],
188  ['rx78_Null_089', {'name': 'rleg_ankle_p', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 3, 'limit_upper': math.pi / 3, 'pid': ankle_pid}],
189  ['rx78_Null_091', {'name': 'rleg_ankle_r', 'axis': [-1, 0, 0], 'limit_lower': -math.pi / 6, 'limit_upper': math.pi / 6, 'pid': ankle_pid}],
190 
191  ['rx78_Null_090', {'name': 'rleg_ankle_r_mimic', 'axis': [-1, 0, 0], 'limit_lower': -math.pi / 6, 'limit_upper': math.pi / 6,
192  'mimic': 'rleg_ankle_r', 'mimic_multiplier': 1.0, 'pid': ankle_r_mimic_pid}], # ankle back
193  ['rx78_Null_092', {'joint_type': 'fixed'}], # sole
194  ['rx78_Null_093', {'joint_type': 'fixed'}], # sole
195  ['rx78_Null_094', {'joint_type': 'fixed'}], # sole
196  ['rx78_Null_095', {'joint_type': 'fixed'}], # sole
197  ['rx78_Null_030', {'name': 'rleg_ankle_p_mimic', 'axis': [1, 0, 0], 'limit_lower': -math.pi / 6, 'limit_upper': math.pi / 6,
198  'mimic': 'rleg_ankle_p', 'mimic_multiplier': -0.5, 'pid': ankle_p_mimic_pid}], # ankle cover
199 
200 ]
201 
202 
203 def get_bouding_box(geometries):
204  bbox_min = []
205  bbox_max = []
206  for g in geometries:
207  for p in g.primitives:
208  if p.vertex is not None:
209  for i in p.vertex_index:
210  bbox_min.append(numpy.amin(p.vertex[i], axis=0))
211  bbox_max.append(numpy.amax(p.vertex[i], axis=0))
212 
213  xyz = list((numpy.amax(numpy.array(bbox_max), axis=0) +
214  numpy.amin(numpy.array(bbox_min), axis=0)) / 2)
215  size = list(numpy.amax(numpy.array(bbox_max), axis=0) -
216  numpy.amin(numpy.array(bbox_min), axis=0))
217  return Collision(
218  origin=Pose(xyz=xyz),
219  geometry=Box(size=size))
220 
221 
222 def calc_inertia(collision, density=100.0):
223  global all_weight_
224  bbox_x = collision.geometry.size[0]
225  bbox_y = collision.geometry.size[1]
226  bbox_z = collision.geometry.size[2]
227  mass = density * bbox_x * bbox_y * bbox_z
228  # GGC hack, small mass reduce stability of simulation
229  if 0 < mass and mass < 50:
230  mass = 50
231  all_weight_ += mass
232  return Inertial(mass=mass,
233  origin=copy.deepcopy(collision.origin),
234  inertia=Inertia(
235  ixx=mass * (bbox_y * bbox_y + bbox_z * bbox_z) / 12.0,
236  iyy=mass * (bbox_z * bbox_z + bbox_x * bbox_x) / 12.0,
237  izz=mass * (bbox_x * bbox_x + bbox_y * bbox_y) / 12.0))
238 
239 
240 def get_volume(geometries, density):
241  global all_weight_
242  if len(geometries) > 0:
243  m = 0.0
244  c = numpy.array([0.0, 0.0, 0.0])
245  I = numpy.array([[0.0, 0.0, 0.0], [0.0, 0.0, 0.0], [0.0, 0.0, 0.0]])
246  for g in geometries:
247  for p in g.primitives:
248  _mesh = trimesh.Trimesh(vertices=p.vertex.astype("float64"), faces=p.vertex_index, face_normals=p.normal[p.normal_index].astype("float64"), validate=True).convex_hull
249  _m = _mesh.volume * density
250  _c = _mesh.center_mass
251  _I = _mesh.moment_inertia * density
252  m += _m
253  c += _m * _c
254  I += _I + _m * (numpy.inner(_c, _c) * numpy.identity(3) - numpy.outer(_c, _c))
255  if m > 0:
256  all_weight_ += m
257  c = c / m
258  I = I - m * (numpy.inner(c, c) * numpy.identity(3) - numpy.outer(c, c))
259  if m < 50: # GGC hack, small mass reduce stability of simulation
260  I *= 50 / m
261  m = 50
262  components, vectors = trimesh.inertia.principal_axis(I)
263  vectors[2] = numpy.cross(vectors[0], vectors[1])
264  rotate = Rotation.from_dcm(vectors.transpose()).as_euler('xyz', degrees=False)
265  return Inertial(mass=m,
266  origin=Pose(xyz=c, rpy=[rotate[0], rotate[1], rotate[2]]),
267  inertia=Inertia(
268  ixx=components[0],
269  iyy=components[1],
270  izz=components[2]))
271  else:
272  return None
273  else:
274  return None
275 
276 
277 def retrive_node(nodes, joints_dict, links_dict, parent=None):
278  global robot_, depth_
279  # if len(robot_.joints) > 8: return True ############################# FOR
280  # DEBUG
281  depth_ += 1
282  for node in nodes:
283  print(' ' * depth_), # write indent
284  try:
285  print('id .. {} {}'.format(node.id, type(node)))
286  except:
287  print('node .. {}'.format(node))
288  if isinstance(node, scene.Node):
289  if node.id:
290  if node.id[-5:] == '_link':
291  linkname = node.id
292  else:
293  linkname = node.id + '_link'
294  l = Link(name=linkname,
295  visual=None,
296  inertial=None,
297  collision=None,
298  origin=None)
299  # add link
300  robot_.add_link(l)
301  if parent:
302  if parent.id[-5:] == '_link':
303  parentname = parent.id
304  else:
305  parentname = parent.id + '_link'
306  j = Joint(name=node.id + '_joint',
307  parent=parentname,
308  child=l.name,
309  joint_type='fixed',
310  origin=Pose(
311  xyz=translation_from_matrix(node.matrix),
312  rpy=euler_from_matrix(node.matrix))
313  )
314  print(
315  '{} - {}'.format(' ' * depth_, [type(n) for n in node.children]))
316  # if not any(isinstance(n, scene.GeometryNode) for n in node.children):
317  # j.joint_type = 'revolute'
318  # # j.axis = numpy.array(parent.matrix)[:3, :3].dot([0,
319  # # 0, 1])
320  # j.axis = [0, 0, 1]
321  # if len(node.transforms) > 1:
322  # print(node.transforms[1:])
323  # if any(isinstance(n, scene.RotateTransform) for n in node.transforms):
324  # j.axis = [1, 0, 0]
325  # j.limit = JointLimit(
326  # lower=-math.pi / 2, upper=math.pi / 2, effort=1000000000, velocity=1000000)
327  #
328  if node.id in joints_dict:
329  j.joint_type = 'revolute'
330  j.axis = [0, 0, 1]
331  if len(node.transforms) > 1:
332  print(node.transforms[1:])
333  if any(isinstance(n, scene.RotateTransform) for n in node.transforms):
334  j.axis = [1, 0, 0]
335  j.limit = JointLimit(
336  lower=-math.pi / 2, upper=math.pi / 2, effort=1000000000, velocity=1000000)
337  j.dynamics = JointDynamics(
338  damping='3e2', friction='1e3')
339  if 'joint_type' in joints_dict[node.id]:
340  j.joint_type = joints_dict[node.id]['joint_type']
341  if j.joint_type == 'fixed':
342  j.limit = None
343  j.axis = None
344  j.dynamics = None
345  if 'name' in joints_dict[node.id]:
346  j.name = joints_dict[node.id]['name']
347  if 'axis' in joints_dict[node.id]:
348  j.axis = joints_dict[node.id]['axis']
349  if 'limit_lower' in joints_dict[node.id]:
350  j.limit.lower = joints_dict[node.id]['limit_lower']
351  if 'limit_upper' in joints_dict[node.id]:
352  j.limit.upper = joints_dict[node.id]['limit_upper']
353  if 'child' in joints_dict[node.id]:
354  j.child = joints_dict[node.id]['child'] + '_link'
355  if 'origin_xyz' in joints_dict[node.id]:
356  j.origin.xyz = joints_dict[node.id]['origin_xyz']
357  if 'origin_rpy' in joints_dict[node.id]:
358  j.origin.rpy = joints_dict[node.id]['origin_rpy']
359  if args.no_mimic and 'mimic' in joints_dict[node.id]:
360  # disable mimic
361  j.joint_type = 'fixed'
362  j.limit = None
363  j.axis = None
364  else:
365  if 'mimic' in joints_dict[node.id]:
366  j.mimic = JointMimic(
367  joint_name=joints_dict[node.id]['mimic'])
368  if 'mimic_multiplier' in joints_dict[node.id]:
369  j.mimic.multiplier = joints_dict[
370  node.id]['mimic_multiplier']
371  if 'mimic_offset' in joints_dict[node.id]:
372  j.mimic.offset = joints_dict[
373  node.id]['mimic_offset']
374  #
375  # add joint
376  robot_.add_joint(j)
377 
378  retrive_node(node.children, joints_dict, links_dict, node)
379  depth_ -= 1
380  elif isinstance(node, scene.GeometryNode):
381  # print('writing mesh file to meshes/{}.dae'.format(node.geometry.id))
382  # write mesh
383  c = Collada()
384  g = node.geometry
385  n = scene.Node(g.name + '-node', [node])
386  s = scene.Scene(g.name + '-scene', [])
387  # s.nodes.extend(parent.transforms) # ?? need this?
388  s.nodes.append(n)
389  cont = asset.Contributor(
390  author="Association GUNDAM GLOBAL CHALLENGE",
391  comments="This file is automatically generated by " +
392  (' '.join(sys.argv)).replace('--', '\-\-') + ' '
393  "and distributed under the TERMS OF USE FOR GUNDAM RESEARCH OPEN SIMULATOR Attribution-NonCommercial-ShareAlike",
394  copyright="SOTSU, SUNRISE / GUNDAM GLOBAL CHALLENGE",
395  )
396  c.assetInfo.contributors.append(cont)
397  c.geometries.append(g)
398  c.materials = [m.target for m in node.materials]
399  c.effects = [m.target.effect for m in node.materials]
400  c.scenes.append(s)
401  c.scene = s
402  if args.write_mesh:
403  c.write('meshes/{}.dae'.format(g.id))
404  #
405  # update urdf
406  l = [l for l in robot_.links if l.name == parent.id + '_link'][0]
407  l.visuals.append(Visual(
408  geometry=Mesh(
409  filename='package://gundam_rx78_description/meshes/{}.dae'.format(
410  g.id))))
411  # get bounding box of scene
412  l.collisions.append(Collision(
413  geometry=Mesh(
414  filename='package://gundam_rx78_description/meshes/{}.dae'.format(
415  g.id))))
416  if l.name in link_dict:
417  link_dict[l.name].append(g)
418  else:
419  link_dict[l.name] = [g]
420  l.inertial = None
421  elif isinstance(node, scene.ExtraNode):
422  pass
423  else:
424  print('skipping {}'.format(node))
425 
426 
427 def add_gazebo_nodes(robot, link_dict):
428  for j in robot.joints:
429  if j.joint_type != "revolute":
430  continue
431 
432  # actuated joint
433  if not args.no_mimic or j.mimic is None:
434  # add extra info for actuated joints
435  g = etree.Element('gazebo', reference=j.name)
436  etree.SubElement(g, 'provideFeedback').text = '1'
437  etree.SubElement(g, 'implicitSpringDamper').text = '0'
438  robot.add_aggregate('gazebo', g)
439  # add transmission
440  trans = Transmission()
441  trans.name = j.name + '_trans'
442  joi = TransmissionJoint(j.name)
443  if args.controller_type == 'position':
444  joi.add_aggregate(
445  'hardwareInterface', 'hardware_interface/PositionJointInterface')
446  if args.controller_type == 'velocity':
447  joi.add_aggregate(
448  'hardwareInterface', 'hardware_interface/VelocityJointInterface')
449  if args.controller_type == 'effort':
450  joi.add_aggregate(
451  'hardwareInterface', 'hardware_interface/EffortJointInterface')
452  act = Actuator(j.name + '_motor')
453  act.mechanicalReduction = 1.0
454  trans.add_aggregate('joint', joi)
455  trans.add_aggregate('actuator', act)
456  trans.type = "transmission_interface/SimpleTransmission"
457  robot.add_aggregate('transmission', trans)
458 
459  for l in robot.links:
460  g = etree.Element('gazebo', reference=l.name)
461  etree.SubElement(g, 'selfCollide').text = 'false'
462  # etree.SubElement(g, 'mu1').text = '0.2'
463  # etree.SubElement(g, 'mu2').text = '0.2'
464  etree.SubElement(g, 'mu1').text = '1.5'
465  etree.SubElement(g, 'mu2').text = '1.5'
466  etree.SubElement(g, 'mu2').text = '9000'
467  etree.SubElement(g, 'kp').text = '140000000.0'
468  etree.SubElement(g, 'kd').text = '280000.0'
469  etree.SubElement(g, 'fdir1').text = '1 0 0'
470  etree.SubElement(g, 'maxVel').text = '10.0'
471  robot.add_aggregate('gazebo', g)
472 
473  # calculate mass property
474  if l.name != "base_link":
475  if "addition_null" in l.name: # avoid null link ** GGC HACK
476  l.collision = Collision(origin=Pose(xyz=[0, 0, 0]), geometry=Box(size=[0.8, 0.8, 0.8]))
477  l.inertial = calc_inertia(l.collision, 400)
478  else:
479  if l.inertial is None:
480  if l.name in link_dict:
481  l.inertial = get_volume(link_dict[l.name], density)
482 
483  # for urdfdom_py = 0.4.0
484  # Once https://github.com/ros/urdf_parser_py/pull/47 is merged, we can remove this block
485  from rospkg import RosPack
486  if RosPack().get_manifest('urdfdom_py').version == '0.4.0':
487  for l in robot.links:
488  if l.visual:
489  l.add_aggregate('visual', l.visual)
490  if l.collision:
491  l.add_aggregate('collision', l.collision)
492 
493  robot.add_aggregate('gazebo', etree.fromstring('<gazebo>'
494  '<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">'
495  '<robotNamespace>/</robotNamespace>'
496  '<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>'
497  '<legacyModeNS>true</legacyModeNS>'
498  '</plugin>'
499  '<plugin name="ground_truth" filename="libgazebo_ros_p3d.so">'
500  '<frameName>world</frameName>'
501  '<bodyName>base_link</bodyName>'
502  '<topicName>base_link_ground_truth</topicName>'
503  '<updateRate>30.0</updateRate>'
504  '</plugin>'
505  '</gazebo>'))
506 
507 
508 # write urdf file
509 def write_urdf_file(name, robot):
510  f = open('urdf/{}.urdf'.format(name), 'w')
511  print("writing urdf file to %s" % f.name)
512  f.write(
513  '<?xml version="1.0" ?>\n'
514  '<!--\n'
515  ' This file is automatically generated by ' + (' '.join(sys.argv)).replace('--', '\-\-') + '\n'
516  ' and distributed under the TERMS OF USE FOR GUNDAM RESEARCH OPEN SIMULATOR Attribution-NonCommercial-ShareAlike\n'
517  ' Copyright: SOTSU, SUNRISE / GUNDAM GLOBAL CHALLENGE\n'
518  '-->\n')
519  f.write(robot.to_xml_string().split("\n", 1)[1]) # skip <?xml version="1.0" ?>
520  f.close()
521 
522 
523 # write ros_control configuration file
524 def write_control_file(joints_dict):
525  # write control file
526  f = open('../gundam_rx78_control/config/gundam_rx78_control.yaml', 'w')
527  print("Writing ros_control config file to %s" % f.name)
528  f.write('# Publish all joint states -----------------------------------\n'
529  'joint_state_controller:\n'
530  ' type: joint_state_controller/JointStateController\n'
531  ' publish_rate: 50\n'
532  '\n')
533  f.write('# Position Controllers ---------------------------------------\n')
534  for i, j in joints_dict.items():
535  if ('name' in j) and (not ('mimic' in j)):
536  f.write('%s_position:\n' % j['name'])
537  f.write(' type: %s_controllers/JointPositionController\n' %
538  args.controller_type)
539  f.write(' joint: %s\n' % j['name'])
540  if 'pid' in j:
541  f.write(' pid: {p: %f, i: %f, d: %f}\n' % (j['pid']['p'], j['pid']['i'], j['pid']['d']))
542  else:
543  f.write(' pid: {p: %f, i: %f, d: %f}\n' % (default_pid['p'], default_pid['i'], default_pid['d']))
544  # for mimic joints
545  if not args.no_mimic:
546  has_mimic_joints = False
547  for ii, jj in joints_dict.items():
548  if 'mimic' in jj and jj['mimic'] == j['name']:
549  if not has_mimic_joints:
550  f.write(' mimic_joints:\n')
551  has_mimic_joints = True
552  f.write(' %s_position:\n' % jj['name'])
553  f.write(' type: %s_controllers/JointPositionController\n' % args.controller_type)
554  f.write(' joint: %s\n' % jj['name'])
555  if 'pid' in jj:
556  f.write(' pid: {p: %f, i: %f, d: %f}\n' % (jj['pid']['p'], jj['pid']['i'], jj['pid']['d']))
557  elif 'pid' in j:
558  f.write(' pid: {p: %f, i: %f, d: %f}\n' % (j['pid']['p'], j['pid']['i'], j['pid']['d']))
559  else:
560  f.write(' pid: {p: %f, i: %f, d: %f}\n' % (default_pid['p'], default_pid['i'], default_pid['d']))
561 
562  f.write('\n')
563  f.write('# Joint Trajectory Controllers ---------------------------------------\n')
564  f.write('fullbody_controller:\n')
565  f.write('# type: %s_controllers/JointTrajectoryController\n' % args.controller_type)
566  f.write(' type: gundam_rx78_control/JointTrajectoryController\n')
567  f.write(' joints:\n')
568  for i, j in joints_dict.items():
569  if ('name' in j) and not ('mimic' in j):
570  f.write(' - %s\n' % j['name'])
571  # for mimic joints
572  if not args.no_mimic:
573  f.write(' mimic_joints:\n')
574  for i, j in joints_dict.items():
575  if 'mimic' in j:
576  f.write(' - %s # %s\n' % (j['name'], j['mimic']))
577  # gains
578  f.write(' gains:\n')
579  for i, j in joints_dict.items():
580  if ('name' in j) and not ('mimic' in j):
581  if 'pid' in j:
582  f.write(' %s : {p: %f, i: %f, d: %f}\n' % (j['name'], j['pid']['p'], j['pid']['i'], j['pid']['d']))
583  else:
584  f.write(' %s : {p: %f, i: %f, d: %f}\n' % (j['name'], default_pid['p'], default_pid['i'], default_pid['d']))
585  # for mimic joints
586  if not args.no_mimic:
587  for i, j in joints_dict.items():
588  if 'mimic' in j:
589  if 'pid' in j:
590  f.write(' %s : {p: %f, i: %f, d: %f}' % (j['name'], j['pid']['p'], j['pid']['i'], j['pid']['d']))
591  elif [item for key, item in joints_dict.items() if (item['name'] == j['mimic']) and ('pid' in item)] != None:
592  jj = [item for key, item in joints_dict.items() if (item['name'] == j['mimic']) and ('pid' in item)][0]
593  f.write(' %s_joint : {p: %f, i: %f, d: %f}' % (j['name'], jj['pid']['p'], jj['pid']['i'], jj['pid']['d']))
594  else:
595  f.write(' %s_joint : {p: %f, i: %f, d: %f}' % (j['name'], default_pid['p'], default_pid['i'], default_pid['d']))
596  f.write(' # mimic joint of %s_joint\n' % (j['mimic']))
597  f.write(' constraints:\n')
598  f.write(' goal_time: 0.6\n')
599  f.write(' stopped_velocity_tolerance: 0.05\n')
600  f.write(' # joint: {trajectory: 0.2, goal: 0.2}\n')
601  f.write(' stop_trajectory_duration: 0.5\n')
602  f.write(' state_publish_rate: 125\n')
603  f.write(' action_monitor_rate: 10\n')
604  f.write(' allow_partial_joints_goal: true\n')
605 
606 
607 global robot, args
608 if __name__ == '__main__':
609  parser = argparse.ArgumentParser()
610  parser.add_argument('input_file', help='input collada file name')
611  parser.add_argument('--controller_type', choices=[
612  'position', 'velocity', 'effort'], default='effort', help='set controller type')
613  parser.add_argument(
614  '--no_mimic', action='store_true', help='disable mimic joint')
615  parser.add_argument(
616  '--pin', action='store_true', help='pin the robot to the world')
617  parser.add_argument(
618  '--write_mesh', action='store_true', help='write mech files')
619  args = parser.parse_args()
620 
621  # load collada file
622  mesh_ = Collada(args.input_file)
623  if mesh_.xmlnode.getroot().attrib['version'] != '1.4.1':
624  print('This program only support COLLADA 1.4.1, but the input file is %s' %
625  mesh_.xmlnode.getroot().attrib['version'])
626  sys.exit(1)
627 
628  # remove unused geometries / materials / effects / animations
629  simplify_collada(mesh_)
630 
631  # merge nodes into one node if no joints exist between them.
632  # add additional nodes if multiple joints exist for one childnode
633  # add root link
634  mergenode_collada(mesh_, joints_, root_offset)
635  joints_dict = dict(joints_)
636 
637  # apply scale
638  scale_collada(mesh_, scale_)
639 
640  # extract robot name
641  name_ = os.path.splitext(os.path.basename(mesh_.filename))[0]
642 
643  # create robot instance
644  robot_ = Robot(name=name_)
645  # DEBUG: create pinned model
646  if args.pin:
647  robot_.add_link(Link(name='world'))
648  robot_.add_joint(
649  Joint(name='world_to_base', parent='world', child='base_link', joint_type='fixed'))
650  # robot_.add_link(Link(name='base_link'))
651  print("loaded collada file {}".format(name_))
652  link_dict = dict()
653  retrive_node(mesh_.scene.nodes[0].children, joints_dict, link_dict) # hack for base_link
654 
655  # update transmission joints to human readable ones
656  # update_joint_name(robot_, joints_dict)
657 
658  # add gazebo information
659  add_gazebo_nodes(robot_, link_dict)
660 
661  print('all weight is %f' % all_weight_)
662 
663  # write urdf file
664  write_urdf_file(name_, robot_)
665 
666  # write control file
667  write_control_file(joints_dict)
def get_bouding_box(geometries)
def calc_inertia(collision, density=100.0)
def retrive_node(nodes, joints_dict, links_dict, parent=None)
def write_control_file(joints_dict)
def write_urdf_file(name, robot)
def add_gazebo_nodes(robot, link_dict)
def get_volume(geometries, density)


gundam_rx78_description
Author(s): Association GUNDAM GLOBAL CHALLENGE, Kei Okada , Naoki Hiraoka
autogenerated on Wed Sep 2 2020 03:33:36