diff --git a/include/people_simulation_alg_node.h b/include/people_simulation_alg_node.h
index 653de2eae2c85a6337b4653a35a44ea120892dc0..ba48585fcca503e1d4d981d174d9fddeff5a752d 100644
--- a/include/people_simulation_alg_node.h
+++ b/include/people_simulation_alg_node.h
@@ -38,9 +38,9 @@
 
 // [service client headers]
 #include <std_srvs/Empty.h>
-#include <iri_perception_msgs/InitialiceSim.h>
+#include <iri_nav_msgs/InitialiceSim.h>
 #include <actionlib/client/terminal_state.h>
-#include <iri_perception_msgs/restartSim.h>
+#include <iri_nav_msgs/restartSim.h>
 // [action server client headers]
 
 /**
@@ -71,7 +71,7 @@ class PeopleSimulationAlgNode : public algorithm_base::IriBaseAlgorithm<PeopleSi
 
     // server to initialice person positions.
     ros::ServiceServer init_simulations_server_;
-    bool init_simulationsCallback(iri_perception_msgs::InitialiceSim::Request &req, iri_perception_msgs::InitialiceSim::Response &res);
+    bool init_simulationsCallback(iri_nav_msgs::InitialiceSim::Request &req, iri_nav_msgs::InitialiceSim::Response &res);
     pthread_mutex_t init_simulations_mutex_;
     void init_simulations_mutex_enter(void);
     void init_simulations_mutex_exit(void);
diff --git a/src/people_simulation_alg_node.cpp b/src/people_simulation_alg_node.cpp
index 1236a5d53c7019b2860c79ba791dba5a2cdd184b..269776c412217b7267e8e750f9235ad57f54f4fd 100644
--- a/src/people_simulation_alg_node.cpp
+++ b/src/people_simulation_alg_node.cpp
@@ -6,7 +6,8 @@ PeopleSimulationAlgNode::PeopleSimulationAlgNode(void) :
   tf_listener_(ros::Duration(10.f))
 {
   //init class attributes if necessary
-  this->loop_rate_ = 10;//in [Hz]
+  //this->loop_rate_ = 10;//in [Hz] Es de ubuntu 14.04
+  setRate(10);
 
   // [init publishers]
   this->tracksMarkers_publisher_ = this->public_node_handle_.advertise<visualization_msgs::MarkerArray>("tracksMarkers", 100);
@@ -328,7 +329,7 @@ void PeopleSimulationAlgNode::init_simulations_mutex_exit(void)
 
 /* [service callback] => restart persons to initial position */
 
-bool PeopleSimulationAlgNode::init_simulationsCallback(iri_perception_msgs::InitialiceSim::Request &req, iri_perception_msgs::InitialiceSim::Response &res)
+bool PeopleSimulationAlgNode::init_simulationsCallback(iri_nav_msgs::InitialiceSim::Request &req, iri_nav_msgs::InitialiceSim::Response &res)
 {
   ROS_INFO("tibi [People_companion] PeopleSimulationAlgNode::init_simulationsCallback: New Request Received!");