From 1699f18f6cd147e2b078de06a67dc84baa6d68b7 Mon Sep 17 00:00:00 2001 From: Ely Repiso Polo <erepiso@iri.upc.edu> Date: Mon, 21 Jun 2021 16:14:07 +0000 Subject: [PATCH] corregido error por cambio en IribaseAlgorithm para ubuntu 18.04 y ROS-melodic; y corregido cambio mensajes simulacion de iri_perception_msgs a iri_nav_msgs --- include/people_simulation_alg_node.h | 6 +++--- src/people_simulation_alg_node.cpp | 5 +++-- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/include/people_simulation_alg_node.h b/include/people_simulation_alg_node.h index 653de2e..ba48585 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 1236a5d..269776c 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!"); -- GitLab