Skip to content

Commit

Permalink
Make the kinematic chain start from base_link instead of base.
Browse files Browse the repository at this point in the history
  • Loading branch information
fmauch committed May 29, 2019
1 parent 8531055 commit 462aaa7
Showing 1 changed file with 8 additions and 3 deletions.
11 changes: 8 additions & 3 deletions ur_description/urdf/ur10.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -58,8 +58,12 @@
<xacro:property name="shoulder_offset" value="0.220941" /> <!-- measured from model -->
<xacro:property name="elbow_offset" value="0.049042" /> <!-- measured from model -->

<!-- This is for compatibility reasons, as transformation between base and base_link was always 180 degree in the ur_description -->
<xacro:property name="base_correction" value="${pi}" />

<link name="${prefix}base_link" >
<visual>
<origin xyz="0 0 0" rpy="0 0 ${base_correction}"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/base.dae"/>
</geometry>
Expand All @@ -68,6 +72,7 @@
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 ${base_correction}"/>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/collision/base.stl"/>
</geometry>
Expand All @@ -78,9 +83,9 @@
</link>

<joint name="${prefix}shoulder_pan_joint" type="revolute">
<parent link="${prefix}base" />
<parent link="${prefix}base_link" />
<child link = "${prefix}shoulder_link" />
<origin xyz="${__kinematics['shoulder']['x']} ${__kinematics['shoulder']['y']} ${__kinematics['shoulder']['z']}" rpy="${__kinematics['shoulder']['roll']} ${__kinematics['shoulder']['pitch']} ${__kinematics['shoulder']['yaw']}" />
<origin xyz="${__kinematics['shoulder']['x']} ${__kinematics['shoulder']['y']} ${__kinematics['shoulder']['z']}" rpy="${__kinematics['shoulder']['roll']} ${__kinematics['shoulder']['pitch']} ${__kinematics['shoulder']['yaw'] + base_correction}" />
<axis xyz="0 0 1" />
<xacro:unless value="${joint_limited}">
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="330.0" velocity="2.16"/>
Expand Down Expand Up @@ -318,7 +323,7 @@
not corrected wrt the real robot (ie: rotated over 180
degrees)
-->
<origin xyz="0 0 0" rpy="0 0 ${-pi}"/>
<origin xyz="0 0 0" rpy="0 0 ${-base_correction}"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}base"/>
</joint>
Expand Down

0 comments on commit 462aaa7

Please sign in to comment.