Skip to content

Commit

Permalink
replaced last occurrences of dh parameters with real values
Browse files Browse the repository at this point in the history
I would prefer getting this correct from the kinematic parameters and the offsets,
however this will go into another MR
  • Loading branch information
fmauch committed May 29, 2019
1 parent 462aaa7 commit e4369b1
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions ur_description/urdf/ur10.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -147,8 +147,8 @@
<mesh filename="package://ur_description/meshes/ur10/collision/upperarm.stl"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="0.075" length="${-a2}" mass="${upper_arm_mass}">
<origin xyz="0.0 0.0 ${-a2/2.0}" rpy="0 0 0" />
<xacro:cylinder_inertial radius="0.075" length="${0.612}" mass="${upper_arm_mass}">
<origin xyz="0.0 0.0 ${0.612/2.0}" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>

Expand Down Expand Up @@ -182,8 +182,8 @@
<mesh filename="package://ur_description/meshes/ur10/collision/forearm.stl"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="0.075" length="${-a3}" mass="${forearm_mass}">
<origin xyz="0.0 0.0 ${-a3/2.0}" rpy="0 0 0" />
<xacro:cylinder_inertial radius="0.075" length="${0.5723}" mass="${forearm_mass}">
<origin xyz="0.0 0.0 ${0.5723/2.0}" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>

Expand Down

0 comments on commit e4369b1

Please sign in to comment.