Skip to content

Commit f9dc100

Browse files
committed
[ros-o] boost::make_shared -> std::make_shared, use .makeShared()
1 parent 93e11f8 commit f9dc100

16 files changed

+108
-19
lines changed

jsk_pcl_ros/include/jsk_pcl_ros/container_occupancy_detector.h

+7
Original file line numberDiff line numberDiff line change
@@ -107,10 +107,17 @@ namespace jsk_pcl_ros{
107107
tf2_ros::TransformListener* tf_listener_;
108108
sensor_msgs::PointCloud2::Ptr transformed_points_msg_ =
109109
boost::shared_ptr<sensor_msgs::PointCloud2>(new sensor_msgs::PointCloud2);
110+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
111+
pcl::PCLPointCloud2Ptr pcl_pc2_ptr_ =
112+
std::shared_ptr<pcl::PCLPointCloud2>(new pcl::PCLPointCloud2);
113+
pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_xyz_ptr_ =
114+
std::shared_ptr<pcl::PointCloud<pcl::PointXYZ>>(new pcl::PointCloud<pcl::PointXYZ>);
115+
#else
110116
pcl::PCLPointCloud2Ptr pcl_pc2_ptr_ =
111117
boost::shared_ptr<pcl::PCLPointCloud2>(new pcl::PCLPointCloud2);
112118
pcl::PointCloud<pcl::PointXYZ>::Ptr pcl_xyz_ptr_ =
113119
boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ>>(new pcl::PointCloud<pcl::PointXYZ>);
120+
#endif
114121

115122
////////////////////////////////////////////////////////
116123
// Diagnostics Variables

jsk_pcl_ros/include/jsk_pcl_ros/particle_filter_tracking.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -186,7 +186,7 @@ namespace pcl
186186
// }
187187

188188
if (!change_detector_)
189-
change_detector_ = boost::shared_ptr<pcl::octree::OctreePointCloudChangeDetector<PointInT> >(new pcl::octree::OctreePointCloudChangeDetector<PointInT> (change_detector_resolution_));
189+
pcl::octree::OctreePointCloudChangeDetector<PointInT> *change_detector_ = new pcl::octree::OctreePointCloudChangeDetector<PointInT> (change_detector_resolution_);
190190

191191
if (!particles_ || particles_->points.empty ())
192192
initParticles (true);

jsk_pcl_ros/include/jsk_pcl_ros/target_adaptive_tracking.h

+1
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,7 @@
4242
#include <pcl/features/gfpfh.h>
4343
#include <pcl/features/pfh.h>
4444
#include <pcl/features/cvfh.h>
45+
#include <pcl/features/pfh_tools.h> // for computePairFeatures
4546
#include <pcl/features/normal_3d_omp.h>
4647
#include <pcl/tracking/tracking.h>
4748
#include <pcl/common/common.h>

jsk_pcl_ros/src/edgebased_cube_finder_nodelet.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -756,7 +756,11 @@ namespace jsk_pcl_ros
756756
*points_on_edges = *points_on_edges + *points_on_edge;
757757
cubes.push_back(cube);
758758
}
759+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
760+
pub_debug_filtered_cloud_.publish(*points_on_edges);
761+
#else
759762
pub_debug_filtered_cloud_.publish(points_on_edges);
763+
#endif
760764
}
761765
}
762766

jsk_pcl_ros/src/euclidean_cluster_extraction_nodelet.cpp

+13-2
Original file line numberDiff line numberDiff line change
@@ -140,7 +140,9 @@ namespace jsk_pcl_ros
140140
EuclideanClusterExtraction<pcl::PointXYZ> impl;
141141
if (filtered_cloud->points.size() > 0) {
142142
jsk_topic_tools::ScopedTimer timer = kdtree_acc_.scopedTimer();
143-
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 )
143+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
144+
pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>());
145+
#elif ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 )
144146
pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
145147
tree = boost::make_shared< pcl::search::KdTree<pcl::PointXYZ> > ();
146148
#else
@@ -332,7 +334,9 @@ namespace jsk_pcl_ros
332334
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
333335
pcl::fromROSMsg(req.input, *cloud);
334336

