Skip to content

Commit e339baa

Browse files
authored
Fix UR3 mesh positioning (backport of #258) (#259)
1 parent 3fa38f8 commit e339baa

File tree

3 files changed

+19
-6
lines changed

3 files changed

+19
-6
lines changed

config/ur3/visual_parameters.yaml

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@ mesh_files:
7878
mesh:
7979
package: ur_description
8080
path: meshes/ur3/collision/wrist2.stl
81-
visual_offset: -0.085
81+
visual_offset: -0.083
8282

8383
wrist_3:
8484
visual:
@@ -93,3 +93,4 @@ mesh_files:
9393
package: ur_description
9494
path: meshes/ur3/collision/wrist3.stl
9595
visual_offset: -0.082
96+
visual_offset_xyz: "0 -0.00255 -0.082"

urdf/inc/ur_common.xacro

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,12 @@
2222
</xacro:macro>
2323

2424
<xacro:macro name="get_visual_params" params="name:=^ type:=^" >
25-
<xacro:property name="visual_params" value="${sec_mesh_files[name][type]}" scope="parent"/>
25+
<xacro:if value="${type in sec_mesh_files[name]}">
26+
<xacro:property name="visual_params" value="${sec_mesh_files[name][type]}" scope="parent"/>
27+
</xacro:if>
28+
<xacro:unless value="${type in sec_mesh_files[name]}">
29+
<xacro:property name="visual_params" value="" scope="parent"/>
30+
</xacro:unless>
2631
</xacro:macro>
2732

2833
<!-- Simplification of getting meshes. Available types can be seen in the visual_parameters.yaml (At the time of writing: visual, collision) -->

urdf/ur_macro.xacro

Lines changed: 11 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -270,7 +270,7 @@
270270
</inertial>
271271
</link>
272272
<link name="${tf_prefix}wrist_2_link">
273-
<xacro:get_visual_params name="wrist_2" type="visual_offset"/>
273+
<xacro:get_visual_params name="wrist_2" type="visual_offset"/>
274274
<visual>
275275
<origin xyz="0 0 ${visual_params}" rpy="0 0 0"/>
276276
<geometry>
@@ -297,15 +297,22 @@
297297
</inertial>
298298
</link>
299299
<link name="${tf_prefix}wrist_3_link">
300-
<xacro:get_visual_params name="wrist_3" type="visual_offset"/>
300+
<!-- TODO: remove this once all wrist_3 meshes have the visual_offset_xyz tag -->
301+
<xacro:get_visual_params name="wrist_3" type="visual_offset_xyz"/>
302+
<xacro:property name="mesh_offset" value="${visual_params}" scope="parent"/>
303+
304+
<xacro:if value="${visual_params == ''}">
305+
<xacro:get_visual_params name="wrist_3" type="visual_offset"/>
306+
<xacro:property name="mesh_offset" value="0 0 ${visual_params}" scope="parent"/>
307+
</xacro:if>
301308
<visual>
302-
<origin xyz="0 0 ${visual_params}" rpy="${pi/2} 0 0"/>
309+
<origin xyz="${mesh_offset}" rpy="${pi/2} 0 0"/>
303310
<geometry>
304311
<xacro:get_mesh name="wrist_3" type="visual"/>
305312
</geometry>
306313
</visual>
307314
<collision>
308-
<origin xyz="0 0 ${visual_params}" rpy="${pi/2} 0 0"/>
315+
<origin xyz="${mesh_offset}" rpy="${pi/2} 0 0"/>
309316
<geometry>
310317
<xacro:get_mesh name="wrist_3" type="collision"/>
311318
</geometry>

0 commit comments

Comments
 (0)