diff --git a/ur_description/urdf/ur10.urdf.xacro b/ur_description/urdf/ur10.urdf.xacro index a4dd2fbdd311ee635ac6f0383b8b353a65d319f8..333c5421f992d69cfa201698cfc348f4499edbe0 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 3aab4c032ab197157032f42ae38e4cabb51c9f18..a01152a26ffa2823b3a5f583261a97b1c58c6a4a 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 a6144133190d698031650c7a501b73df8771612c..def9d241549a95129339f1431df4243d22ff2aad 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 2c5998b0a6ec532a4e41a4127e1643b3fffc6265..324ff520362af38c3854f7155f8886745219c373 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 eb2000834b28d4901db9b57483952932c29a66cc..ebce3b0e343ac5c31256189283eb529f34abdaf9 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 a912fba9e940590f67f1ee11afd746d8409c6c2f..4ff7e3e63d3dd8d31ab7c735c041dbd77cc5ecfd 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"/>