335-
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 )
337+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
338+
pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ> ());
339+
#elif ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 )
336340
pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
337341
tree = boost::make_shared< pcl::search::KdTree<pcl::PointXYZ> > ();
338342
#else
@@ -361,12 +365,19 @@ namespace jsk_pcl_ros
361365
pcl_conversions::toPCL(req.input, *pcl_cloud);
362366
pcl::ExtractIndices<pcl::PCLPointCloud2> ex;
363367
ex.setInputCloud(pcl_cloud);
368+
#elif ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
369+
pcl::ExtractIndices<sensor_msgs::PointCloud2> ex;
370+
ex.setInputCloud ( req.input.makeShared() );
364371
#else
365372
pcl::ExtractIndices<sensor_msgs::PointCloud2> ex;
366373
ex.setInputCloud ( boost::make_shared< sensor_msgs::PointCloud2 > (req.input) );
367374
#endif
368375
for ( size_t i = 0; i < cluster_indices.size(); i++ ) {
376+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
377+
ex.setIndices ( std::make_shared< pcl::PointIndices > (cluster_indices[i]) );
378+
#else
369379
ex.setIndices ( boost::make_shared< pcl::PointIndices > (cluster_indices[i]) );
380+
#endif
370381
ex.setNegative ( false );
371382
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 7 )
372383
pcl::PCLPointCloud2 output_cloud;

jsk_pcl_ros/src/icp_registration_nodelet.cpp

