Rename headers from .h to .hpp (#296)

* Rename headers from .h to .hpp per ROS2 guidelines

This change is the result of the following command run from pcl_ros dir:

$ find -name *.h | xargs -I {} mv {} {}pp

Signed-off-by: Sean Kelly <sean@seankelly.dev>

* Update internal includes for the renamed headers

This change was the result of the following bash script:

$ find -name *.h -o -name *.cpp -o -name *.hpp | xargs -I {} sed -i 's/\(pcl_ros\/.*\)\(h\)\([">]\)$/\1\2pp\3/g' {}

Signed-off-by: Sean Kelly <sean@seankelly.dev>
This commit is contained in:
Sean Kelly 2020-08-06 14:13:01 -04:00 committed by GitHub
parent 21cf907c46
commit 0ac6810688
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
83 changed files with 94 additions and 94 deletions

View File

@ -41,7 +41,7 @@
#define EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET true #define EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET true
#include <pcl/features/boundary.h> #include <pcl/features/boundary.h>
#include "pcl_ros/features/feature.h" #include "pcl_ros/features/feature.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -42,12 +42,12 @@
#include <pcl/features/feature.h> #include <pcl/features/feature.h>
#include <pcl_msgs/PointIndices.h> #include <pcl_msgs/PointIndices.h>
#include "pcl_ros/pcl_nodelet.h" #include "pcl_ros/pcl_nodelet.hpp"
#include <message_filters/pass_through.h> #include <message_filters/pass_through.h>
// Dynamic reconfigure // Dynamic reconfigure
#include <dynamic_reconfigure/server.h> #include <dynamic_reconfigure/server.h>
#include "pcl_ros/FeatureConfig.h" #include "pcl_ros/FeatureConfig.hpp"
// PCL conversions // PCL conversions
#include <pcl_conversions/pcl_conversions.h> #include <pcl_conversions/pcl_conversions.h>

View File

@ -39,7 +39,7 @@
#define PCL_ROS_FPFH_H_ #define PCL_ROS_FPFH_H_
#include <pcl/features/fpfh.h> #include <pcl/features/fpfh.h>
#include "pcl_ros/features/pfh.h" #include "pcl_ros/features/pfh.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -39,7 +39,7 @@
#define PCL_ROS_FPFH_OMP_H_ #define PCL_ROS_FPFH_OMP_H_
#include <pcl/features/fpfh_omp.h> #include <pcl/features/fpfh_omp.h>
#include "pcl_ros/features/fpfh.h" #include "pcl_ros/features/fpfh.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -39,7 +39,7 @@
#define PCL_ROS_MOMENT_INVARIANTS_H_ #define PCL_ROS_MOMENT_INVARIANTS_H_
#include <pcl/features/moment_invariants.h> #include <pcl/features/moment_invariants.h>
#include "pcl_ros/features/feature.h" #include "pcl_ros/features/feature.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -39,7 +39,7 @@
#define PCL_ROS_NORMAL_3D_H_ #define PCL_ROS_NORMAL_3D_H_
#include <pcl/features/normal_3d.h> #include <pcl/features/normal_3d.h>
#include "pcl_ros/features/feature.h" #include "pcl_ros/features/feature.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -39,7 +39,7 @@
#define PCL_ROS_NORMAL_3D_OMP_H_ #define PCL_ROS_NORMAL_3D_OMP_H_
#include <pcl/features/normal_3d_omp.h> #include <pcl/features/normal_3d_omp.h>
#include "pcl_ros/features/normal_3d.h" #include "pcl_ros/features/normal_3d.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -38,11 +38,11 @@
#ifndef PCL_ROS_NORMAL_3D_TBB_H_ #ifndef PCL_ROS_NORMAL_3D_TBB_H_
#define PCL_ROS_NORMAL_3D_TBB_H_ #define PCL_ROS_NORMAL_3D_TBB_H_
//#include "pcl_ros/pcl_ros_config.h" //#include "pcl_ros/pcl_ros_config.hpp"
//#if defined(HAVE_TBB) //#if defined(HAVE_TBB)
#include <pcl/features/normal_3d_tbb.h> #include <pcl/features/normal_3d_tbb.h>
#include "pcl_ros/features/normal_3d.h" #include "pcl_ros/features/normal_3d.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -39,7 +39,7 @@
#define PCL_ROS_PFH_H_ #define PCL_ROS_PFH_H_
#include <pcl/features/pfh.h> #include <pcl/features/pfh.h>
#include "pcl_ros/features/feature.h" #include "pcl_ros/features/feature.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -40,7 +40,7 @@
#define EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET true #define EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET true
#include <pcl/features/principal_curvatures.h> #include <pcl/features/principal_curvatures.h>
#include "pcl_ros/features/feature.h" #include "pcl_ros/features/feature.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -38,7 +38,7 @@
#define PCL_ROS_SHOT_H_ #define PCL_ROS_SHOT_H_
#include <pcl/features/shot.h> #include <pcl/features/shot.h>
#include "pcl_ros/features/pfh.h" #include "pcl_ros/features/pfh.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -38,7 +38,7 @@
#define PCL_ROS_SHOT_OMP_H_ #define PCL_ROS_SHOT_OMP_H_
#include <pcl/features/shot_omp.h> #include <pcl/features/shot_omp.h>
#include "pcl_ros/features/shot.h" #include "pcl_ros/features/shot.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -39,7 +39,7 @@
#define PCL_ROS_FEATURES_VFH_H_ #define PCL_ROS_FEATURES_VFH_H_
#include <pcl/features/vfh.h> #include <pcl/features/vfh.h>
#include "pcl_ros/features/fpfh.h" #include "pcl_ros/features/fpfh.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -41,10 +41,10 @@
// PCL includes // PCL includes
#include <pcl/filters/crop_box.h> #include <pcl/filters/crop_box.h>
#include "pcl_ros/filters/filter.h" #include "pcl_ros/filters/filter.hpp"
// Dynamic reconfigure // Dynamic reconfigure
#include "pcl_ros/CropBoxConfig.h" #include "pcl_ros/CropBoxConfig.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -41,8 +41,8 @@
// PCL includes // PCL includes
#include <pcl/filters/extract_indices.h> #include <pcl/filters/extract_indices.h>
#include "pcl_ros/filters/filter.h" #include "pcl_ros/filters/filter.hpp"
#include "pcl_ros/ExtractIndicesConfig.h" #include "pcl_ros/ExtractIndicesConfig.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -40,11 +40,11 @@
// PCL includes // PCL includes
#include <pcl/filters/filter.h> #include <pcl/filters/filter.h>
#include "pcl_ros/pcl_nodelet.h" #include "pcl_ros/pcl_nodelet.hpp"
// Dynamic reconfigure // Dynamic reconfigure
#include <dynamic_reconfigure/server.h> #include <dynamic_reconfigure/server.h>
#include "pcl_ros/FilterConfig.h" #include "pcl_ros/FilterConfig.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -40,7 +40,7 @@
// PCL includes // PCL includes
#include <pcl/filters/passthrough.h> #include <pcl/filters/passthrough.h>
#include "pcl_ros/filters/filter.h" #include "pcl_ros/filters/filter.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -40,7 +40,7 @@
// PCL includes // PCL includes
#include <pcl/filters/project_inliers.h> #include <pcl/filters/project_inliers.h>
#include "pcl_ros/filters/filter.h" #include "pcl_ros/filters/filter.hpp"
#include <message_filters/subscriber.h> #include <message_filters/subscriber.h>

View File

@ -40,10 +40,10 @@
// PCL includes // PCL includes
#include <pcl/filters/radius_outlier_removal.h> #include <pcl/filters/radius_outlier_removal.h>
#include "pcl_ros/filters/filter.h" #include "pcl_ros/filters/filter.hpp"
// Dynamic reconfigure // Dynamic reconfigure
#include "pcl_ros/RadiusOutlierRemovalConfig.h" #include "pcl_ros/RadiusOutlierRemovalConfig.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -40,10 +40,10 @@
// PCL includes // PCL includes
#include <pcl/filters/statistical_outlier_removal.h> #include <pcl/filters/statistical_outlier_removal.h>
#include "pcl_ros/filters/filter.h" #include "pcl_ros/filters/filter.hpp"
// Dynamic reconfigure // Dynamic reconfigure
#include "pcl_ros/StatisticalOutlierRemovalConfig.h" #include "pcl_ros/StatisticalOutlierRemovalConfig.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -40,10 +40,10 @@
// PCL includes // PCL includes
#include <pcl/filters/voxel_grid.h> #include <pcl/filters/voxel_grid.h>
#include "pcl_ros/filters/filter.h" #include "pcl_ros/filters/filter.hpp"
// Dynamic reconfigure // Dynamic reconfigure
#include "pcl_ros/VoxelGridConfig.h" #include "pcl_ros/VoxelGridConfig.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -38,7 +38,7 @@
#define pcl_ros_IMPL_TRANSFORMS_H_ #define pcl_ros_IMPL_TRANSFORMS_H_
#include <pcl_conversions/pcl_conversions.h> #include <pcl_conversions/pcl_conversions.h>
#include "pcl_ros/transforms.h" #include "pcl_ros/transforms.hpp"
using pcl_conversions::fromPCL; using pcl_conversions::fromPCL;
using pcl_conversions::toPCL; using pcl_conversions::toPCL;

View File

@ -38,7 +38,7 @@
#ifndef PCL_ROS_IO_BAG_IO_H_ #ifndef PCL_ROS_IO_BAG_IO_H_
#define PCL_ROS_IO_BAG_IO_H_ #define PCL_ROS_IO_BAG_IO_H_
#include <pcl_ros/pcl_nodelet.h> #include <pcl_ros/pcl_nodelet.hpp>
#include <sensor_msgs/PointCloud2.h> #include <sensor_msgs/PointCloud2.h>
#include <rosbag/bag.h> #include <rosbag/bag.h>
#include <rosbag/view.h> #include <rosbag/view.h>

View File

@ -39,7 +39,7 @@
#define PCL_ROS_IO_PCD_IO_H_ #define PCL_ROS_IO_PCD_IO_H_
#include <pcl/io/pcd_io.h> #include <pcl/io/pcd_io.h>
#include "pcl_ros/pcl_nodelet.h" #include "pcl_ros/pcl_nodelet.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -51,7 +51,7 @@
#include <pcl/pcl_base.h> #include <pcl/pcl_base.h>
#include <pcl/point_types.h> #include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h> #include <pcl_conversions/pcl_conversions.h>
#include "pcl_ros/point_cloud.h" #include "pcl_ros/point_cloud.hpp"
// ROS Nodelet includes // ROS Nodelet includes
#include <nodelet_topic_tools/nodelet_lazy.h> #include <nodelet_topic_tools/nodelet_lazy.h>
#include <message_filters/subscriber.h> #include <message_filters/subscriber.h>

View File

@ -39,11 +39,11 @@
#define PCL_ROS_EXTRACT_CLUSTERS_H_ #define PCL_ROS_EXTRACT_CLUSTERS_H_
#include <pcl/segmentation/extract_clusters.h> #include <pcl/segmentation/extract_clusters.h>
#include "pcl_ros/pcl_nodelet.h" #include "pcl_ros/pcl_nodelet.hpp"
// Dynamic reconfigure // Dynamic reconfigure
#include <dynamic_reconfigure/server.h> #include <dynamic_reconfigure/server.h>
#include "pcl_ros/EuclideanClusterExtractionConfig.h" #include "pcl_ros/EuclideanClusterExtractionConfig.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -38,7 +38,7 @@
#ifndef PCL_ROS_EXTRACT_POLYGONAL_PRISM_DATA_H_ #ifndef PCL_ROS_EXTRACT_POLYGONAL_PRISM_DATA_H_
#define PCL_ROS_EXTRACT_POLYGONAL_PRISM_DATA_H_ #define PCL_ROS_EXTRACT_POLYGONAL_PRISM_DATA_H_
#include "pcl_ros/pcl_nodelet.h" #include "pcl_ros/pcl_nodelet.hpp"
#include <message_filters/sync_policies/exact_time.h> #include <message_filters/sync_policies/exact_time.h>
#include <message_filters/sync_policies/approximate_time.h> #include <message_filters/sync_policies/approximate_time.h>
#include <message_filters/pass_through.h> #include <message_filters/pass_through.h>
@ -48,7 +48,7 @@
// Dynamic reconfigure // Dynamic reconfigure
#include <dynamic_reconfigure/server.h> #include <dynamic_reconfigure/server.h>
#include "pcl_ros/ExtractPolygonalPrismDataConfig.h" #include "pcl_ros/ExtractPolygonalPrismDataConfig.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -38,7 +38,7 @@
#ifndef PCL_ROS_SAC_SEGMENTATION_H_ #ifndef PCL_ROS_SAC_SEGMENTATION_H_
#define PCL_ROS_SAC_SEGMENTATION_H_ #define PCL_ROS_SAC_SEGMENTATION_H_
#include "pcl_ros/pcl_nodelet.h" #include "pcl_ros/pcl_nodelet.hpp"
#include <message_filters/pass_through.h> #include <message_filters/pass_through.h>
// PCL includes // PCL includes
@ -46,8 +46,8 @@
// Dynamic reconfigure // Dynamic reconfigure
#include <dynamic_reconfigure/server.h> #include <dynamic_reconfigure/server.h>
#include "pcl_ros/SACSegmentationConfig.h" #include "pcl_ros/SACSegmentationConfig.hpp"
#include "pcl_ros/SACSegmentationFromNormalsConfig.h" #include "pcl_ros/SACSegmentationFromNormalsConfig.hpp"
namespace pcl_ros namespace pcl_ros
{ {

View File

@ -39,11 +39,11 @@
#define PCL_ROS_SEGMENT_DIFFERENCES_H_ #define PCL_ROS_SEGMENT_DIFFERENCES_H_
#include <pcl/segmentation/segment_differences.h> #include <pcl/segmentation/segment_differences.h>
#include "pcl_ros/pcl_nodelet.h" #include "pcl_ros/pcl_nodelet.hpp"
// Dynamic reconfigure // Dynamic reconfigure
#include <dynamic_reconfigure/server.h> #include <dynamic_reconfigure/server.h>
#include "pcl_ros/SegmentDifferencesConfig.h" #include "pcl_ros/SegmentDifferencesConfig.hpp"
namespace pcl_ros namespace pcl_ros

View File

@ -38,7 +38,7 @@
#ifndef PCL_ROS_CONVEX_HULL_2D_H_ #ifndef PCL_ROS_CONVEX_HULL_2D_H_
#define PCL_ROS_CONVEX_HULL_2D_H_ #define PCL_ROS_CONVEX_HULL_2D_H_
#include "pcl_ros/pcl_nodelet.h" #include "pcl_ros/pcl_nodelet.hpp"
// PCL includes // PCL includes
#include <pcl/surface/convex_hull.h> #include <pcl/surface/convex_hull.h>

View File

@ -38,7 +38,7 @@
#ifndef PCL_ROS_MOVING_LEAST_SQUARES_H_ #ifndef PCL_ROS_MOVING_LEAST_SQUARES_H_
#define PCL_ROS_MOVING_LEAST_SQUARES_H_ #define PCL_ROS_MOVING_LEAST_SQUARES_H_
#include "pcl_ros/pcl_nodelet.h" #include "pcl_ros/pcl_nodelet.hpp"
// PCL includes // PCL includes
#include <pcl/surface/mls.h> #include <pcl/surface/mls.h>

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/boundary.h" #include "pcl_ros/features/boundary.hpp"
void void
pcl_ros::BoundaryEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::BoundaryEstimation::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -48,7 +48,7 @@
//#include "principal_curvatures.cpp" //#include "principal_curvatures.cpp"
//#include "vfh.cpp" //#include "vfh.cpp"
#include <pcl/io/io.h> #include <pcl/io/io.h>
#include "pcl_ros/features/feature.h" #include "pcl_ros/features/feature.hpp"
#include <message_filters/null_types.h> #include <message_filters/null_types.h>
//////////////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////////////

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/fpfh.h" #include "pcl_ros/features/fpfh.hpp"
void void
pcl_ros::FPFHEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::FPFHEstimation::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/fpfh_omp.h" #include "pcl_ros/features/fpfh_omp.hpp"
void void
pcl_ros::FPFHEstimationOMP::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::FPFHEstimationOMP::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/moment_invariants.h" #include "pcl_ros/features/moment_invariants.hpp"
void void
pcl_ros::MomentInvariantsEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::MomentInvariantsEstimation::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/normal_3d.h" #include "pcl_ros/features/normal_3d.hpp"
void void
pcl_ros::NormalEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::NormalEstimation::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/normal_3d_omp.h" #include "pcl_ros/features/normal_3d_omp.hpp"
void void
pcl_ros::NormalEstimationOMP::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::NormalEstimationOMP::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/normal_3d_tbb.h" #include "pcl_ros/features/normal_3d_tbb.hpp"
#if defined HAVE_TBB #if defined HAVE_TBB

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/pfh.h" #include "pcl_ros/features/pfh.hpp"
void void
pcl_ros::PFHEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::PFHEstimation::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/principal_curvatures.h" #include "pcl_ros/features/principal_curvatures.hpp"
void void
pcl_ros::PrincipalCurvaturesEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::PrincipalCurvaturesEstimation::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -35,7 +35,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/shot.h" #include "pcl_ros/features/shot.hpp"
void void
pcl_ros::SHOTEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::SHOTEstimation::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -35,7 +35,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/shot_omp.h" #include "pcl_ros/features/shot_omp.hpp"
void void
pcl_ros::SHOTEstimationOMP::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::SHOTEstimationOMP::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/vfh.h" #include "pcl_ros/features/vfh.hpp"
void void
pcl_ros::VFHEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::VFHEstimation::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -37,7 +37,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/filters/crop_box.h" #include "pcl_ros/filters/crop_box.hpp"
////////////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////////////
bool bool

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/filters/extract_indices.h" #include "pcl_ros/filters/extract_indices.hpp"
////////////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////////////
bool bool

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/boundary.h" #include "pcl_ros/features/boundary.hpp"
void void
pcl_ros::BoundaryEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::BoundaryEstimation::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -48,7 +48,7 @@
//#include "principal_curvatures.cpp" //#include "principal_curvatures.cpp"
//#include "vfh.cpp" //#include "vfh.cpp"
#include <pcl/io/io.h> #include <pcl/io/io.h>
#include "pcl_ros/features/feature.h" #include "pcl_ros/features/feature.hpp"
#include <message_filters/null_types.h> #include <message_filters/null_types.h>
//////////////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////////////

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/fpfh.h" #include "pcl_ros/features/fpfh.hpp"
void void
pcl_ros::FPFHEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::FPFHEstimation::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/fpfh_omp.h" #include "pcl_ros/features/fpfh_omp.hpp"
void void
pcl_ros::FPFHEstimationOMP::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::FPFHEstimationOMP::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/moment_invariants.h" #include "pcl_ros/features/moment_invariants.hpp"
void void
pcl_ros::MomentInvariantsEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::MomentInvariantsEstimation::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/normal_3d.h" #include "pcl_ros/features/normal_3d.hpp"
void void
pcl_ros::NormalEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::NormalEstimation::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/normal_3d_omp.h" #include "pcl_ros/features/normal_3d_omp.hpp"
void void
pcl_ros::NormalEstimationOMP::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::NormalEstimationOMP::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/normal_3d_tbb.h" #include "pcl_ros/features/normal_3d_tbb.hpp"
#if defined HAVE_TBB #if defined HAVE_TBB

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/pfh.h" #include "pcl_ros/features/pfh.hpp"
void void
pcl_ros::PFHEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::PFHEstimation::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/principal_curvatures.h" #include "pcl_ros/features/principal_curvatures.hpp"
void void
pcl_ros::PrincipalCurvaturesEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::PrincipalCurvaturesEstimation::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/features/vfh.h" #include "pcl_ros/features/vfh.hpp"
void void
pcl_ros::VFHEstimation::emptyPublish (const PointCloudInConstPtr &cloud) pcl_ros::VFHEstimation::emptyPublish (const PointCloudInConstPtr &cloud)

View File

@ -36,8 +36,8 @@
*/ */
#include <pcl/io/io.h> #include <pcl/io/io.h>
#include "pcl_ros/transforms.h" #include "pcl_ros/transforms.hpp"
#include "pcl_ros/filters/filter.h" #include "pcl_ros/filters/filter.hpp"
/*//#include <pcl/filters/pixel_grid.h> /*//#include <pcl/filters/pixel_grid.h>
//#include <pcl/filters/filter_dimension.h> //#include <pcl/filters/filter_dimension.h>

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/filters/passthrough.h" #include "pcl_ros/filters/passthrough.hpp"
////////////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////////////
bool bool

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/filters/project_inliers.h" #include "pcl_ros/filters/project_inliers.hpp"
#include <pcl/io/io.h> #include <pcl/io/io.h>
////////////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////////////

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/filters/radius_outlier_removal.h" #include "pcl_ros/filters/radius_outlier_removal.hpp"
////////////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////////////
bool bool

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/filters/statistical_outlier_removal.h" #include "pcl_ros/filters/statistical_outlier_removal.hpp"
////////////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////////////
bool bool

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/filters/voxel_grid.h" #include "pcl_ros/filters/voxel_grid.hpp"
////////////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////////////
bool bool

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/io/bag_io.h" #include "pcl_ros/io/bag_io.hpp"
////////////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////////////
bool bool

View File

@ -37,8 +37,8 @@
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include <pcl/io/io.h> #include <pcl/io/io.h>
#include "pcl_ros/transforms.h" #include "pcl_ros/transforms.hpp"
#include "pcl_ros/io/concatenate_data.h" #include "pcl_ros/io/concatenate_data.hpp"
#include <pcl_conversions/pcl_conversions.h> #include <pcl_conversions/pcl_conversions.h>

View File

@ -39,7 +39,7 @@
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include <pcl/io/io.h> #include <pcl/io/io.h>
#include "pcl_ros/io/concatenate_fields.h" #include "pcl_ros/io/concatenate_fields.hpp"
#include <pcl_conversions/pcl_conversions.h> #include <pcl_conversions/pcl_conversions.h>

View File

@ -38,7 +38,7 @@
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include <sensor_msgs/PointCloud2.h> #include <sensor_msgs/PointCloud2.h>
#include <message_filters/subscriber.h> #include <message_filters/subscriber.h>
//#include <pcl_ros/subscriber.h> //#include <pcl_ros/subscriber.hpp>
#include <nodelet_topic_tools/nodelet_mux.h> #include <nodelet_topic_tools/nodelet_mux.h>
#include <nodelet_topic_tools/nodelet_demux.h> #include <nodelet_topic_tools/nodelet_demux.h>

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include <pcl_ros/io/pcd_io.h> #include <pcl_ros/io/pcd_io.hpp>
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
void void

View File

@ -38,7 +38,7 @@
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include <pcl/io/io.h> #include <pcl/io/io.h>
#include <pcl/PointIndices.h> #include <pcl/PointIndices.h>
#include "pcl_ros/segmentation/extract_clusters.h" #include "pcl_ros/segmentation/extract_clusters.hpp"
#include <pcl_conversions/pcl_conversions.h> #include <pcl_conversions/pcl_conversions.h>

View File

@ -36,8 +36,8 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/transforms.h" #include "pcl_ros/transforms.hpp"
#include "pcl_ros/segmentation/extract_polygonal_prism_data.h" #include "pcl_ros/segmentation/extract_polygonal_prism_data.hpp"
#include <pcl/io/io.h> #include <pcl/io/io.h>
#include <pcl_conversions/pcl_conversions.h> #include <pcl_conversions/pcl_conversions.h>

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/segmentation/sac_segmentation.h" #include "pcl_ros/segmentation/sac_segmentation.hpp"
#include <pcl/io/io.h> #include <pcl/io/io.h>
#include <pcl_conversions/pcl_conversions.h> #include <pcl_conversions/pcl_conversions.h>

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/segmentation/segment_differences.h" #include "pcl_ros/segmentation/segment_differences.hpp"
#include <pcl/io/io.h> #include <pcl/io/io.h>
////////////////////////////////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////////////////////////////////

View File

@ -37,7 +37,7 @@
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include <pcl/common/io.h> #include <pcl/common/io.h>
#include "pcl_ros/surface/convex_hull.h" #include "pcl_ros/surface/convex_hull.hpp"
#include <geometry_msgs/PolygonStamped.h> #include <geometry_msgs/PolygonStamped.h>
////////////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////////////

View File

@ -36,7 +36,7 @@
*/ */
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
#include "pcl_ros/surface/moving_least_squares.h" #include "pcl_ros/surface/moving_least_squares.hpp"
#include <pcl/io/io.h> #include <pcl/io/io.h>
////////////////////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////////////////////
void void

View File

@ -41,7 +41,7 @@
#include <boost/bind.hpp> #include <boost/bind.hpp>
#include <boost/scoped_ptr.hpp> #include <boost/scoped_ptr.hpp>
#include <pcl_ros/point_cloud.h> #include <pcl_ros/point_cloud.hpp>
#include <pcl_conversions/pcl_conversions.h> #include <pcl_conversions/pcl_conversions.h>
#include <ros/ros.h> #include <ros/ros.h>

View File

@ -38,7 +38,7 @@
#include <pcl/common/io.h> #include <pcl/common/io.h>
#include <pcl/point_types.h> #include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h> #include <pcl_conversions/pcl_conversions.h>
#include "pcl_ros/transforms.h" #include "pcl_ros/transforms.hpp"
#include "pcl_ros/impl/transforms.hpp" #include "pcl_ros/impl/transforms.hpp"
namespace pcl_ros namespace pcl_ros

View File

@ -51,7 +51,7 @@ Cloud Data) format.
#include <pcl/io/io.h> #include <pcl/io/io.h>
#include <pcl/io/pcd_io.h> #include <pcl/io/pcd_io.h>
#include <pcl_conversions/pcl_conversions.h> #include <pcl_conversions/pcl_conversions.h>
#include "pcl_ros/transforms.h" #include "pcl_ros/transforms.hpp"
#include <tf/transform_listener.h> #include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h> #include <tf/transform_broadcaster.h>

View File

@ -54,7 +54,7 @@
#include <pcl/point_types.h> #include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h> #include <pcl_conversions/pcl_conversions.h>
#include "pcl_ros/publisher.h" #include "pcl_ros/publisher.hpp"
using namespace std; using namespace std;