diff --git a/src/lidar_obstacle_detector_alg_node.cpp b/src/lidar_obstacle_detector_alg_node.cpp index 11bb545934ef8a7f03ab20583f10a44c111ed77b..794195baaf9158f7db481219ec3ab4a50d6c11d2 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;