+14
Original file line numberDiff line numberDiff line change
@@ -592,6 +592,12 @@ namespace jsk_pcl_ros
592592
pcl::PointCloud<PointT>::Ptr& output_cloud,
593593
Eigen::Affine3d& output_transform)
594594
{
595+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
596+
pcl::GeneralizedIterativeClosestPoint<PointT, PointT> icp;
597+
icp.setRotationEpsilon(rotation_epsilon_);
598+
icp.setCorrespondenceRandomness(correspondence_randomness_);
599+
icp.setMaximumOptimizerIterations(maximum_optimizer_iterations_);
600+
#else
595601
pcl::IterativeClosestPoint<PointT, PointT> icp;
596602
if (use_normal_) {
597603
pcl::IterativeClosestPointWithNormals<PointT, PointT> icp_with_normal;
@@ -606,6 +612,7 @@ namespace jsk_pcl_ros
606612
gicp.setMaximumOptimizerIterations(maximum_optimizer_iterations_);
607613
icp = gicp;
608614
}
615+
#endif
609616
if (correspondence_algorithm_ == 1) { // Projective
610617
if (!camera_info_msg_) {
611618
NODELET_ERROR("no camera info is available yet");
@@ -636,10 +643,17 @@ namespace jsk_pcl_ros
636643
icp.setInputTarget(cloud);
637644

638645
if (transform_3dof_) {
646+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
647+
pcl::registration::WarpPointRigid3D<PointT, PointT>::Ptr warp_func
648+
(new pcl::registration::WarpPointRigid3D<PointT, PointT>);
649+
pcl::registration::TransformationEstimationLM<PointT, PointT>::Ptr te
650+
(new pcl::registration::TransformationEstimationLM<PointT, PointT>);
651+
#else
639652
boost::shared_ptr<pcl::registration::WarpPointRigid3D<PointT, PointT> > warp_func
640653
(new pcl::registration::WarpPointRigid3D<PointT, PointT>);
641654
boost::shared_ptr<pcl::registration::TransformationEstimationLM<PointT, PointT> > te
642655
(new pcl::registration::TransformationEstimationLM<PointT, PointT>);
656+
#endif
643657
te->setWarpFunction(warp_func);
644658
icp.setTransformationEstimation(te);
645659
}

jsk_pcl_ros/src/moving_least_square_smoothing_nodelet.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939
#include <geometry_msgs/PointStamped.h>
4040

4141
#include "jsk_recognition_utils/pcl_conversion_util.h"
42+
#include <pcl/search/kdtree.h> // for KdTree
4243

4344
namespace jsk_pcl_ros
4445
{
@@ -56,7 +57,9 @@ namespace jsk_pcl_ros
5657
pcl::MovingLeastSquares<pcl::PointXYZRGB, pcl::PointXYZRGB> smoother;
5758
smoother.setSearchRadius (search_radius_);
5859
if (gauss_param_set_) smoother.setSqrGaussParam (gauss_param_set_);
60+
#if PCL_VERSION_COMPARE (<, 1, 9, 0) // https://github.com/PointCloudLibrary/pcl/blob/cc08f815a9a5f2a1d3f897fb2bc9d541635792c9/CHANGES.md?plain=1#L1633
5961
smoother.setPolynomialFit (use_polynomial_fit_);
62+
#endif
6063
smoother.setPolynomialOrder (polynomial_order_);
6164
smoother.setComputeNormals (calc_normal_);
6265

jsk_pcl_ros/src/organized_multi_plane_segmentation_nodelet.cpp

+28
Original file line numberDiff line numberDiff line change
@@ -246,10 +246,17 @@ namespace jsk_pcl_ros
246246

247247
// compute the distance between two boundaries.
248248
// if they are near enough, we can regard these two map should connect
249+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
250+
pcl::PointIndices::Ptr a_indices
251+
= std::make_shared<pcl::PointIndices>(boundary_indices[i]);
252+
pcl::PointIndices::Ptr b_indices
253+
= std::make_shared<pcl::PointIndices>(boundary_indices[j]);
254+
#else
249255
pcl::PointIndices::Ptr a_indices
250256
= boost::make_shared<pcl::PointIndices>(boundary_indices[i]);
251257
pcl::PointIndices::Ptr b_indices
252258
= boost::make_shared<pcl::PointIndices>(boundary_indices[j]);
259+
#endif
253260
pcl::PointCloud<PointT> a_cloud, b_cloud;
254261
extract.setIndices(a_indices);
255262
extract.filter(a_cloud);
@@ -364,10 +371,17 @@ namespace jsk_pcl_ros
364371
pcl::ModelCoefficients pcl_new_coefficients;
365372
pcl_new_coefficients.values = new_coefficients;
366373
// estimate concave hull
374+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
375+
pcl::PointIndices::Ptr indices_ptr
376+
= std::make_shared<pcl::PointIndices>(one_boundaries);
377+
pcl::ModelCoefficients::Ptr coefficients_ptr
378+
= std::make_shared<pcl::ModelCoefficients>(pcl_new_coefficients);
379+
#else
367380
pcl::PointIndices::Ptr indices_ptr
368381
= boost::make_shared<pcl::PointIndices>(one_boundaries);
369382
pcl::ModelCoefficients::Ptr coefficients_ptr
370383
= boost::make_shared<pcl::ModelCoefficients>(pcl_new_coefficients);
384+
#endif
371385
jsk_recognition_utils::ConvexPolygon::Ptr convex
372386
= jsk_recognition_utils::convexFromCoefficientsAndInliers<PointT>(
373387
input, indices_ptr, coefficients_ptr);
@@ -478,7 +492,11 @@ namespace jsk_pcl_ros
478492
for (size_t i = 0; i < boundary_indices.size(); i++) {
479493
pcl::PointCloud<PointT> boundary_cloud;
480494
pcl::PointIndices boundary_one_indices = boundary_indices[i];
495+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
496+
pcl::PointIndices::Ptr indices_ptr = std::make_shared<pcl::PointIndices>(boundary_indices[i]);
497+
#else
481498
pcl::PointIndices::Ptr indices_ptr = boost::make_shared<pcl::PointIndices>(boundary_indices[i]);
499+
#endif
482500
extract.setIndices(indices_ptr);
483501
extract.filter(boundary_cloud);
484502
boundaries.push_back(boundary_cloud);
@@ -510,8 +528,13 @@ namespace jsk_pcl_ros
510528
////////////////////////////////////////////////////////
511529
jsk_recognition_utils::Vertices centroids;
512530
for (size_t i = 0; i < inliers.size(); i++) {
531+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
532+
pcl::PointIndices::Ptr target_inliers
533+
= std::make_shared<pcl::PointIndices>(inliers[i]);
534+
#else
513535
pcl::PointIndices::Ptr target_inliers
514536
= boost::make_shared<pcl::PointIndices>(inliers[i]);
537+
#endif
515538
pcl::PointCloud<PointT>::Ptr target_cloud (new pcl::PointCloud<PointT>);
516539
Eigen::Vector4f centroid;
517540
pcl::ExtractIndices<PointT> ex;
@@ -640,8 +663,13 @@ namespace jsk_pcl_ros
640663
jsk_topic_tools::ScopedTimer timer
641664
= ransac_refinement_time_acc_.scopedTimer();
642665
for (size_t i = 0; i < input_indices.size(); i++) {
666+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
667+
pcl::PointIndices::Ptr input_indices_ptr
668+
= std::make_shared<pcl::PointIndices>(input_indices[i]);
669+
#else
643670
pcl::PointIndices::Ptr input_indices_ptr
644671
= boost::make_shared<pcl::PointIndices>(input_indices[i]);
672+
#endif
645673
Eigen::Vector3f normal(input_coefficients[i].values[0],
646674
input_coefficients[i].values[1],
647675
input_coefficients[i].values[2]);

jsk_pcl_ros/src/particle_filter_tracking_nodelet.cpp

+3-6
Original file line numberDiff line numberDiff line change
@@ -145,19 +145,16 @@ namespace jsk_pcl_ros
145145
}
146146

147147

148-
boost::shared_ptr<DistanceCoherence<PointT> >
149-
distance_coherence(new DistanceCoherence<PointT>);
148+
DistanceCoherence<PointT>::Ptr distance_coherence(new DistanceCoherence<PointT>);
150149
coherence->addPointCoherence(distance_coherence);
151150

152151
//add HSV coherence
153152
if (use_hsv) {
154-
boost::shared_ptr<HSVColorCoherence<PointT> > hsv_color_coherence
155-
= boost::shared_ptr<HSVColorCoherence<PointT> >(new HSVColorCoherence<PointT>());
153+
HSVColorCoherence<PointT>::Ptr hsv_color_coherence(new HSVColorCoherence<PointT>());
156154
coherence->addPointCoherence(hsv_color_coherence);
157155
}
158156

159-
boost::shared_ptr<pcl::search::Octree<PointT> > search
160-
(new pcl::search::Octree<PointT>(octree_resolution));
157+
pcl::search::Octree<PointT>::Ptr search(new pcl::search::Octree<PointT>(octree_resolution));
161158
//boost::shared_ptr<pcl::search::KdTree<PointT> > search(new pcl::search::KdTree<PointT>());
162159
coherence->setSearchMethod(search);
163160
double max_distance;

jsk_pcl_ros/src/pointcloud_database_server_nodelet.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939
#include <pcl/io/pcd_io.h>
4040
#include <pcl/io/vtk_lib_io.h>
4141
#include "jsk_recognition_utils/pcl_conversion_util.h"
42+
#include <boost/filesystem.hpp>
4243

4344
namespace jsk_pcl_ros
4445
{

jsk_pcl_ros/src/pointcloud_screenpoint_nodelet.cpp

+3-4
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ void PointcloudScreenpoint::onInit()
4949
ConnectionBasedNodelet::onInit();
5050

5151

52-
normals_tree_ = boost::make_shared< pcl::search::KdTree< pcl::PointXYZ > > ();
52+
pcl::search::KdTree<pcl::PointXYZ>::Ptr normals_tree_(new pcl::search::KdTree<pcl::PointXYZ>);
5353
n3d_.setSearchMethod (normals_tree_);
5454

5555
dyn_srv_ = boost::make_shared< dynamic_reconfigure::Server< Config > >(*pnh_);
@@ -257,8 +257,7 @@ bool PointcloudScreenpoint::screenpoint_cb (
257257
}
258258

259259
// search normal
260-
n3d_.setSearchSurface(
261-
boost::make_shared<pcl::PointCloud<pcl::PointXYZ > > (latest_cloud_));
260+
n3d_.setSearchSurface(latest_cloud_.makeShared());
262261

263262
pcl::PointCloud<pcl::PointXYZ> cloud_;
264263
pcl::PointXYZ pt;
@@ -268,7 +267,7 @@ bool PointcloudScreenpoint::screenpoint_cb (
268267
cloud_.points.resize(0);
269268
cloud_.points.push_back(pt);
270269

271-
n3d_.setInputCloud (boost::make_shared<pcl::PointCloud<pcl::PointXYZ > > (cloud_));
270+
n3d_.setInputCloud (cloud_.makeShared());
272271
pcl::PointCloud<pcl::Normal> cloud_normals;
273272
n3d_.compute (cloud_normals);
274273

jsk_pcl_ros/src/region_growing_multiple_plane_segmentation_nodelet.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -204,7 +204,11 @@ namespace jsk_pcl_ros
204204
for (size_t i = 0; i < clusters->size(); i++) {
205205
pcl::PointIndices::Ptr plane_inliers(new pcl::PointIndices);
206206
pcl::ModelCoefficients::Ptr plane_coefficients(new pcl::ModelCoefficients);
207+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
208+
pcl::PointIndices::Ptr cluster = std::make_shared<pcl::PointIndices>((*clusters)[i]);
209+
#else
207210
pcl::PointIndices::Ptr cluster = boost::make_shared<pcl::PointIndices>((*clusters)[i]);
211+
#endif
208212
ransacEstimation(cloud, cluster,
209213
*plane_inliers, *plane_coefficients);
210214
if (plane_inliers->indices.size() > 0) {

jsk_pcl_ros/src/region_growing_segmentation_nodelet.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -89,7 +89,11 @@ namespace jsk_pcl_ros
8989
void RegionGrowingSegmentation::segment(const sensor_msgs::PointCloud2::ConstPtr& msg)
9090
{
9191
boost::mutex::scoped_lock lock(mutex_);
92+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
93+
pcl::search::Search<pcl::PointNormal>::Ptr tree(new pcl::search::KdTree<pcl::PointNormal>());
94+
#else
9295
pcl::search::Search<pcl::PointNormal>::Ptr tree = boost::shared_ptr<pcl::search::Search<pcl::PointNormal> > (new pcl::search::KdTree<pcl::PointNormal>);
96+
#endif
9397
pcl::PointCloud<pcl::PointNormal> cloud;
9498
pcl::fromROSMsg(*msg, cloud);
9599

jsk_pcl_ros/src/resize_points_publisher_nodelet.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -184,7 +184,11 @@ namespace jsk_pcl_ros
184184
}
185185
pcl::ExtractIndices<T> extract;
186186
extract.setInputCloud (pcl_input_cloud.makeShared());
187+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
188+
extract.setIndices (std::make_shared <std::vector<int> > (ex_indices));
189+
#else
187190
extract.setIndices (boost::make_shared <std::vector<int> > (ex_indices));
191+
#endif
188192
extract.setNegative (false);
189193
extract.filter (output);
190194

jsk_pcl_ros/src/supervoxel_segmentation_nodelet.cpp

+6-2
Original file line numberDiff line numberDiff line change
@@ -72,8 +72,12 @@ namespace jsk_pcl_ros
7272
pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
7373
pcl::fromROSMsg(*cloud_msg, *cloud);
7474
pcl::SupervoxelClustering<PointT> super(voxel_resolution_,
75-
seed_resolution_,
76-
use_transform_);
75+
seed_resolution_
76+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
77+
);
78+
#else
79+
, use_transform_);
80+
#endif
7781
super.setInputCloud(cloud);
7882
super.setColorImportance(color_importance_);
7983
super.setSpatialImportance(spatial_importance_);

jsk_pcl_ros/src/target_adaptive_tracking_nodelet.cpp

+12-4
Original file line numberDiff line numberDiff line change
@@ -1782,8 +1782,12 @@ namespace jsk_pcl_ros
17821782
boost::mutex::scoped_lock lock(mutex_);
17831783
pcl::SupervoxelClustering<PointT> super(
17841784
voxel_resolution_,
1785-
static_cast<double>(seed_resolution),
1786-
use_transform_);
1785+
static_cast<double>(seed_resolution)
1786+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
1787+
);
1788+
#else
1789+
, use_transform_);
1790+
#endif
17871791
super.setInputCloud(cloud);
17881792
super.setColorImportance(color_importance_);
17891793
super.setSpatialImportance(spatial_importance_);
@@ -1804,8 +1808,12 @@ namespace jsk_pcl_ros
18041808
}
18051809
boost::mutex::scoped_lock lock(mutex_);
18061810
pcl::SupervoxelClustering<PointT> super(voxel_resolution_,
1807-
seed_resolution_,
1808-
use_transform_);
1811+
seed_resolution_
1812+
#if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 )
1813+
);
1814+
#else
1815+
, use_transform_);
1816+
#endif
18091817
super.setInputCloud(cloud);
18101818
super.setColorImportance(color_importance_);
18111819
super.setSpatialImportance(spatial_importance_);

0 commit comments

Comments
 (0)