From eb6334027ebeb7730380ab63e4d7161f85cdf872 Mon Sep 17 00:00:00 2001
From: Ely Repiso Polo <erepiso@iri.upc.edu>
Date: Fri, 16 Jul 2021 18:57:26 +0000
Subject: [PATCH] algo que cambie y no subi

---
 launch/people_simulation.launch    |  2 +-
 src/people_simulation_alg_node.cpp | 11 +++++++----
 2 files changed, 8 insertions(+), 5 deletions(-)

diff --git a/launch/people_simulation.launch b/launch/people_simulation.launch
index 3ac3af2..71314be 100644
--- a/launch/people_simulation.launch
+++ b/launch/people_simulation.launch
@@ -14,7 +14,7 @@
       <!-- TODO change map with arg -->
       <remap from="~tracks"        to="/$(optenv ROBOT tibi)/tracks"/>
       <remap from="~tracksMarkers" to="/$(optenv ROBOT tibi)/tracksMarkers"/> 
-      <remap from="~init_simulations" to="/init_simulations"/> 
+      <remap from="~init_simulations" to="/$(optenv ROBOT tibi)/init_simulations"/> 
     </node>
 
 </launch>
diff --git a/src/people_simulation_alg_node.cpp b/src/people_simulation_alg_node.cpp
index 05b5429..d0da545 100644
--- a/src/people_simulation_alg_node.cpp
+++ b/src/people_simulation_alg_node.cpp
@@ -2,11 +2,12 @@
 
 PeopleSimulationAlgNode::PeopleSimulationAlgNode(void) :
   algorithm_base::IriBaseAlgorithm<PeopleSimulationAlgorithm>(),
-  n_persons_(0), simulation_mode_( PeopleSimulationAlgNode::Normal ),
+  n_persons_(10), simulation_mode_( PeopleSimulationAlgNode::Normal ),
   tf2_listener_(tf2_buffer),
   tf_(NULL)
  // tf2_listener_(ros::Duration(10.f))
 {
+	ROS_INFO(" approaching Init node. PeopleSimulationAlgNode");
   //init class attributes if necessary
   //this->loop_rate_ = 10;//in [Hz] Es de ubuntu 14.04
   setRate(10);//ROS_INFO("PeopleSimulationAlgNode::init_node");
@@ -21,12 +22,13 @@ PeopleSimulationAlgNode::PeopleSimulationAlgNode(void) :
   // [init clients]
   
   // [init action servers]
-    // [init services] => My cervice reset cscene sim, persons to initial pose
+    // [init services] => My service reset cscene sim, persons to initial pose
   this->init_simulations_server_ = this->public_node_handle_.advertiseService("init_simulations", &PeopleSimulationAlgNode::init_simulationsCallback, this);
 
   // [init action clients]
   
   init_sim();
+  ROS_INFO(" approaching Fin init node. PeopleSimulationAlgNode");
 }
 
 PeopleSimulationAlgNode::~PeopleSimulationAlgNode(void)
@@ -37,6 +39,7 @@ PeopleSimulationAlgNode::~PeopleSimulationAlgNode(void)
 
 void PeopleSimulationAlgNode::init_sim()
 {
+	 ROS_INFO(" approaching init init_sim(). PeopleSimulationAlgNode");
   scene_.set_dt( 0.1 );
 	//this->public_node_handle_.getParam("simulation_mode", simulation_mode_);
   this->public_node_handle_.getParam("number_persons", n_persons_);
@@ -96,12 +99,12 @@ void PeopleSimulationAlgNode::init_sim()
 	id_marker_.color.r = 0.0;
 	id_marker_.color.g = 0.0;
 	id_marker_.color.b = 0.0;
-
+	 ROS_INFO(" approaching Fin init_sim(). PeopleSimulationAlgNode");
 }
 
 void PeopleSimulationAlgNode::mainNodeThread(void)
 {
-ROS_INFO(" PeopleSimulationAlgNode::mainNodeThread !!!");
+ROS_INFO("approaching PeopleSimulationAlgNode::mainNodeThread !!!");
 
 //ros::init(argc, argv, "init_simulations");
 // ros::NodeHandle nh("~");
-- 
GitLab