diff --git a/urdf/helena.xacro b/urdf/helena.xacro
index 43d6241abc220bdb3ae333212c28e976454e3582..78dfa92bf02eaffe99d6a3fda3ccda1b6a9675b6 100755
--- a/urdf/helena.xacro
+++ b/urdf/helena.xacro
@@ -9,20 +9,20 @@
   <xacro:include filename="$(find helena_description)/urdf/sensors/camera.xacro" />
     
   <xacro:sensor_laser parent="top_plate" name="front_laser" prefix="$(arg name)">
-    <origin xyz="0.2 0 0.05" rpy="0 0 0"/>
+    <origin xyz="0.2 -0.15 0.05" rpy="0 0 -0.785398163"/>
   </xacro:sensor_laser>
   
   <xacro:sensor_laser parent="top_plate" name="rear_laser" prefix="$(arg name)">
-    <origin xyz="-0.2 0 0.05" rpy="0 0 3.14159"/>
+    <origin xyz="-0.2 0.15 0.05" rpy="0 0 2.35619449"/>
   </xacro:sensor_laser>
 
-  <xacro:sensor_camera parent="top_plate" name="front_camera" prefix="$(arg name)">
-    <origin xyz="0.2 0 1.0" rpy="0 0 0"/>
+  <xacro:sensor_camera parent="top_plate" name="front_bluefox_camera" prefix="$(arg name)">
+    <origin xyz="0.2 0 0.1" rpy="0 0 0"/>
   </xacro:sensor_camera>
 
   <!--
   <xacro:sensor_camera parent="top_plate" name="rear_camera" prefix="$(arg name)">
-    <origin xyz="-0.1 0 0.4" rpy="0 0 3.14159"/>
+    <origin xyz="-0.2 0 0.4" rpy="0 0 3.14159"/>
   </xacro:sensor_camera>
   -->
 
diff --git a/urdf/sensors/camera.xacro b/urdf/sensors/camera.xacro
index 0fe7b43c9b615de6885b1a595a5a50edff84ccb4..0d0ffdaddf08e95e33ad44837f8737e10d620b0a 100644
--- a/urdf/sensors/camera.xacro
+++ b/urdf/sensors/camera.xacro
@@ -1,8 +1,8 @@
 <?xml version="1.0"?>
 <xacro xmlns:xacro="http://www.ros.org/wiki/xacro" name="VLP-16">
   <xacro:property name="M_PI" value="3.1415926535897931" />
-  <xacro:property name="RATE" value="10" />
-  <xacro:property name="PIXEL_WIDTH" value="600" />
+  <xacro:property name="RATE" value="30" />
+  <xacro:property name="PIXEL_WIDTH" value="752" />
   <xacro:property name="PIXEL_HEIGHT" value="480" />
 
   <xacro:macro name="sensor_camera" params="parent name prefix *origin">
@@ -66,8 +66,8 @@
           <alwaysOn>true</alwaysOn>
           <updateRate>0.0</updateRate>
           <cameraName>${prefix}/${name}</cameraName>
-          <imageTopicName>/${prefix}/sensors/${name}/image_raw</imageTopicName>
-          <cameraInfoTopicName>/${prefix}/sensors/${name}/camera_info</cameraInfoTopicName>
+          <imageTopicName>/${prefix}/${name}/image_raw</imageTopicName>
+          <cameraInfoTopicName>/${prefix}/${name}/camera_info</cameraInfoTopicName>
           <frameName>${prefix}/${name}_link_optical</frameName>
           <hackBaseline>0.07</hackBaseline>
           <distortionK1>0.0</distortionK1>
diff --git a/urdf/sensors/laser.xacro b/urdf/sensors/laser.xacro
index cef00dc826b116738a0c075dfe08bbb141354122..62d53f5a369848d7bba022b02b869dbb12d27984 100644
--- a/urdf/sensors/laser.xacro
+++ b/urdf/sensors/laser.xacro
@@ -27,7 +27,7 @@
         <origin xyz="0 0 0"/>
         <geometry>
           <!--<mesh filename="package://helena_description/meshes/${MESH}"/>-->
-          <box size="0.1 0.1 0.1"/>
+          <box size="0.05 0.05 0.1"/>
         </geometry>
       </collision>
     </link>
@@ -40,10 +40,10 @@
         <ray>
           <scan>
             <horizontal>
-              <samples>720</samples>
+              <samples>1080</samples>
               <resolution>1</resolution>
-              <min_angle>-1.570796</min_angle>
-              <max_angle>1.570796</max_angle>
+              <min_angle>-2.35619449</min_angle>
+              <max_angle>2.35619449</max_angle>
             </horizontal>
           </scan>
           <range>