diff --git a/include/akp_local_planner_alg_node.h b/include/akp_local_planner_alg_node.h
index 50c3ef7d5da26d9363c175ceaad2c5a3167d12f7..2a47dc4f98d955fe42c0eba63b505eccd0da17ea 100644
--- a/include/akp_local_planner_alg_node.h
+++ b/include/akp_local_planner_alg_node.h
@@ -57,7 +57,7 @@
 #include <geometry_msgs/PoseStamped.h>
 //#include <tf/transform_broadcaster.h> // robot companion (ely) trasladar modelo tibi robot companion al marcker donde deberia estar el robot.
 
-#include <iri_perception_msgs/restartSim.h>
+#include <iri_nav_msgs/restartSim.h>
 
 #include <random>
 #include <iostream>
@@ -99,7 +99,7 @@ using namespace std;
 
 
 // [service client headers]
-#include <iri_perception_msgs/InitialiceSim.h>
+#include <iri_nav_msgs/InitialiceSim.h>
 #include <move_base/move_base.h>
 
 // [action server client headers]
@@ -257,7 +257,7 @@ class AkpLocalPlanner : public nav_core::BaseLocalPlanner
     ros::Publisher tibi_akp_status_publisher_;
     std_msgs::UInt64 tibi_akp_status_UInt64_msg_;
 
-    iri_perception_msgs::InitialiceSim init_simulations_srv_;
+    iri_nav_msgs::InitialiceSim init_simulations_srv_;
 
     nav_msgs::GetPlan get_plan_srv_;
 
diff --git a/local_lib_people_prediction/bin/prediction_example b/local_lib_people_prediction/bin/prediction_example
index 3e86ef4e23c680979c4899f9c081ce98ce28d8e1..55f69720edec9dff044f24f4a2ce3c573396aab7 100755
Binary files a/local_lib_people_prediction/bin/prediction_example and b/local_lib_people_prediction/bin/prediction_example differ
diff --git a/src/akp_local_planner_alg_node.cpp b/src/akp_local_planner_alg_node.cpp
index e333a77c7db667ef546f6a671b22015672613292..fe0c6db5f08a48b6fff2b2409e62db34e03f4f1a 100644
--- a/src/akp_local_planner_alg_node.cpp
+++ b/src/akp_local_planner_alg_node.cpp
@@ -232,7 +232,7 @@ void AkpLocalPlanner::init()
 
 
   // [init clients]
-  init_simulations_client_ = this->public_node_handle_.serviceClient<iri_perception_msgs::InitialiceSim>("init_simulations");
+  init_simulations_client_ = this->public_node_handle_.serviceClient<iri_nav_msgs::InitialiceSim>("init_simulations");
 
 
   get_plan_client_ = this->public_node_handle_.serviceClient<nav_msgs::GetPlan>("/tibi/move_base/NavfnROS/make_plan");