Skip to content

Commit

Permalink
Modify the collision parameters of urdf
Browse files Browse the repository at this point in the history
Fixed a bug where objects in gazebo did not collide when they touched.
  • Loading branch information
jimy92 committed Nov 14, 2018
1 parent 38a1255 commit 9d7b495
Showing 1 changed file with 8 additions and 8 deletions.
16 changes: 8 additions & 8 deletions xarm_description/urdf/xarm7.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@
<geometry>
<mesh filename="package://xarm_description/meshes/xarm7/visual/link1.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<origin xyz="0 0 -0.261" rpy="0 0 0"/>
</collision>
<inertial>
<origin xyz="0.00017 0.02867 -0.00967" rpy="0 0 0"/>
Expand Down Expand Up @@ -99,14 +99,14 @@
<geometry>
<mesh filename="package://xarm_description/meshes/xarm7/visual/link2.stl"/>
</geometry>
<origin xyz="0 0 -0.260" rpy="0 0 0"/>
<origin xyz="0 0 -0.261" rpy="0 0 0"/>
<material name="White" />
</visual>
<collision>
<geometry>
<mesh filename="package://xarm_description/meshes/xarm7/visual/link2.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<origin xyz="0 0 -0.261" rpy="0 0 0"/>
</collision>
<inertial>
<origin xyz="1E-05 -0.13885 0.0139" rpy="0 0 0"/>
Expand Down Expand Up @@ -146,7 +146,7 @@
<geometry>
<mesh filename="package://xarm_description/meshes/xarm7/visual/link3.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<origin xyz="0 0 -0.546" rpy="0 0 0"/>
</collision>
<inertial>
<origin xyz="0.04387 0.02142 -0.00835" rpy="0 0 0"/>
Expand Down Expand Up @@ -186,7 +186,7 @@
<geometry>
<mesh filename="package://xarm_description/meshes/xarm7/visual/link4.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<origin xyz="-0.050 0 -0.546" rpy="0 0 0"/>
</collision>
<inertial>
<origin xyz="0.07059 0.11905 0.01071" rpy="0 0 0"/>
Expand Down Expand Up @@ -226,7 +226,7 @@
<geometry>
<mesh filename="package://xarm_description/meshes/xarm7/visual/link5.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<origin xyz="-0.1285 0 -0.210" rpy="0 0 0"/>
</collision>
<inertial>
<origin xyz="-0.00014 0.0234 -0.03053" rpy="0 0 0"/>
Expand Down Expand Up @@ -266,7 +266,7 @@
<geometry>
<mesh filename="package://xarm_description/meshes/xarm7/visual/link6.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<origin xyz="-0.1285 0 -0.210" rpy="0 0 0"/>
</collision>
<inertial>
<origin xyz="0.06596 0.00669 0.00097" rpy="0 0 0"/>
Expand Down Expand Up @@ -306,7 +306,7 @@
<geometry>
<mesh filename="package://xarm_description/meshes/xarm7/visual/link7.stl"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<origin xyz="-0.2015 0 -0.1405" rpy="0 0 0"/>
</collision>
<inertial>
<origin xyz="-3.5072E-05 9.5542E-06 -0.022065" rpy="0 0 0"/>
Expand Down

0 comments on commit 9d7b495

Please sign in to comment.