Skip to content

Commit

Permalink
correct inertial of wrist3
Browse files Browse the repository at this point in the history
  • Loading branch information
fmauch committed May 29, 2019
1 parent 7cfe226 commit e42b021
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions ur_description/urdf/ur10.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -270,8 +270,8 @@
<mesh filename="package://ur_description/meshes/ur10/collision/wrist3.stl"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="0.075" length="0.12" mass="${wrist_3_mass}">
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
<xacro:cylinder_inertial radius="0.045" length="0.0305" mass="${wrist_3_mass}">
<origin xyz="0.0 0.0 ${-0.0305/2.0}" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>

Expand Down

0 comments on commit e42b021

Please sign in to comment.