diff --git a/pcl_ros/src/pcl_ros/features/boundary.cpp b/pcl_ros/src/pcl_ros/features/boundary.cpp index 0b6a8c36..9334641a 100644 --- a/pcl_ros/src/pcl_ros/features/boundary.cpp +++ b/pcl_ros/src/pcl_ros/features/boundary.cpp @@ -71,4 +71,4 @@ pcl_ros::BoundaryEstimation::computePublish (const PointCloudInConstPtr &cloud, } typedef pcl_ros::BoundaryEstimation BoundaryEstimation; -PLUGINLIB_DECLARE_CLASS (pcl, BoundaryEstimation, BoundaryEstimation, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(BoundaryEstimation, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/features/fpfh.cpp b/pcl_ros/src/pcl_ros/features/fpfh.cpp index 081696b1..3f698aad 100644 --- a/pcl_ros/src/pcl_ros/features/fpfh.cpp +++ b/pcl_ros/src/pcl_ros/features/fpfh.cpp @@ -72,5 +72,5 @@ pcl_ros::FPFHEstimation::computePublish (const PointCloudInConstPtr &cloud, } typedef pcl_ros::FPFHEstimation FPFHEstimation; -PLUGINLIB_DECLARE_CLASS (pcl, FPFHEstimation, FPFHEstimation, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(FPFHEstimation, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/features/fpfh_omp.cpp b/pcl_ros/src/pcl_ros/features/fpfh_omp.cpp index 09a573f6..58dd911f 100644 --- a/pcl_ros/src/pcl_ros/features/fpfh_omp.cpp +++ b/pcl_ros/src/pcl_ros/features/fpfh_omp.cpp @@ -72,5 +72,5 @@ pcl_ros::FPFHEstimationOMP::computePublish (const PointCloudInConstPtr &cloud, } typedef pcl_ros::FPFHEstimationOMP FPFHEstimationOMP; -PLUGINLIB_DECLARE_CLASS (pcl, FPFHEstimationOMP, FPFHEstimationOMP, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(FPFHEstimationOMP, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/features/moment_invariants.cpp b/pcl_ros/src/pcl_ros/features/moment_invariants.cpp index 49838204..d0ec3441 100644 --- a/pcl_ros/src/pcl_ros/features/moment_invariants.cpp +++ b/pcl_ros/src/pcl_ros/features/moment_invariants.cpp @@ -70,5 +70,5 @@ pcl_ros::MomentInvariantsEstimation::computePublish (const PointCloudInConstPtr } typedef pcl_ros::MomentInvariantsEstimation MomentInvariantsEstimation; -PLUGINLIB_DECLARE_CLASS (pcl, MomentInvariantsEstimation, MomentInvariantsEstimation, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(MomentInvariantsEstimation, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/features/normal_3d.cpp b/pcl_ros/src/pcl_ros/features/normal_3d.cpp index 31b4dc70..9e700f78 100644 --- a/pcl_ros/src/pcl_ros/features/normal_3d.cpp +++ b/pcl_ros/src/pcl_ros/features/normal_3d.cpp @@ -70,5 +70,5 @@ pcl_ros::NormalEstimation::computePublish (const PointCloudInConstPtr &cloud, } typedef pcl_ros::NormalEstimation NormalEstimation; -PLUGINLIB_DECLARE_CLASS (pcl, NormalEstimation, NormalEstimation, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(NormalEstimation, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/features/normal_3d_omp.cpp b/pcl_ros/src/pcl_ros/features/normal_3d_omp.cpp index 06c1b31a..a741c052 100644 --- a/pcl_ros/src/pcl_ros/features/normal_3d_omp.cpp +++ b/pcl_ros/src/pcl_ros/features/normal_3d_omp.cpp @@ -70,5 +70,5 @@ pcl_ros::NormalEstimationOMP::computePublish (const PointCloudInConstPtr &cloud, } typedef pcl_ros::NormalEstimationOMP NormalEstimationOMP; -PLUGINLIB_DECLARE_CLASS (pcl, NormalEstimationOMP, NormalEstimationOMP, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(NormalEstimationOMP, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/features/normal_3d_tbb.cpp b/pcl_ros/src/pcl_ros/features/normal_3d_tbb.cpp index d6636f73..a4a8581e 100644 --- a/pcl_ros/src/pcl_ros/features/normal_3d_tbb.cpp +++ b/pcl_ros/src/pcl_ros/features/normal_3d_tbb.cpp @@ -75,7 +75,7 @@ pcl_ros::NormalEstimationTBB::computePublish (const PointCloudInConstPtr &cloud, } typedef pcl_ros::NormalEstimationTBB NormalEstimationTBB; -PLUGINLIB_DECLARE_CLASS (pcl, NormalEstimationTBB, NormalEstimationTBB, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(NormalEstimationTBB, nodelet::Nodelet) #endif // HAVE_TBB diff --git a/pcl_ros/src/pcl_ros/features/pfh.cpp b/pcl_ros/src/pcl_ros/features/pfh.cpp index 94b97c88..38b4d19c 100644 --- a/pcl_ros/src/pcl_ros/features/pfh.cpp +++ b/pcl_ros/src/pcl_ros/features/pfh.cpp @@ -72,5 +72,5 @@ pcl_ros::PFHEstimation::computePublish (const PointCloudInConstPtr &cloud, } typedef pcl_ros::PFHEstimation PFHEstimation; -PLUGINLIB_DECLARE_CLASS (pcl, PFHEstimation, PFHEstimation, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(PFHEstimation, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/features/principal_curvatures.cpp b/pcl_ros/src/pcl_ros/features/principal_curvatures.cpp index 471549ab..113124dc 100644 --- a/pcl_ros/src/pcl_ros/features/principal_curvatures.cpp +++ b/pcl_ros/src/pcl_ros/features/principal_curvatures.cpp @@ -72,5 +72,5 @@ pcl_ros::PrincipalCurvaturesEstimation::computePublish (const PointCloudInConstP } typedef pcl_ros::PrincipalCurvaturesEstimation PrincipalCurvaturesEstimation; -PLUGINLIB_DECLARE_CLASS (pcl, PrincipalCurvaturesEstimation, PrincipalCurvaturesEstimation, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(PrincipalCurvaturesEstimation, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/features/shot.cpp b/pcl_ros/src/pcl_ros/features/shot.cpp index 82122c8d..d051ab0f 100644 --- a/pcl_ros/src/pcl_ros/features/shot.cpp +++ b/pcl_ros/src/pcl_ros/features/shot.cpp @@ -71,5 +71,5 @@ pcl_ros::SHOTEstimation::computePublish (const PointCloudInConstPtr &cloud, } typedef pcl_ros::SHOTEstimation SHOTEstimation; -PLUGINLIB_DECLARE_CLASS (pcl, SHOTEstimation, SHOTEstimation, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(SHOTEstimation, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/features/shot_omp.cpp b/pcl_ros/src/pcl_ros/features/shot_omp.cpp index 887e4b5d..1ac1b065 100644 --- a/pcl_ros/src/pcl_ros/features/shot_omp.cpp +++ b/pcl_ros/src/pcl_ros/features/shot_omp.cpp @@ -71,5 +71,5 @@ pcl_ros::SHOTEstimationOMP::computePublish (const PointCloudInConstPtr &cloud, } typedef pcl_ros::SHOTEstimationOMP SHOTEstimationOMP; -PLUGINLIB_DECLARE_CLASS (pcl, SHOTEstimationOMP, SHOTEstimationOMP, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(SHOTEstimationOMP, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/features/vfh.cpp b/pcl_ros/src/pcl_ros/features/vfh.cpp index 86ddc137..9d0fe361 100644 --- a/pcl_ros/src/pcl_ros/features/vfh.cpp +++ b/pcl_ros/src/pcl_ros/features/vfh.cpp @@ -72,5 +72,5 @@ pcl_ros::VFHEstimation::computePublish (const PointCloudInConstPtr &cloud, } typedef pcl_ros::VFHEstimation VFHEstimation; -PLUGINLIB_DECLARE_CLASS (pcl, VFHEstimation, VFHEstimation, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(VFHEstimation, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/segmentation/extract_clusters.cpp b/pcl_ros/src/pcl_ros/segmentation/extract_clusters.cpp index ce23f4b5..fdf06b2d 100644 --- a/pcl_ros/src/pcl_ros/segmentation/extract_clusters.cpp +++ b/pcl_ros/src/pcl_ros/segmentation/extract_clusters.cpp @@ -248,5 +248,5 @@ pcl_ros::EuclideanClusterExtraction::input_indices_callback ( } typedef pcl_ros::EuclideanClusterExtraction EuclideanClusterExtraction; -PLUGINLIB_DECLARE_CLASS (pcl, EuclideanClusterExtraction, EuclideanClusterExtraction, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(EuclideanClusterExtraction, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/segmentation/extract_polygonal_prism_data.cpp b/pcl_ros/src/pcl_ros/segmentation/extract_polygonal_prism_data.cpp index 683a9ec0..1963b6e8 100644 --- a/pcl_ros/src/pcl_ros/segmentation/extract_polygonal_prism_data.cpp +++ b/pcl_ros/src/pcl_ros/segmentation/extract_polygonal_prism_data.cpp @@ -216,5 +216,5 @@ pcl_ros::ExtractPolygonalPrismData::input_hull_indices_callback ( } typedef pcl_ros::ExtractPolygonalPrismData ExtractPolygonalPrismData; -PLUGINLIB_DECLARE_CLASS (pcl, ExtractPolygonalPrismData, ExtractPolygonalPrismData, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(ExtractPolygonalPrismData, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/segmentation/sac_segmentation.cpp b/pcl_ros/src/pcl_ros/segmentation/sac_segmentation.cpp index f623d7c4..7dc0c60a 100644 --- a/pcl_ros/src/pcl_ros/segmentation/sac_segmentation.cpp +++ b/pcl_ros/src/pcl_ros/segmentation/sac_segmentation.cpp @@ -691,6 +691,6 @@ pcl_ros::SACSegmentationFromNormals::input_normals_indices_callback ( typedef pcl_ros::SACSegmentation SACSegmentation; typedef pcl_ros::SACSegmentationFromNormals SACSegmentationFromNormals; -PLUGINLIB_DECLARE_CLASS (pcl, SACSegmentation, SACSegmentation, nodelet::Nodelet); -PLUGINLIB_DECLARE_CLASS (pcl, SACSegmentationFromNormals, SACSegmentationFromNormals, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(SACSegmentation, nodelet::Nodelet) +PLUGINLIB_EXPORT_CLASS(SACSegmentationFromNormals, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/segmentation/segment_differences.cpp b/pcl_ros/src/pcl_ros/segmentation/segment_differences.cpp index 22a7482b..402b7790 100644 --- a/pcl_ros/src/pcl_ros/segmentation/segment_differences.cpp +++ b/pcl_ros/src/pcl_ros/segmentation/segment_differences.cpp @@ -139,5 +139,5 @@ pcl_ros::SegmentDifferences::input_target_callback (const PointCloudConstPtr &cl } typedef pcl_ros::SegmentDifferences SegmentDifferences; -PLUGINLIB_DECLARE_CLASS (pcl, SegmentDifferences, SegmentDifferences, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(SegmentDifferences, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/surface/convex_hull.cpp b/pcl_ros/src/pcl_ros/surface/convex_hull.cpp index fffaf568..a577881c 100644 --- a/pcl_ros/src/pcl_ros/surface/convex_hull.cpp +++ b/pcl_ros/src/pcl_ros/surface/convex_hull.cpp @@ -199,5 +199,5 @@ void } typedef pcl_ros::ConvexHull2D ConvexHull2D; -PLUGINLIB_DECLARE_CLASS (pcl, ConvexHull2D, ConvexHull2D, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(ConvexHull2D, nodelet::Nodelet) diff --git a/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp b/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp index 514c2f48..321f3e6a 100644 --- a/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp +++ b/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp @@ -230,4 +230,4 @@ pcl_ros::MovingLeastSquares::config_callback (MLSConfig &config, uint32_t level) } typedef pcl_ros::MovingLeastSquares MovingLeastSquares; -PLUGINLIB_DECLARE_CLASS (pcl, MovingLeastSquares, MovingLeastSquares, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(MovingLeastSquares, nodelet::Nodelet)