From 461b81ce35940ebe06ce0e9b821ca62a16727a0a Mon Sep 17 00:00:00 2001
From: Sergi Hernandez Juan <shernand@iri.upc.edu>
Date: Tue, 14 Jul 2020 17:38:57 +0200
Subject: [PATCH] Changed the macro used to create new plugins. Used the
 nodelet_spin() function in the nodelet.

---
 src/iri_average_point_cloud_alg_node.cpp | 4 ++--
 src/point_cloud_throttle_nodelet.cpp     | 2 +-
 2 files changed, 3 insertions(+), 3 deletions(-)

diff --git a/src/iri_average_point_cloud_alg_node.cpp b/src/iri_average_point_cloud_alg_node.cpp
index 4f121f3..b5f1a83 100644
--- a/src/iri_average_point_cloud_alg_node.cpp
+++ b/src/iri_average_point_cloud_alg_node.cpp
@@ -151,10 +151,10 @@ void *AveragePointCloudAlgNodelet::spin_thread(void *param)
 {
   AveragePointCloudAlgNodelet *nodelet=(AveragePointCloudAlgNodelet *)param;
 
-  nodelet->node->spin();
+  nodelet->node->nodelet_spin();
 
   pthread_exit(NULL);
 }
 
 // parameters are: package, class name, class type, base class type
-PLUGINLIB_DECLARE_CLASS(iri_average_point_cloud, AveragePointCloudAlgNodelet, AveragePointCloudAlgNodelet, nodelet::Nodelet);
+PLUGINLIB_EXPORT_CLASS(AveragePointCloudAlgNodelet, nodelet::Nodelet);
diff --git a/src/point_cloud_throttle_nodelet.cpp b/src/point_cloud_throttle_nodelet.cpp
index 256de24..f544cb0 100644
--- a/src/point_cloud_throttle_nodelet.cpp
+++ b/src/point_cloud_throttle_nodelet.cpp
@@ -3,4 +3,4 @@
 #include <pluginlib/class_list_macros.h>
 
 typedef nodelet_topic_tools::NodeletThrottle<sensor_msgs::PointCloud2> NodeletThrottlePC;
-PLUGINLIB_DECLARE_CLASS(iri_nav_average_point_cloud, NodeletThrottlePC, NodeletThrottlePC, nodelet::Nodelet);
+PLUGINLIB_EXPORT_CLASS(NodeletThrottlePC,nodelet::Nodelet);
-- 
GitLab