Skip to content
Snippets Groups Projects
Commit 2e1fee2f authored by gavanderhoorn's avatar gavanderhoorn
Browse files

description: add '_joint' suffix to newly introduced joint tags.

This is more in-line with naming of existing joint tags.
parent db6b1637
Branches
Tags
No related merge requests found
......@@ -302,7 +302,7 @@
<!-- ROS base_link to UR 'Base' Coordinates transform -->
<link name="${prefix}base"/>
<joint name="${prefix}base_link-base" type="fixed">
<joint name="${prefix}base_link-base_fixed_joint" type="fixed">
<!-- NOTE: this rotation is only needed as long as base_link itself is
not corrected wrt the real robot (ie: rotated over 180
degrees)
......@@ -314,7 +314,7 @@
<!-- Frame coincident with all-zeros TCP on UR controller -->
<link name="${prefix}tool0"/>
<joint name="${prefix}wrist_3_link-tool0" type="fixed">
<joint name="${prefix}wrist_3_link-tool0_fixed_joint" type="fixed">
<origin xyz="0 ${wrist_3_length} 0" rpy="${pi/-2.0} 0 0"/>
<parent link="${prefix}wrist_3_link"/>
<child link="${prefix}tool0"/>
......
......@@ -283,7 +283,7 @@
</actuator>
</transmission>
<link name="base"/>
<joint name="base_link-base" type="fixed">
<joint name="base_link-base_fixed_joint" type="fixed">
<!-- NOTE: this rotation is only needed as long as base_link itself is
not corrected wrt the real robot (ie: rotated over 180
degrees)
......@@ -293,7 +293,7 @@
<child link="base"/>
</joint>
<link name="tool0"/>
<joint name="wrist_3_link-tool0" type="fixed">
<joint name="wrist_3_link-tool0_fixed_joint" type="fixed">
<origin rpy="-1.570796325 0 0" xyz="0 0.0922 0"/>
<parent link="wrist_3_link"/>
<child link="tool0"/>
......
......@@ -283,7 +283,7 @@
</actuator>
</transmission>
<link name="base"/>
<joint name="base_link-base" type="fixed">
<joint name="base_link-base_fixed_joint" type="fixed">
<!-- NOTE: this rotation is only needed as long as base_link itself is
not corrected wrt the real robot (ie: rotated over 180
degrees)
......@@ -293,7 +293,7 @@
<child link="base"/>
</joint>
<link name="tool0"/>
<joint name="wrist_3_link-tool0" type="fixed">
<joint name="wrist_3_link-tool0_fixed_joint" type="fixed">
<origin rpy="-1.570796325 0 0" xyz="0 0.0922 0"/>
<parent link="wrist_3_link"/>
<child link="tool0"/>
......
......@@ -317,7 +317,7 @@
<!-- ROS base_link to UR 'Base' Coordinates transform -->
<link name="${prefix}base"/>
<joint name="${prefix}base_link-base" type="fixed">
<joint name="${prefix}base_link-base_fixed_joint" type="fixed">
<!-- NOTE: this rotation is only needed as long as base_link itself is
not corrected wrt the real robot (ie: rotated over 180
degrees)
......@@ -329,7 +329,7 @@
<!-- Frame coincident with all-zeros TCP on UR controller -->
<link name="${prefix}tool0"/>
<joint name="${prefix}wrist_3_link-tool0" type="fixed">
<joint name="${prefix}wrist_3_link-tool0_fixed_joint" type="fixed">
<origin xyz="0 ${wrist_3_length} 0" rpy="${pi/-2.0} 0 0"/>
<parent link="${prefix}wrist_3_link"/>
<child link="${prefix}tool0"/>
......
......@@ -283,7 +283,7 @@
</actuator>
</transmission>
<link name="base"/>
<joint name="base_link-base" type="fixed">
<joint name="base_link-base_fixed_joint" type="fixed">
<!-- NOTE: this rotation is only needed as long as base_link itself is
not corrected wrt the real robot (ie: rotated over 180
degrees)
......@@ -293,7 +293,7 @@
<child link="base"/>
</joint>
<link name="tool0"/>
<joint name="wrist_3_link-tool0" type="fixed">
<joint name="wrist_3_link-tool0_fixed_joint" type="fixed">
<origin rpy="-1.570796325 0 0" xyz="0 0.0823 0"/>
<parent link="wrist_3_link"/>
<child link="tool0"/>
......
......@@ -283,7 +283,7 @@
</actuator>
</transmission>
<link name="base"/>
<joint name="base_link-base" type="fixed">
<joint name="base_link-base_fixed_joint" type="fixed">
<!-- NOTE: this rotation is only needed as long as base_link itself is
not corrected wrt the real robot (ie: rotated over 180
degrees)
......@@ -293,7 +293,7 @@
<child link="base"/>
</joint>
<link name="tool0"/>
<joint name="wrist_3_link-tool0" type="fixed">
<joint name="wrist_3_link-tool0_fixed_joint" type="fixed">
<origin rpy="-1.570796325 0 0" xyz="0 0.0823 0"/>
<parent link="wrist_3_link"/>
<child link="tool0"/>
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment