diff --git a/meshes/uxm30lnp.stl b/meshes/uxm30lnp.stl
new file mode 100755
index 0000000000000000000000000000000000000000..1d8ab8d0f50061a9e114e8fdc240cd8963b918ce
Binary files /dev/null and b/meshes/uxm30lnp.stl differ
diff --git a/urdf/helena.gazebo b/urdf/helena.gazebo
index bbb2352a2410e46a876906e7bba055d873a65b4e..05ce4ccd976c130f8a17519bd9f1682bb5e896f5 100755
--- a/urdf/helena.gazebo
+++ b/urdf/helena.gazebo
@@ -120,9 +120,9 @@
     </sensor>
   </gazebo>  
 
-  <!-- hokuyo -->
-  <gazebo reference="front_hokuyo_link">
-    <sensor type="ray" name="head_front_hokuyo_sensor">
+  <!-- laser -->
+  <gazebo reference="front_laser_link">
+    <sensor type="ray" name="head_front_laser_sensor">
       <pose>0 0 0 0 0 0</pose>
       <visualize>false</visualize>
       <update_rate>40</update_rate>
@@ -150,16 +150,16 @@
           <stddev>0.01</stddev>
         </noise>
       </ray>
-      <plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
+      <plugin name="gazebo_ros_head_laser_controller" filename="libgazebo_ros_laser.so">
         <topicName>/helena/lasers/front_scan</topicName>
-        <frameName>/helena/front_hokuyo_link</frameName>
+        <frameName>/helena/front_laser_link</frameName>
       </plugin>
     </sensor>
   </gazebo>
 
-  <!-- hokuyo -->
-  <gazebo reference="rear_hokuyo_link">
-    <sensor type="ray" name="head_rear_hokuyo_sensor">
+  <!-- laser -->
+  <gazebo reference="rear_laser_link">
+    <sensor type="ray" name="head_rear_laser_sensor">
       <pose>0 0 0 0 0 0</pose>
       <visualize>false</visualize>
       <update_rate>40</update_rate>
@@ -187,9 +187,9 @@
           <stddev>0.01</stddev>
         </noise>
       </ray>
-      <plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
+      <plugin name="gazebo_ros_head_laser_controller" filename="libgazebo_ros_laser.so">
         <topicName>/helena/lasers/rear_scan</topicName>
-        <frameName>/helena/rear_hokuyo_link</frameName>
+        <frameName>/helena/rear_laser_link</frameName>
       </plugin>
     </sensor>
   </gazebo>
diff --git a/urdf/helena.xacro b/urdf/helena.xacro
index 24b3d7aac8bc9f227151d6667b0b5c2497ed5fe7..0727cf06d022e50354fa90b20c3ce33269d1a67e 100755
--- a/urdf/helena.xacro
+++ b/urdf/helena.xacro
@@ -218,15 +218,15 @@
     </inertial>
   </link>
 
-  <joint name="front_hokuyo_joint" type="fixed">
+  <joint name="front_laser_joint" type="fixed">
     <axis xyz="0 1 0" />
     <origin xyz="0.2 0 0.05" rpy="0 0 0"/>
     <parent link="top_plate"/>
-    <child link="front_hokuyo_link"/>
+    <child link="front_laser_link"/>
   </joint>
 
   <!-- Hokuyo Laser -->
-  <link name="front_hokuyo_link">
+  <link name="front_laser_link">
     <collision>
       <origin xyz="0 0 0" rpy="0 0 0"/>
       <geometry>
@@ -237,7 +237,7 @@
     <visual>
       <origin xyz="0 0 0" rpy="0 0 0"/>
       <geometry>
-        <mesh filename="package://helena_description/meshes/hokuyo.dae"/>
+        <mesh filename="package://helena_description/meshes/uxm30lnp.stl"/>
       </geometry>
     </visual>
 
@@ -248,15 +248,15 @@
     </inertial>
   </link>
 
-  <joint name="rear_hokuyo_joint" type="fixed">
+  <joint name="rear_laser_joint" type="fixed">
     <axis xyz="0 1 0" />
     <origin xyz="-0.2 0 0.05" rpy="0 0 3.14159"/>
     <parent link="top_plate"/>
-    <child link="rear_hokuyo_link"/>
+    <child link="rear_laser_link"/>
   </joint>
 
   <!-- Hokuyo Laser -->
-  <link name="rear_hokuyo_link">
+  <link name="rear_laser_link">
     <collision>
       <origin xyz="0 0 0" rpy="0 0 0"/>
       <geometry>
@@ -267,7 +267,7 @@
     <visual>
       <origin xyz="0 0 0" rpy="0 0 0"/>
       <geometry>
-        <mesh filename="package://helena_description/meshes/hokuyo.dae"/>
+        <mesh filename="package://helena_description/meshes/uxm30lnp.stl"/>
       </geometry>
     </visual>