update pluginlib macro
This commit is contained in:
parent
8133001c65
commit
758f23264d
@ -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);
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -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
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -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);
|
||||
*/
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
@ -51,7 +51,7 @@ typedef nodelet::NodeletDEMUX<sensor_msgs::PointCloud2> 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);
|
||||
|
||||
|
||||
@ -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);
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user