|
58 | 58 | <!-- crane_x7_link_1 -->
|
59 | 59 | <link name="${NAME_LINK_1}">
|
60 | 60 | <visual>
|
61 |
| - <origin xyz="0 0 0" rpy="0 0 ${M_PI}"/> |
| 61 | + <origin xyz="0 0 0" rpy="0 0 ${radians(180)}"/> |
62 | 62 | <geometry>
|
63 | 63 | <mesh filename="package://crane_x7_description/meshes/visual/base_revolute_part.stl"
|
64 | 64 | scale="1 1 1"/>
|
|
67 | 67 | </visual>
|
68 | 68 |
|
69 | 69 | <collision>
|
70 |
| - <!--<origin xyz="0 0 0" rpy="0 0 ${M_PI}"/>--> |
| 70 | + <!--<origin xyz="0 0 0" rpy="0 0 ${radians(180)}"/>--> |
71 | 71 | <!--<geometry>-->
|
72 | 72 | <!--<mesh filename="package://crane_x7_description/meshes/collision/base_revolute_part.stl"-->
|
73 | 73 | <!--scale="1 1 1"/>-->
|
|
78 | 78 | </geometry>
|
79 | 79 | </collision>
|
80 | 80 | <collision>
|
81 |
| - <origin xyz="0 0 0.064" rpy="${M_PI/2} 0 0"/> |
| 81 | + <origin xyz="0 0 0.064" rpy="${radians(90)} 0 0"/> |
82 | 82 | <geometry>
|
83 | 83 | <cylinder radius="0.034" length="0.0491"/>
|
84 | 84 | </geometry>
|
|
111 | 111 | <!-- crane_x7_link_2 -->
|
112 | 112 | <link name="${NAME_LINK_2}">
|
113 | 113 | <visual>
|
114 |
| - <origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/> |
| 114 | + <origin xyz="0 0 0" rpy="${radians(90)} 0 0"/> |
115 | 115 | <geometry>
|
116 | 116 | <mesh filename="package://crane_x7_description/meshes/visual/rotating_link_type_1_fixed_part.stl"
|
117 | 117 | scale="1 1 1"/>
|
|
120 | 120 | </visual>
|
121 | 121 |
|
122 | 122 | <collision>
|
123 |
| - <origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/> |
| 123 | + <origin xyz="0 0 0" rpy="${radians(90)} 0 0"/> |
124 | 124 | <geometry>
|
125 | 125 | <mesh filename="package://crane_x7_description/meshes/collision/rotating_link_type_1_fixed_part.stl"
|
126 | 126 | scale="1 1 1"/>
|
|
129 | 129 |
|
130 | 130 | <inertial>
|
131 | 131 | <mass value="0.136"/>
|
132 |
| - <origin xyz="3.10E-05 1.90E-05 3.42E-02" rpy="${M_PI/2} 0 0"/> |
| 132 | + <origin xyz="3.10E-05 1.90E-05 3.42E-02" rpy="${radians(90)} 0 0"/> |
133 | 133 | <inertia ixx="1.68E-04" ixy="2.05E-08" ixz="-4.00E-07"
|
134 | 134 | iyy="9.62E-05" iyz="6.24E-08"
|
135 | 135 | izz="1.34E-04"/>
|
|
146 | 146 | <!-- crane_x7_link_cover_2_l -->
|
147 | 147 | <link name="${NAME_LINK_COVER_2_L}">
|
148 | 148 | <visual>
|
149 |
| - <origin xyz="0 0 0" rpy="-${M_PI/2} 0 0"/> |
| 149 | + <origin xyz="0 0 0" rpy="${radians(-90)} 0 0"/> |
150 | 150 | <geometry>
|
151 | 151 | <mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
|
152 | 152 | scale="1 1 1"/>
|
|
155 | 155 | </visual>
|
156 | 156 |
|
157 | 157 | <collision>
|
158 |
| - <origin xyz="0 0 0" rpy="-${M_PI/2} 0 0"/> |
| 158 | + <origin xyz="0 0 0" rpy="${radians(-90)} 0 0"/> |
159 | 159 | <geometry>
|
160 | 160 | <mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
|
161 | 161 | scale="1 1 1"/>
|
|
173 | 173 | <!-- crane_x7_link_cover_2_r -->
|
174 | 174 | <link name="${NAME_LINK_COVER_2_R}">
|
175 | 175 | <visual>
|
176 |
| - <origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/> |
| 176 | + <origin xyz="0 0 0" rpy="${radians(90)} 0 0"/> |
177 | 177 | <geometry>
|
178 | 178 | <mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
|
179 | 179 | scale="1 1 1"/>
|
|
182 | 182 | </visual>
|
183 | 183 |
|
184 | 184 | <collision>
|
185 |
| - <origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/> |
| 185 | + <origin xyz="0 0 0" rpy="${radians(90)} 0 0"/> |
186 | 186 | <geometry>
|
187 | 187 | <mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
|
188 | 188 | scale="1 1 1"/>
|
|
250 | 250 | <!-- crane_x7_link_4 -->
|
251 | 251 | <link name="${NAME_LINK_4}">
|
252 | 252 | <visual>
|
253 |
| - <origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/> |
| 253 | + <origin xyz="0 0 0" rpy="${radians(90)} 0 0"/> |
254 | 254 | <geometry>
|
255 | 255 | <mesh filename="package://crane_x7_description/meshes/visual/rotating_link_type_2_fixed_part.stl"
|
256 | 256 | scale="1 1 1"/>
|
|
259 | 259 | </visual>
|
260 | 260 |
|
261 | 261 | <collision>
|
262 |
| - <origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/> |
| 262 | + <origin xyz="0 0 0" rpy="${radians(90)} 0 0"/> |
263 | 263 | <geometry>
|
264 | 264 | <mesh filename="package://crane_x7_description/meshes/collision/rotating_link_type_2_fixed_part.stl"
|
265 | 265 | scale="1 1 1"/>
|
|
268 | 268 |
|
269 | 269 | <inertial>
|
270 | 270 | <mass value="0.222"/>
|
271 |
| - <origin xyz="-9.39E-03 6.40E-05 8.04E-02" rpy="${M_PI/2} 0 0"/> |
| 271 | + <origin xyz="-9.39E-03 6.40E-05 8.04E-02" rpy="${radians(90)} 0 0"/> |
272 | 272 | <inertia ixx="4.89E-04" ixy="-3.90E-06" ixz="8.29E-08"
|
273 | 273 | iyy="1.14E-04" iyz="2.82E-06"
|
274 | 274 | izz="5.03E-04"/>
|
|
285 | 285 | <!-- crane_x7_link_cover_4_l -->
|
286 | 286 | <link name="${NAME_LINK_COVER_4_L}">
|
287 | 287 | <visual>
|
288 |
| - <origin xyz="0 0 0" rpy="-${M_PI/2} 0 0"/> |
| 288 | + <origin xyz="0 0 0" rpy="${radians(-90)} 0 0"/> |
289 | 289 | <geometry>
|
290 | 290 | <mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
|
291 | 291 | scale="1 1 1"/>
|
|
294 | 294 | </visual>
|
295 | 295 |
|
296 | 296 | <collision>
|
297 |
| - <origin xyz="0 0 0" rpy="-${M_PI/2} 0 0"/> |
| 297 | + <origin xyz="0 0 0" rpy="${radians(-90)} 0 0"/> |
298 | 298 | <geometry>
|
299 | 299 | <mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
|
300 | 300 | scale="1 1 1"/>
|
|
312 | 312 | <!-- crane_x7_link_cover_4_r -->
|
313 | 313 | <link name="${NAME_LINK_COVER_4_R}">
|
314 | 314 | <visual>
|
315 |
| - <origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/> |
| 315 | + <origin xyz="0 0 0" rpy="${radians(90)} 0 0"/> |
316 | 316 | <geometry>
|
317 | 317 | <mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
|
318 | 318 | scale="1 1 1"/>
|
|
321 | 321 | </visual>
|
322 | 322 |
|
323 | 323 | <collision>
|
324 |
| - <origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/> |
| 324 | + <origin xyz="0 0 0" rpy="${radians(90)} 0 0"/> |
325 | 325 | <geometry>
|
326 | 326 | <mesh filename="package://crane_x7_description/meshes/visual/joint_cover.stl"
|
327 | 327 | scale="1 1 1"/>
|
|
393 | 393 | <!-- crane_x7_link_6 -->
|
394 | 394 | <link name="${NAME_LINK_6}">
|
395 | 395 | <visual>
|
396 |
| - <origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/> |
| 396 | + <origin xyz="0 0 0" rpy="${radians(90)} 0 0"/> |
397 | 397 | <geometry>
|
398 | 398 | <mesh filename="package://crane_x7_description/meshes/visual/wrist.stl"
|
399 | 399 | scale="1 1 1"/>
|
|
402 | 402 | </visual>
|
403 | 403 |
|
404 | 404 | <collision>
|
405 |
| - <origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/> |
| 405 | + <origin xyz="0 0 0" rpy="${radians(90)} 0 0"/> |
406 | 406 | <geometry>
|
407 | 407 | <mesh filename="package://crane_x7_description/meshes/collision/wrist.stl"
|
408 | 408 | scale="1 1 1"/>
|
|
411 | 411 |
|
412 | 412 | <inertial>
|
413 | 413 | <mass value="0.14"/>
|
414 |
| - <origin xyz="6.10E-03 8.26E-04 -3.55E-03" rpy="${M_PI/2} 0 0"/> |
| 414 | + <origin xyz="6.10E-03 8.26E-04 -3.55E-03" rpy="${radians(90)} 0 0"/> |
415 | 415 | <inertia ixx="4.01E-05" ixy="-2.91E-06" ixz="6.39E-07"
|
416 | 416 | iyy="6.13E-05" iyz="-4.90E-07"
|
417 | 417 | izz="7.35E-05"/>
|
|
0 commit comments