Skip to content
Snippets Groups Projects
Commit 117aa35a authored by Fernando Herrero's avatar Fernando Herrero
Browse files

Merge branch 'melodic_migration' into 'master'

Changed the macro used to create new plugins.

See merge request !1
parents 2d22085c 461b81ce
No related branches found
No related tags found
1 merge request!1Changed the macro used to create new plugins.
...@@ -151,10 +151,10 @@ void *AveragePointCloudAlgNodelet::spin_thread(void *param) ...@@ -151,10 +151,10 @@ void *AveragePointCloudAlgNodelet::spin_thread(void *param)
{ {
AveragePointCloudAlgNodelet *nodelet=(AveragePointCloudAlgNodelet *)param; AveragePointCloudAlgNodelet *nodelet=(AveragePointCloudAlgNodelet *)param;
nodelet->node->spin(); nodelet->node->nodelet_spin();
pthread_exit(NULL); pthread_exit(NULL);
} }
// parameters are: package, class name, class type, base class type // 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);
...@@ -3,4 +3,4 @@ ...@@ -3,4 +3,4 @@
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
typedef nodelet_topic_tools::NodeletThrottle<sensor_msgs::PointCloud2> NodeletThrottlePC; 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);
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment