From 3a7e56e18b1c98c5a53c8245b1f4b9e8f8197c1a Mon Sep 17 00:00:00 2001
From: Sergi Hernandez Juan <shernand@iri.upc.edu>
Date: Thu, 6 Feb 2020 11:36:41 +0100
Subject: [PATCH] Used the public node handle instead of the private one.

---
 src/lidar_obstacle_detector_alg_node.cpp | 8 ++++----
 1 file changed, 4 insertions(+), 4 deletions(-)

diff --git a/src/lidar_obstacle_detector_alg_node.cpp b/src/lidar_obstacle_detector_alg_node.cpp
index 11bb545..794195b 100644
--- a/src/lidar_obstacle_detector_alg_node.cpp
+++ b/src/lidar_obstacle_detector_alg_node.cpp
@@ -12,12 +12,12 @@ LidarObstacleDetectorAlgNode::LidarObstacleDetectorAlgNode(const ros::NodeHandle
   //this->loop_rate_ = 2;//in [Hz]
 
   // [init publishers]
-  this->obstacles_img_publisher_ = this->private_node_handle_.advertise<sensor_msgs::Image>("obstacles_img/image_raw", 1);
-  this->scan_clearing_out_publisher_ = this->private_node_handle_.advertise<sensor_msgs::LaserScan>("scan_clearing_out", 1);
-  this->scan_out_publisher_ = this->private_node_handle_.advertise<sensor_msgs::LaserScan>("scan_out", 1);
+  this->obstacles_img_publisher_ = this->public_node_handle_.advertise<sensor_msgs::Image>("obstacles_img/image_raw", 1);
+  this->scan_clearing_out_publisher_ = this->public_node_handle_.advertise<sensor_msgs::LaserScan>("scan_clearing_out", 1);
+  this->scan_out_publisher_ = this->public_node_handle_.advertise<sensor_msgs::LaserScan>("scan_out", 1);
   
   // [init subscribers]
-  this->pointcloud_in_subscriber_ = this->private_node_handle_.subscribe("pointcloud_in", 1, &LidarObstacleDetectorAlgNode::pointcloud_in_callback, this);
+  this->pointcloud_in_subscriber_ = this->public_node_handle_.subscribe("pointcloud_in", 1, &LidarObstacleDetectorAlgNode::pointcloud_in_callback, this);
   pthread_mutex_init(&this->pointcloud_in_mutex_,NULL);
 
   this->scan_clearing_out_LaserScan_msg_.angle_min=-3.14159;
-- 
GitLab