diff --git a/pcl_ros/src/pcl_ros/filters/extract_indices.cpp b/pcl_ros/src/pcl_ros/filters/extract_indices.cpp index 2d596cd9..98419b09 100644 --- a/pcl_ros/src/pcl_ros/filters/extract_indices.cpp +++ b/pcl_ros/src/pcl_ros/filters/extract_indices.cpp @@ -66,5 +66,5 @@ pcl_ros::ExtractIndices::config_callback (pcl_ros::ExtractIndicesConfig &config, } typedef pcl_ros::ExtractIndices ExtractIndices; -PLUGINLIB_DECLARE_CLASS (pcl, ExtractIndices, ExtractIndices, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(ExtractIndices,nodelet::Nodelet); diff --git a/pcl_ros/src/pcl_ros/filters/features/boundary.cpp b/pcl_ros/src/pcl_ros/filters/features/boundary.cpp index 0e17c5fd..d90ac374 100644 --- a/pcl_ros/src/pcl_ros/filters/features/boundary.cpp +++ b/pcl_ros/src/pcl_ros/filters/features/boundary.cpp @@ -74,4 +74,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/filters/features/fpfh.cpp b/pcl_ros/src/pcl_ros/filters/features/fpfh.cpp index 7782fde9..c7f98f1d 100644 --- a/pcl_ros/src/pcl_ros/filters/features/fpfh.cpp +++ b/pcl_ros/src/pcl_ros/filters/features/fpfh.cpp @@ -75,5 +75,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/filters/features/fpfh_omp.cpp b/pcl_ros/src/pcl_ros/filters/features/fpfh_omp.cpp index 51880a9f..57c508c0 100644 --- a/pcl_ros/src/pcl_ros/filters/features/fpfh_omp.cpp +++ b/pcl_ros/src/pcl_ros/filters/features/fpfh_omp.cpp @@ -75,5 +75,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/filters/features/moment_invariants.cpp b/pcl_ros/src/pcl_ros/filters/features/moment_invariants.cpp index 85bd209a..0d1c039a 100644 --- a/pcl_ros/src/pcl_ros/filters/features/moment_invariants.cpp +++ b/pcl_ros/src/pcl_ros/filters/features/moment_invariants.cpp @@ -73,5 +73,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/filters/features/normal_3d.cpp b/pcl_ros/src/pcl_ros/filters/features/normal_3d.cpp index a512c41f..fbc81abc 100644 --- a/pcl_ros/src/pcl_ros/filters/features/normal_3d.cpp +++ b/pcl_ros/src/pcl_ros/filters/features/normal_3d.cpp @@ -73,5 +73,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/filters/features/normal_3d_omp.cpp b/pcl_ros/src/pcl_ros/filters/features/normal_3d_omp.cpp index e53fe9c7..0a257afa 100644 --- a/pcl_ros/src/pcl_ros/filters/features/normal_3d_omp.cpp +++ b/pcl_ros/src/pcl_ros/filters/features/normal_3d_omp.cpp @@ -73,5 +73,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/filters/features/normal_3d_tbb.cpp b/pcl_ros/src/pcl_ros/filters/features/normal_3d_tbb.cpp index d6636f73..330e2de7 100644 --- a/pcl_ros/src/pcl_ros/filters/features/normal_3d_tbb.cpp +++ b/pcl_ros/src/pcl_ros/filters/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/filters/features/pfh.cpp b/pcl_ros/src/pcl_ros/filters/features/pfh.cpp index f40e0bab..b8e3d8d2 100644 --- a/pcl_ros/src/pcl_ros/filters/features/pfh.cpp +++ b/pcl_ros/src/pcl_ros/filters/features/pfh.cpp @@ -75,5 +75,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/filters/features/principal_curvatures.cpp b/pcl_ros/src/pcl_ros/filters/features/principal_curvatures.cpp index d6431160..5e8c10f7 100644 --- a/pcl_ros/src/pcl_ros/filters/features/principal_curvatures.cpp +++ b/pcl_ros/src/pcl_ros/filters/features/principal_curvatures.cpp @@ -75,5 +75,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/filters/features/vfh.cpp b/pcl_ros/src/pcl_ros/filters/features/vfh.cpp index f13028e3..351a8af7 100644 --- a/pcl_ros/src/pcl_ros/filters/features/vfh.cpp +++ b/pcl_ros/src/pcl_ros/filters/features/vfh.cpp @@ -75,5 +75,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/filters/filter.cpp b/pcl_ros/src/pcl_ros/filters/filter.cpp index 9fcf844c..6257301a 100644 --- a/pcl_ros/src/pcl_ros/filters/filter.cpp +++ b/pcl_ros/src/pcl_ros/filters/filter.cpp @@ -55,8 +55,8 @@ //#include "statistical_outlier_removal.cpp" //#include "voxel_grid.cpp" -/*//PLUGINLIB_DECLARE_CLASS (pcl, PixelGrid, PixelGrid, nodelet::Nodelet); -//PLUGINLIB_DECLARE_CLASS (pcl, FilterDimension, FilterDimension, nodelet::Nodelet); +/*//PLUGINLIB_EXPORT_CLASS(PixelGrid,nodelet::Nodelet); +//PLUGINLIB_EXPORT_CLASS(FilterDimension,nodelet::Nodelet); */ ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/pcl_ros/src/pcl_ros/filters/passthrough.cpp b/pcl_ros/src/pcl_ros/filters/passthrough.cpp index e4f54f4b..e0de5af3 100644 --- a/pcl_ros/src/pcl_ros/filters/passthrough.cpp +++ b/pcl_ros/src/pcl_ros/filters/passthrough.cpp @@ -116,5 +116,5 @@ pcl_ros::PassThrough::config_callback (pcl_ros::FilterConfig &config, uint32_t l } typedef pcl_ros::PassThrough PassThrough; -PLUGINLIB_DECLARE_CLASS (pcl, PassThrough, PassThrough, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(PassThrough,nodelet::Nodelet); diff --git a/pcl_ros/src/pcl_ros/filters/project_inliers.cpp b/pcl_ros/src/pcl_ros/filters/project_inliers.cpp index f498ba65..77349c46 100644 --- a/pcl_ros/src/pcl_ros/filters/project_inliers.cpp +++ b/pcl_ros/src/pcl_ros/filters/project_inliers.cpp @@ -140,5 +140,5 @@ pcl_ros::ProjectInliers::input_indices_model_callback (const PointCloud2::ConstP } typedef pcl_ros::ProjectInliers ProjectInliers; -PLUGINLIB_DECLARE_CLASS (pcl, ProjectInliers, ProjectInliers, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(ProjectInliers,nodelet::Nodelet); diff --git a/pcl_ros/src/pcl_ros/filters/radius_outlier_removal.cpp b/pcl_ros/src/pcl_ros/filters/radius_outlier_removal.cpp index 6aaf2fbb..da965c69 100644 --- a/pcl_ros/src/pcl_ros/filters/radius_outlier_removal.cpp +++ b/pcl_ros/src/pcl_ros/filters/radius_outlier_removal.cpp @@ -39,5 +39,5 @@ #include "pcl_ros/filters/radius_outlier_removal.h" typedef pcl_ros::RadiusOutlierRemoval RadiusOutlierRemoval; -PLUGINLIB_DECLARE_CLASS (pcl, RadiusOutlierRemoval, RadiusOutlierRemoval, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(RadiusOutlierRemoval,nodelet::Nodelet); diff --git a/pcl_ros/src/pcl_ros/filters/statistical_outlier_removal.cpp b/pcl_ros/src/pcl_ros/filters/statistical_outlier_removal.cpp index 74288f56..16535b7f 100644 --- a/pcl_ros/src/pcl_ros/filters/statistical_outlier_removal.cpp +++ b/pcl_ros/src/pcl_ros/filters/statistical_outlier_removal.cpp @@ -77,5 +77,5 @@ pcl_ros::StatisticalOutlierRemoval::config_callback (pcl_ros::StatisticalOutlier } typedef pcl_ros::StatisticalOutlierRemoval StatisticalOutlierRemoval; -PLUGINLIB_DECLARE_CLASS (pcl, StatisticalOutlierRemoval, StatisticalOutlierRemoval, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(StatisticalOutlierRemoval,nodelet::Nodelet); diff --git a/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp b/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp index 55181f75..87c6ea43 100644 --- a/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp +++ b/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp @@ -120,5 +120,5 @@ pcl_ros::VoxelGrid::config_callback (pcl_ros::VoxelGridConfig &config, uint32_t } typedef pcl_ros::VoxelGrid VoxelGrid; -PLUGINLIB_DECLARE_CLASS (pcl, VoxelGrid, VoxelGrid, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(VoxelGrid,nodelet::Nodelet); diff --git a/pcl_ros/src/pcl_ros/io/bag_io.cpp b/pcl_ros/src/pcl_ros/io/bag_io.cpp index cc370da9..a17edd14 100644 --- a/pcl_ros/src/pcl_ros/io/bag_io.cpp +++ b/pcl_ros/src/pcl_ros/io/bag_io.cpp @@ -109,5 +109,5 @@ pcl_ros::BAGReader::onInit () } typedef pcl_ros::BAGReader BAGReader; -PLUGINLIB_DECLARE_CLASS (pcl, BAGReader, BAGReader, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(BAGReader,nodelet::Nodelet); diff --git a/pcl_ros/src/pcl_ros/io/concatenate_data.cpp b/pcl_ros/src/pcl_ros/io/concatenate_data.cpp index 3055f4cd..e4ccba9c 100644 --- a/pcl_ros/src/pcl_ros/io/concatenate_data.cpp +++ b/pcl_ros/src/pcl_ros/io/concatenate_data.cpp @@ -253,5 +253,5 @@ pcl_ros::PointCloudConcatenateDataSynchronizer::input ( } typedef pcl_ros::PointCloudConcatenateDataSynchronizer PointCloudConcatenateDataSynchronizer; -PLUGINLIB_DECLARE_CLASS (pcl, PointCloudConcatenateDataSynchronizer, PointCloudConcatenateDataSynchronizer, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(PointCloudConcatenateDataSynchronizer,nodelet::Nodelet); diff --git a/pcl_ros/src/pcl_ros/io/concatenate_fields.cpp b/pcl_ros/src/pcl_ros/io/concatenate_fields.cpp index e9a907c5..52b17edd 100644 --- a/pcl_ros/src/pcl_ros/io/concatenate_fields.cpp +++ b/pcl_ros/src/pcl_ros/io/concatenate_fields.cpp @@ -148,5 +148,5 @@ pcl_ros::PointCloudConcatenateFieldsSynchronizer::input_callback (const PointClo } typedef pcl_ros::PointCloudConcatenateFieldsSynchronizer PointCloudConcatenateFieldsSynchronizer; -PLUGINLIB_DECLARE_CLASS (pcl, PointCloudConcatenateFieldsSynchronizer, PointCloudConcatenateFieldsSynchronizer, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(PointCloudConcatenateFieldsSynchronizer,nodelet::Nodelet); diff --git a/pcl_ros/src/pcl_ros/io/io.cpp b/pcl_ros/src/pcl_ros/io/io.cpp index 41139a6b..c9887581 100644 --- a/pcl_ros/src/pcl_ros/io/io.cpp +++ b/pcl_ros/src/pcl_ros/io/io.cpp @@ -51,7 +51,7 @@ typedef nodelet::NodeletDEMUX NodeletDEMUX; //#include "concatenate_fields.cpp" //#include "concatenate_data.cpp" -PLUGINLIB_DECLARE_CLASS (pcl, NodeletMUX, NodeletMUX, nodelet::Nodelet); -PLUGINLIB_DECLARE_CLASS (pcl, NodeletDEMUX, NodeletDEMUX, nodelet::Nodelet); -//PLUGINLIB_DECLARE_CLASS (pcl, NodeletDEMUX_ROS, NodeletDEMUX_ROS, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(NodeletMUX,nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(NodeletDEMUX,nodelet::Nodelet); +//PLUGINLIB_EXPORT_CLASS(NodeletDEMUX_ROS,nodelet::Nodelet); diff --git a/pcl_ros/src/pcl_ros/io/pcd_io.cpp b/pcl_ros/src/pcl_ros/io/pcd_io.cpp index 5d4e24e4..026c0d20 100644 --- a/pcl_ros/src/pcl_ros/io/pcd_io.cpp +++ b/pcl_ros/src/pcl_ros/io/pcd_io.cpp @@ -170,6 +170,6 @@ pcl_ros::PCDWriter::input_callback (const PointCloud2ConstPtr &cloud) typedef pcl_ros::PCDReader PCDReader; typedef pcl_ros::PCDWriter PCDWriter; -PLUGINLIB_DECLARE_CLASS (pcl, PCDReader, PCDReader, nodelet::Nodelet); -PLUGINLIB_DECLARE_CLASS (pcl, PCDWriter, PCDWriter, nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(PCDReader,nodelet::Nodelet); +PLUGINLIB_EXPORT_CLASS(PCDWriter,nodelet::Nodelet);