diff --git a/ur_description/urdf/ur10.urdf.xacro b/ur_description/urdf/ur10.urdf.xacro
index c6a9e29dca93c6d8bb8ba374043cb28e90a2e04a..a4dd2fbdd311ee635ac6f0383b8b353a65d319f8 100644
--- a/ur_description/urdf/ur10.urdf.xacro
+++ b/ur_description/urdf/ur10.urdf.xacro
@@ -300,5 +300,25 @@
     <xacro:ur10_arm_transmission prefix="${prefix}" />
     <xacro:ur10_arm_gazebo prefix="${prefix}" />
 
+    <!-- ROS base_link to UR 'Base' Coordinates transform -->
+    <link name="${prefix}base"/>
+    <joint name="${prefix}base_link-base" 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)
+      -->
+      <origin xyz="0 0 0" rpy="0 0 ${-pi}"/>
+      <parent link="${prefix}base_link"/>
+      <child link="${prefix}base"/>
+    </joint>
+
+    <!-- Frame coincident with all-zeros TCP on UR controller -->
+    <link name="${prefix}tool0"/>
+    <joint name="${prefix}wrist_3_link-tool0" 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"/>
+    </joint>
+
   </xacro:macro>
 </robot>
diff --git a/ur_description/urdf/ur10_joint_limited_robot.urdf b/ur_description/urdf/ur10_joint_limited_robot.urdf
index 6889829eda0db558cdaf295046d9d89c5a2eaf01..3aab4c032ab197157032f42ae38e4cabb51c9f18 100644
--- a/ur_description/urdf/ur10_joint_limited_robot.urdf
+++ b/ur_description/urdf/ur10_joint_limited_robot.urdf
@@ -282,6 +282,22 @@
       <mechanicalReduction>1</mechanicalReduction>
     </actuator>
   </transmission>
+  <link name="base"/>
+  <joint name="base_link-base" 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)
+      -->
+    <origin rpy="0 0 -3.14159265" xyz="0 0 0"/>
+    <parent link="base_link"/>
+    <child link="base"/>
+  </joint>
+  <link name="tool0"/>
+  <joint name="wrist_3_link-tool0" type="fixed">
+    <origin rpy="-1.570796325 0 0" xyz="0 0.0922 0"/>
+    <parent link="wrist_3_link"/>
+    <child link="tool0"/>
+  </joint>
   <link name="world"/>
   <joint name="world_joint" type="fixed">
     <parent link="world"/>
diff --git a/ur_description/urdf/ur10_robot.urdf b/ur_description/urdf/ur10_robot.urdf
index 321c04a3b2b1431acbdebad72fc032579d9bd274..a6144133190d698031650c7a501b73df8771612c 100644
--- a/ur_description/urdf/ur10_robot.urdf
+++ b/ur_description/urdf/ur10_robot.urdf
@@ -282,6 +282,22 @@
       <mechanicalReduction>1</mechanicalReduction>
     </actuator>
   </transmission>
+  <link name="base"/>
+  <joint name="base_link-base" 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)
+      -->
+    <origin rpy="0 0 -3.14159265" xyz="0 0 0"/>
+    <parent link="base_link"/>
+    <child link="base"/>
+  </joint>
+  <link name="tool0"/>
+  <joint name="wrist_3_link-tool0" type="fixed">
+    <origin rpy="-1.570796325 0 0" xyz="0 0.0922 0"/>
+    <parent link="wrist_3_link"/>
+    <child link="tool0"/>
+  </joint>
   <link name="world"/>
   <joint name="world_joint" type="fixed">
     <parent link="world"/>
diff --git a/ur_description/urdf/ur5.urdf.xacro b/ur_description/urdf/ur5.urdf.xacro
index 4ccf0b31c178e58f2142e595ef47ea259c1c4139..2c5998b0a6ec532a4e41a4127e1643b3fffc6265 100644
--- a/ur_description/urdf/ur5.urdf.xacro
+++ b/ur_description/urdf/ur5.urdf.xacro
@@ -315,5 +315,25 @@
     <xacro:ur5_arm_transmission prefix="${prefix}" />
     <xacro:ur5_arm_gazebo prefix="${prefix}" />
 
+    <!-- ROS base_link to UR 'Base' Coordinates transform -->
+    <link name="${prefix}base"/>
+    <joint name="${prefix}base_link-base" 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)
+      -->
+      <origin xyz="0 0 0" rpy="0 0 ${-pi}"/>
+      <parent link="${prefix}base_link"/>
+      <child link="${prefix}base"/>
+    </joint>
+
+    <!-- Frame coincident with all-zeros TCP on UR controller -->
+    <link name="${prefix}tool0"/>
+    <joint name="${prefix}wrist_3_link-tool0" 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"/>
+    </joint>
+
   </xacro:macro>
 </robot>
diff --git a/ur_description/urdf/ur5_joint_limited_robot.urdf b/ur_description/urdf/ur5_joint_limited_robot.urdf
index 983a2c0446597e49924f22a06099c6e435a848e8..eb2000834b28d4901db9b57483952932c29a66cc 100644
--- a/ur_description/urdf/ur5_joint_limited_robot.urdf
+++ b/ur_description/urdf/ur5_joint_limited_robot.urdf
@@ -282,6 +282,22 @@
       <mechanicalReduction>1</mechanicalReduction>
     </actuator>
   </transmission>
+  <link name="base"/>
+  <joint name="base_link-base" 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)
+      -->
+    <origin rpy="0 0 -3.14159265" xyz="0 0 0"/>
+    <parent link="base_link"/>
+    <child link="base"/>
+  </joint>
+  <link name="tool0"/>
+  <joint name="wrist_3_link-tool0" type="fixed">
+    <origin rpy="-1.570796325 0 0" xyz="0 0.0823 0"/>
+    <parent link="wrist_3_link"/>
+    <child link="tool0"/>
+  </joint>
   <link name="world"/>
   <joint name="world_joint" type="fixed">
     <parent link="world"/>
diff --git a/ur_description/urdf/ur5_robot.urdf b/ur_description/urdf/ur5_robot.urdf
index 0179fa8982dafdfcb0d1eeaf6eef9225010c34d4..a912fba9e940590f67f1ee11afd746d8409c6c2f 100644
--- a/ur_description/urdf/ur5_robot.urdf
+++ b/ur_description/urdf/ur5_robot.urdf
@@ -282,6 +282,22 @@
       <mechanicalReduction>1</mechanicalReduction>
     </actuator>
   </transmission>
+  <link name="base"/>
+  <joint name="base_link-base" 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)
+      -->
+    <origin rpy="0 0 -3.14159265" xyz="0 0 0"/>
+    <parent link="base_link"/>
+    <child link="base"/>
+  </joint>
+  <link name="tool0"/>
+  <joint name="wrist_3_link-tool0" type="fixed">
+    <origin rpy="-1.570796325 0 0" xyz="0 0.0823 0"/>
+    <parent link="wrist_3_link"/>
+    <child link="tool0"/>
+  </joint>
   <link name="world"/>
   <joint name="world_joint" type="fixed">
     <parent link="world"/>