From 11d24d0e97169bd2fd2714fba1d4ac2dcdc87628 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Tue, 23 Jul 2013 13:32:50 -0700 Subject: [PATCH] Initialize shared pointers before use Should address runtime errors reported in #29 --- pcl_ros/include/pcl_ros/filters/extract_indices.h | 2 +- pcl_ros/include/pcl_ros/filters/passthrough.h | 2 +- pcl_ros/include/pcl_ros/filters/project_inliers.h | 4 ++-- pcl_ros/include/pcl_ros/filters/radius_outlier_removal.h | 2 +- pcl_ros/include/pcl_ros/filters/statistical_outlier_removal.h | 4 ++-- pcl_ros/src/pcl_ros/filters/voxel_grid.cpp | 2 +- 6 files changed, 8 insertions(+), 8 deletions(-) diff --git a/pcl_ros/include/pcl_ros/filters/extract_indices.h b/pcl_ros/include/pcl_ros/filters/extract_indices.h index cdb60e8f..1ae0d1a9 100644 --- a/pcl_ros/include/pcl_ros/filters/extract_indices.h +++ b/pcl_ros/include/pcl_ros/filters/extract_indices.h @@ -66,7 +66,7 @@ namespace pcl_ros PointCloud2 &output) { boost::mutex::scoped_lock lock (mutex_); - pcl::PCLPointCloud2::Ptr pcl_input; + pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2); pcl_conversions::toPCL(*(input), *(pcl_input)); impl_.setInputCloud (pcl_input); impl_.setIndices (indices); diff --git a/pcl_ros/include/pcl_ros/filters/passthrough.h b/pcl_ros/include/pcl_ros/filters/passthrough.h index 7d6c9649..4dad5f2d 100644 --- a/pcl_ros/include/pcl_ros/filters/passthrough.h +++ b/pcl_ros/include/pcl_ros/filters/passthrough.h @@ -64,7 +64,7 @@ namespace pcl_ros PointCloud2 &output) { boost::mutex::scoped_lock lock (mutex_); - pcl::PCLPointCloud2::Ptr pcl_input; + pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2); pcl_conversions::toPCL (*(input), *(pcl_input)); impl_.setInputCloud (pcl_input); impl_.setIndices (indices); diff --git a/pcl_ros/include/pcl_ros/filters/project_inliers.h b/pcl_ros/include/pcl_ros/filters/project_inliers.h index 636291fe..8002bcd2 100644 --- a/pcl_ros/include/pcl_ros/filters/project_inliers.h +++ b/pcl_ros/include/pcl_ros/filters/project_inliers.h @@ -68,11 +68,11 @@ namespace pcl_ros filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output) { - pcl::PCLPointCloud2::Ptr pcl_input; + pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2); pcl_conversions::toPCL (*(input), *(pcl_input)); impl_.setInputCloud (pcl_input); impl_.setIndices (indices); - pcl::ModelCoefficients::Ptr pcl_model; + pcl::ModelCoefficients::Ptr pcl_model(new pcl::ModelCoefficients); pcl_conversions::toPCL(*(model_), *(pcl_model)); impl_.setModelCoefficients (pcl_model); pcl::PCLPointCloud2 pcl_output; diff --git a/pcl_ros/include/pcl_ros/filters/radius_outlier_removal.h b/pcl_ros/include/pcl_ros/filters/radius_outlier_removal.h index 38babf0c..cb75eaee 100644 --- a/pcl_ros/include/pcl_ros/filters/radius_outlier_removal.h +++ b/pcl_ros/include/pcl_ros/filters/radius_outlier_removal.h @@ -61,7 +61,7 @@ namespace pcl_ros filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output) { - pcl::PCLPointCloud2::Ptr pcl_input; + pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2); pcl_conversions::toPCL (*(input), *(pcl_input)); impl_.setInputCloud (pcl_input); impl_.setIndices (indices); diff --git a/pcl_ros/include/pcl_ros/filters/statistical_outlier_removal.h b/pcl_ros/include/pcl_ros/filters/statistical_outlier_removal.h index 22ed8b82..b3d17e35 100644 --- a/pcl_ros/include/pcl_ros/filters/statistical_outlier_removal.h +++ b/pcl_ros/include/pcl_ros/filters/statistical_outlier_removal.h @@ -58,7 +58,7 @@ namespace pcl_ros * \note setFilterFieldName (), setFilterLimits (), and setFilterLimitNegative () are ignored. * \author Radu Bogdan Rusu */ - class StatisticalOutlierRemoval : public Filter + class StatisticalOutlierRemoval : public Filter { protected: /** \brief Pointer to a dynamic reconfigure service. */ @@ -74,7 +74,7 @@ namespace pcl_ros PointCloud2 &output) { boost::mutex::scoped_lock lock (mutex_); - pcl::PCLPointCloud2::Ptr pcl_input; + pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2); pcl_conversions::toPCL(*(input), *(pcl_input)); impl_.setInputCloud (pcl_input); impl_.setIndices (indices); diff --git a/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp b/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp index 6405b3f4..db718d5b 100644 --- a/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp +++ b/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp @@ -58,7 +58,7 @@ pcl_ros::VoxelGrid::filter (const PointCloud2::ConstPtr &input, PointCloud2 &output) { boost::mutex::scoped_lock lock (mutex_); - pcl::PCLPointCloud2::Ptr pcl_input; + pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2); pcl_conversions::toPCL (*(input), *(pcl_input)); impl_.setInputCloud (pcl_input); impl_.setIndices (indices);