@@ -246,10 +246,17 @@ namespace jsk_pcl_ros
246
246
247
247
// compute the distance between two boundaries.
248
248
// 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
249
255
pcl::PointIndices::Ptr a_indices
250
256
= boost::make_shared<pcl::PointIndices>(boundary_indices[i]);
251
257
pcl::PointIndices::Ptr b_indices
252
258
= boost::make_shared<pcl::PointIndices>(boundary_indices[j]);
259
+ #endif
253
260
pcl::PointCloud<PointT> a_cloud, b_cloud;
254
261
extract.setIndices (a_indices);
255
262
extract.filter (a_cloud);
@@ -364,10 +371,17 @@ namespace jsk_pcl_ros
364
371
pcl::ModelCoefficients pcl_new_coefficients;
365
372
pcl_new_coefficients.values = new_coefficients;
366
373
// 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
367
380
pcl::PointIndices::Ptr indices_ptr
368
381
= boost::make_shared<pcl::PointIndices>(one_boundaries);
369
382
pcl::ModelCoefficients::Ptr coefficients_ptr
370
383
= boost::make_shared<pcl::ModelCoefficients>(pcl_new_coefficients);
384
+ #endif
371
385
jsk_recognition_utils::ConvexPolygon::Ptr convex
372
386
= jsk_recognition_utils::convexFromCoefficientsAndInliers<PointT>(
373
387
input, indices_ptr, coefficients_ptr);
@@ -478,7 +492,11 @@ namespace jsk_pcl_ros
478
492
for (size_t i = 0 ; i < boundary_indices.size (); i++) {
479
493
pcl::PointCloud<PointT> boundary_cloud;
480
494
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
481
498
pcl::PointIndices::Ptr indices_ptr = boost::make_shared<pcl::PointIndices>(boundary_indices[i]);
499
+ #endif
482
500
extract.setIndices (indices_ptr);
483
501
extract.filter (boundary_cloud);
484
502
boundaries.push_back (boundary_cloud);
@@ -510,8 +528,13 @@ namespace jsk_pcl_ros
510
528
// //////////////////////////////////////////////////////
511
529
jsk_recognition_utils::Vertices centroids;
512
530
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
513
535
pcl::PointIndices::Ptr target_inliers
514
536
= boost::make_shared<pcl::PointIndices>(inliers[i]);
537
+ #endif
515
538
pcl::PointCloud<PointT>::Ptr target_cloud (new pcl::PointCloud<PointT>);
516
539
Eigen::Vector4f centroid;
517
540
pcl::ExtractIndices<PointT> ex;
@@ -640,8 +663,13 @@ namespace jsk_pcl_ros
640
663
jsk_topic_tools::ScopedTimer timer
641
664
= ransac_refinement_time_acc_.scopedTimer ();
642
665
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
643
670
pcl::PointIndices::Ptr input_indices_ptr
644
671
= boost::make_shared<pcl::PointIndices>(input_indices[i]);
672
+ #endif
645
673
Eigen::Vector3f normal (input_coefficients[i].values [0 ],
646
674
input_coefficients[i].values [1 ],
647
675
input_coefficients[i].values [2 ]);
0 commit comments