From 2e1fee2ffc5925e3cabe25bb6c07bb02220f94f6 Mon Sep 17 00:00:00 2001
From: gavanderhoorn <g.a.vanderhoorn@tudelft.nl>
Date: Tue, 5 May 2015 16:00:14 +0200
Subject: [PATCH] description: add '_joint' suffix to newly introduced joint
 tags.

This is more in-line with naming of existing joint tags.
---
 ur_description/urdf/ur10.urdf.xacro               | 4 ++--
 ur_description/urdf/ur10_joint_limited_robot.urdf | 4 ++--
 ur_description/urdf/ur10_robot.urdf               | 4 ++--
 ur_description/urdf/ur5.urdf.xacro                | 4 ++--
 ur_description/urdf/ur5_joint_limited_robot.urdf  | 4 ++--
 ur_description/urdf/ur5_robot.urdf                | 4 ++--
 6 files changed, 12 insertions(+), 12 deletions(-)

diff --git a/ur_description/urdf/ur10.urdf.xacro b/ur_description/urdf/ur10.urdf.xacro
index a4dd2fb..333c542 100644
--- a/ur_description/urdf/ur10.urdf.xacro
+++ b/ur_description/urdf/ur10.urdf.xacro
@@ -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"/>
diff --git a/ur_description/urdf/ur10_joint_limited_robot.urdf b/ur_description/urdf/ur10_joint_limited_robot.urdf
index 3aab4c0..a01152a 100644
--- a/ur_description/urdf/ur10_joint_limited_robot.urdf
+++ b/ur_description/urdf/ur10_joint_limited_robot.urdf
@@ -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"/>
diff --git a/ur_description/urdf/ur10_robot.urdf b/ur_description/urdf/ur10_robot.urdf
index a614413..def9d24 100644
--- a/ur_description/urdf/ur10_robot.urdf
+++ b/ur_description/urdf/ur10_robot.urdf
@@ -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"/>
diff --git a/ur_description/urdf/ur5.urdf.xacro b/ur_description/urdf/ur5.urdf.xacro
index 2c5998b..324ff52 100644
--- a/ur_description/urdf/ur5.urdf.xacro
+++ b/ur_description/urdf/ur5.urdf.xacro
@@ -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"/>
diff --git a/ur_description/urdf/ur5_joint_limited_robot.urdf b/ur_description/urdf/ur5_joint_limited_robot.urdf
index eb20008..ebce3b0 100644
--- a/ur_description/urdf/ur5_joint_limited_robot.urdf
+++ b/ur_description/urdf/ur5_joint_limited_robot.urdf
@@ -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"/>
diff --git a/ur_description/urdf/ur5_robot.urdf b/ur_description/urdf/ur5_robot.urdf
index a912fba..4ff7e3e 100644
--- a/ur_description/urdf/ur5_robot.urdf
+++ b/ur_description/urdf/ur5_robot.urdf
@@ -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"/>
-- 
GitLab