diff --git a/launch/fake_localization.launch b/launch/fake_localization.launch
index cdfc05635aaf627d6af87531bfc94bc70904ad07..1f67d0a1fd5d64ee50860eb18dab77df2e521ed6 100644
--- a/launch/fake_localization.launch
+++ b/launch/fake_localization.launch
@@ -12,7 +12,7 @@
       <param name="base_frame_id"   value="/$(optenv ROBOT tibi)/base_footprint" />
       <!-- parameters to change the robot initial position, if want the robot in -1 and -8=> delta_x=1.0 ; delta_y=8.0 -->
       <param name="delta_x"   value="1.0" /> <!-- Normal position (estrechez mitad camino) = delta_x=1.0 ;  delta_y=2.0 ; delta_yaw=0.0 -->
-      <param name="delta_y"   value="-18.0" /> <!-- GIRO ESQUINA position (estrechez mitad camino)= delta_x=1.0 ;  delta_y=-18.0 ; delta_yaw=1.57 -->
+      <param name="delta_y"   value="-15.0" /> <!-- GIRO ESQUINA position (estrechez mitad camino)= delta_x=1.0 ;  delta_y=-18.0 ; delta_yaw=1.57 -->
       <param name="delta_yaw" value="1.57" />
       <remap from="/odom" to="/$(optenv ROBOT tibi)/segway/odom"/>
       <remap from="base_pose_ground_truth" to="/$(optenv ROBOT tibi)/segway/odom"/>
diff --git a/src/diff_platform_simulator_alg_node.cpp b/src/diff_platform_simulator_alg_node.cpp
index d254de74e798e62e0552ba7a5fa594bc919be5c0..0ad83bba349898d7af712eb130a806b88f7125a2 100644
--- a/src/diff_platform_simulator_alg_node.cpp
+++ b/src/diff_platform_simulator_alg_node.cpp
@@ -5,7 +5,9 @@ DiffPlatformSimulatorAlgNode::DiffPlatformSimulatorAlgNode(void) :
 {
   //init class attributes if necessary
   this->loop_rate_ = 50;//in [Hz]
-  
+
+  //ROS_INFO("DiffPlatformSimulatorAlgNode:: this->tf_prefix_.c_str()=%s",this->tf_prefix_.c_str()); 
+
   this->public_node_handle_.getParam("robot", this->tf_prefix_);
   this->odom_id_           = "/" + this->tf_prefix_ + "/odom";
   this->base_link_id_      = "/" + this->tf_prefix_ + "/base_link";
diff --git a/src/fake_laser_gen_alg_node.cpp b/src/fake_laser_gen_alg_node.cpp
index c21a260b1c8d7a6ad601035d5be28d4e6fa5d6b2..4af319e5d25cbeaee57e9fa5e19563429c50e4ab 100644
--- a/src/fake_laser_gen_alg_node.cpp
+++ b/src/fake_laser_gen_alg_node.cpp
@@ -195,10 +195,10 @@ void FakeLaserGenAlgNode::node_config_update(Config &config, uint32_t level)
       ROS_INFO("scene");
       for (unsigned int n = 20; n<700; ++n)
         LaserScan_msg_.ranges[n] = 3.0 / sin(LaserScan_msg_.angle_increment * (double) n);
-      for (unsigned int n = 758; n<900; ++n)
-        LaserScan_msg_.ranges[n] = -3.0 / sin(LaserScan_msg_.angle_increment * (double) n);
-      for (unsigned int n = 900; n<1040; ++n)
-        LaserScan_msg_.ranges[n] = -3.0 / cos(LaserScan_msg_.angle_increment * (double) n);
+      for (unsigned int n = 758; n<805; ++n)
+        LaserScan_msg_.ranges[n] = -2.0 / sin(LaserScan_msg_.angle_increment * (double) n);
+      for (unsigned int n = 805; n<1040; ++n)
+        LaserScan_msg_.ranges[n] = -5.0 / cos(LaserScan_msg_.angle_increment * (double) n);
       for (unsigned int n = 1137; n<1260; ++n)
         LaserScan_msg_.ranges[n] = 3.0 / cos(LaserScan_msg_.angle_increment * (double) n);
       for (unsigned int n = 1260; n<1400; ++n)