diff --git a/urdf/lidar_lite.xacro b/urdf/lidar_lite.xacro
index 1924324a8342c45cf1964927db71cb68ce42e895..1f1d7baa2fa25043dea5d643f47095db68de1476 100644
--- a/urdf/lidar_lite.xacro
+++ b/urdf/lidar_lite.xacro
@@ -3,7 +3,7 @@
 <root xmlns:xacro="http://ros.org/wiki/xacro">
 
   <xacro:macro name="lidar_lite" params="name parent resolution *origin">
-    <link name="${name}_lidar_lite_base">
+    <link name="${name}_base">
       <inertial>
         <mass value="0.022" />
         <origin xyz="-0.01383390 0.01454150 0.01782971" rpy="0 0 0"/>
@@ -28,18 +28,18 @@
       </collision>
     </link>
 
-    <joint name="joint_${parent}_to_${name}_lidar_lite_base" type="fixed" >
+    <joint name="joint_${parent}_to_${name}_base" type="fixed" >
       <parent link="${parent}"/>
-      <child link="${name}_lidar_lite_base"/>
+      <child link="${name}_base"/>
       <xacro:insert_block name="origin" />
     </joint>
 
-    <link name="${name}_lidar_lite">
+    <link name="${name}">
     </link>
 
-    <joint name="joint_${name}_lidar_lite_base_to_${name}_lidar_lite" type="fixed" >
-      <parent link="${name}_lidar_lite_base"/>
-      <child link="${name}_lidar_lite"/>
+    <joint name="joint_${name}_base_to_${name}" type="fixed" >
+      <parent link="${name}_base"/>
+      <child link="${name}"/>
       <origin xyz="-0.01386 0.01454 0.041" rpy="3.14159 1.5707 0" />
     </joint>
 
diff --git a/urdf/lidar_lite_example.xacro b/urdf/lidar_lite_example.xacro
index aff05ce0d41bbd59fa36e11018c290f34679d85e..761e46e5753ef964b81fe95c35f28c035ee4cb7a 100644
--- a/urdf/lidar_lite_example.xacro
+++ b/urdf/lidar_lite_example.xacro
@@ -4,7 +4,7 @@
 
   <xacro:include filename="$(find iri_lidar_lite_description)/urdf/lidar_lite.xacro" />
 
-  <link name="lidar_base" >
+  <link name="lidar_base_parent" >
     <visual>
       <origin xyz="0 0 0" rpy="0 0 0" />
       <geometry>
@@ -27,7 +27,7 @@
     </collision>
   </link>
 
-  <xacro:lidar_lite name="lidar_lite_example" parent="lidar_base" resolution="high_res">
+  <xacro:lidar_lite name="lidar_lite" parent="lidar_base_parent" resolution="high_res">
     <origin xyz="0.0 0.0 0.5" rpy="0 0 0" />
   </xacro:lidar_lite>