update to use non deprecated pluginlib macro
This commit is contained in:
parent
d34cd5eda8
commit
08c7c12cff
@ -71,4 +71,4 @@ pcl_ros::BoundaryEstimation::computePublish (const PointCloudInConstPtr &cloud,
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::BoundaryEstimation BoundaryEstimation;
|
typedef pcl_ros::BoundaryEstimation BoundaryEstimation;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, BoundaryEstimation, BoundaryEstimation, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(BoundaryEstimation, nodelet::Nodelet)
|
||||||
|
|||||||
@ -72,5 +72,5 @@ pcl_ros::FPFHEstimation::computePublish (const PointCloudInConstPtr &cloud,
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::FPFHEstimation FPFHEstimation;
|
typedef pcl_ros::FPFHEstimation FPFHEstimation;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, FPFHEstimation, FPFHEstimation, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(FPFHEstimation, nodelet::Nodelet)
|
||||||
|
|
||||||
|
|||||||
@ -72,5 +72,5 @@ pcl_ros::FPFHEstimationOMP::computePublish (const PointCloudInConstPtr &cloud,
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::FPFHEstimationOMP FPFHEstimationOMP;
|
typedef pcl_ros::FPFHEstimationOMP FPFHEstimationOMP;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, FPFHEstimationOMP, FPFHEstimationOMP, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(FPFHEstimationOMP, nodelet::Nodelet)
|
||||||
|
|
||||||
|
|||||||
@ -70,5 +70,5 @@ pcl_ros::MomentInvariantsEstimation::computePublish (const PointCloudInConstPtr
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::MomentInvariantsEstimation MomentInvariantsEstimation;
|
typedef pcl_ros::MomentInvariantsEstimation MomentInvariantsEstimation;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, MomentInvariantsEstimation, MomentInvariantsEstimation, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(MomentInvariantsEstimation, nodelet::Nodelet)
|
||||||
|
|
||||||
|
|||||||
@ -70,5 +70,5 @@ pcl_ros::NormalEstimation::computePublish (const PointCloudInConstPtr &cloud,
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::NormalEstimation NormalEstimation;
|
typedef pcl_ros::NormalEstimation NormalEstimation;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, NormalEstimation, NormalEstimation, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(NormalEstimation, nodelet::Nodelet)
|
||||||
|
|
||||||
|
|||||||
@ -70,5 +70,5 @@ pcl_ros::NormalEstimationOMP::computePublish (const PointCloudInConstPtr &cloud,
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::NormalEstimationOMP NormalEstimationOMP;
|
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;
|
typedef pcl_ros::NormalEstimationTBB NormalEstimationTBB;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, NormalEstimationTBB, NormalEstimationTBB, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(NormalEstimationTBB, nodelet::Nodelet)
|
||||||
|
|
||||||
#endif // HAVE_TBB
|
#endif // HAVE_TBB
|
||||||
|
|
||||||
|
|||||||
@ -72,5 +72,5 @@ pcl_ros::PFHEstimation::computePublish (const PointCloudInConstPtr &cloud,
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::PFHEstimation PFHEstimation;
|
typedef pcl_ros::PFHEstimation PFHEstimation;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, PFHEstimation, PFHEstimation, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(PFHEstimation, nodelet::Nodelet)
|
||||||
|
|
||||||
|
|||||||
@ -72,5 +72,5 @@ pcl_ros::PrincipalCurvaturesEstimation::computePublish (const PointCloudInConstP
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::PrincipalCurvaturesEstimation PrincipalCurvaturesEstimation;
|
typedef pcl_ros::PrincipalCurvaturesEstimation PrincipalCurvaturesEstimation;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, PrincipalCurvaturesEstimation, PrincipalCurvaturesEstimation, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(PrincipalCurvaturesEstimation, nodelet::Nodelet)
|
||||||
|
|
||||||
|
|||||||
@ -71,5 +71,5 @@ pcl_ros::SHOTEstimation::computePublish (const PointCloudInConstPtr &cloud,
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::SHOTEstimation SHOTEstimation;
|
typedef pcl_ros::SHOTEstimation SHOTEstimation;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, SHOTEstimation, SHOTEstimation, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(SHOTEstimation, nodelet::Nodelet)
|
||||||
|
|
||||||
|
|||||||
@ -71,5 +71,5 @@ pcl_ros::SHOTEstimationOMP::computePublish (const PointCloudInConstPtr &cloud,
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::SHOTEstimationOMP SHOTEstimationOMP;
|
typedef pcl_ros::SHOTEstimationOMP SHOTEstimationOMP;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, SHOTEstimationOMP, SHOTEstimationOMP, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(SHOTEstimationOMP, nodelet::Nodelet)
|
||||||
|
|
||||||
|
|||||||
@ -72,5 +72,5 @@ pcl_ros::VFHEstimation::computePublish (const PointCloudInConstPtr &cloud,
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::VFHEstimation VFHEstimation;
|
typedef pcl_ros::VFHEstimation VFHEstimation;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, VFHEstimation, VFHEstimation, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(VFHEstimation, nodelet::Nodelet)
|
||||||
|
|
||||||
|
|||||||
@ -248,5 +248,5 @@ pcl_ros::EuclideanClusterExtraction::input_indices_callback (
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::EuclideanClusterExtraction EuclideanClusterExtraction;
|
typedef pcl_ros::EuclideanClusterExtraction EuclideanClusterExtraction;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, EuclideanClusterExtraction, EuclideanClusterExtraction, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(EuclideanClusterExtraction, nodelet::Nodelet)
|
||||||
|
|
||||||
|
|||||||
@ -216,5 +216,5 @@ pcl_ros::ExtractPolygonalPrismData::input_hull_indices_callback (
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::ExtractPolygonalPrismData ExtractPolygonalPrismData;
|
typedef pcl_ros::ExtractPolygonalPrismData ExtractPolygonalPrismData;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, ExtractPolygonalPrismData, ExtractPolygonalPrismData, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(ExtractPolygonalPrismData, nodelet::Nodelet)
|
||||||
|
|
||||||
|
|||||||
@ -691,6 +691,6 @@ pcl_ros::SACSegmentationFromNormals::input_normals_indices_callback (
|
|||||||
|
|
||||||
typedef pcl_ros::SACSegmentation SACSegmentation;
|
typedef pcl_ros::SACSegmentation SACSegmentation;
|
||||||
typedef pcl_ros::SACSegmentationFromNormals SACSegmentationFromNormals;
|
typedef pcl_ros::SACSegmentationFromNormals SACSegmentationFromNormals;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, SACSegmentation, SACSegmentation, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(SACSegmentation, nodelet::Nodelet)
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, SACSegmentationFromNormals, SACSegmentationFromNormals, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(SACSegmentationFromNormals, nodelet::Nodelet)
|
||||||
|
|
||||||
|
|||||||
@ -139,5 +139,5 @@ pcl_ros::SegmentDifferences::input_target_callback (const PointCloudConstPtr &cl
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::SegmentDifferences SegmentDifferences;
|
typedef pcl_ros::SegmentDifferences SegmentDifferences;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, SegmentDifferences, SegmentDifferences, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(SegmentDifferences, nodelet::Nodelet)
|
||||||
|
|
||||||
|
|||||||
@ -199,5 +199,5 @@ void
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::ConvexHull2D ConvexHull2D;
|
typedef pcl_ros::ConvexHull2D ConvexHull2D;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, ConvexHull2D, ConvexHull2D, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(ConvexHull2D, nodelet::Nodelet)
|
||||||
|
|
||||||
|
|||||||
@ -230,4 +230,4 @@ pcl_ros::MovingLeastSquares::config_callback (MLSConfig &config, uint32_t level)
|
|||||||
}
|
}
|
||||||
|
|
||||||
typedef pcl_ros::MovingLeastSquares MovingLeastSquares;
|
typedef pcl_ros::MovingLeastSquares MovingLeastSquares;
|
||||||
PLUGINLIB_DECLARE_CLASS (pcl, MovingLeastSquares, MovingLeastSquares, nodelet::Nodelet);
|
PLUGINLIB_EXPORT_CLASS(MovingLeastSquares, nodelet::Nodelet)
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user