Skip to content

Commit

Permalink
Merge pull request #2096 from SergioRAgostinho/ecc-deprecated
Browse files Browse the repository at this point in the history
Provide proper EuclideanClusterComparator method depreciation
  • Loading branch information
taketwo authored Nov 27, 2017
2 parents 5d18757 + c3f4710 commit 47629c1
Show file tree
Hide file tree
Showing 8 changed files with 241 additions and 131 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -103,12 +103,14 @@
std::vector<pcl::PointIndices> boundary_indices;
mps.segmentAndRefine (regions, model_coefficients, inlier_indices, labels, label_indices, boundary_indices);

boost::shared_ptr<std::map<uint32_t, bool> > plane_labels = boost::make_shared<std::map<uint32_t, bool> > ();
boost::shared_ptr<std::set<uint32_t> > plane_labels = boost::make_shared<std::set<uint32_t> > ();
for (size_t i = 0; i < label_indices.size (); ++i)
(*plane_labels)[i] = (label_indices[i].indices.size () > (size_t) min_plane_size);
if (label_indices[i].indices.size () > (size_t) min_plane_size)
plane_labels->insert (i);
typename PointCloud<PointT>::CloudVectorType clusters;

typename EuclideanClusterComparator<PointT, pcl::Label>::Ptr euclidean_cluster_comparator = boost::make_shared <EuclideanClusterComparator<PointT, pcl::Label> > ();
typename EuclideanClusterComparator<PointT, pcl::Label>::Ptr euclidean_cluster_comparator =
boost::make_shared <EuclideanClusterComparator<PointT, pcl::Label> > ();
euclidean_cluster_comparator->setInputCloud (input_cloud);
euclidean_cluster_comparator->setLabels (labels);
euclidean_cluster_comparator->setExcludeLabels (plane_labels);
Expand Down
5 changes: 2 additions & 3 deletions apps/src/ni_linemod.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -260,9 +260,8 @@ class NILinemod
scene->points[points_above_plane->indices[i]].label = 1;
euclidean_cluster_comparator->setLabels (scene);

boost::shared_ptr<std::map<uint32_t, bool> > exclude_labels = boost::make_shared<std::map<uint32_t, bool> > ();
(*exclude_labels)[0] = true;
(*exclude_labels)[1] = false;
boost::shared_ptr<std::set<uint32_t> > exclude_labels = boost::make_shared<std::set<uint32_t> > ();
exclude_labels->insert (0);

OrganizedConnectedComponentSegmentation<PointT, Label> euclidean_segmentation (euclidean_cluster_comparator);
euclidean_segmentation.setInputCloud (cloud);
Expand Down
5 changes: 3 additions & 2 deletions apps/src/organized_segmentation_demo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -309,9 +309,10 @@ OrganizedSegmentationDemo::cloud_cb (const CloudConstPtr& cloud)

if (use_clustering_ && regions.size () > 0)
{
boost::shared_ptr<std::map<uint32_t, bool> > plane_labels = boost::make_shared<std::map<uint32_t, bool> > ();
boost::shared_ptr<std::set<uint32_t> > plane_labels = boost::make_shared<std::set<uint32_t> > ();
for (size_t i = 0; i < label_indices.size (); ++i)
(*plane_labels)[i] = (label_indices[i].indices.size () > 10000);
if (label_indices[i].indices.size () > 10000)
plane_labels->insert (i);

euclidean_cluster_comparator_->setInputCloud (cloud);
euclidean_cluster_comparator_->setLabels (labels);
Expand Down
5 changes: 2 additions & 3 deletions apps/src/pcd_select_object_plane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,9 +205,8 @@ class ObjectSelection
scene->points[points_above_plane->indices[i]].label = 1;
euclidean_cluster_comparator->setLabels (scene);

boost::shared_ptr<std::map<uint32_t, bool> > exclude_labels = boost::make_shared<std::map<uint32_t, bool> > ();
(*exclude_labels)[0] = true;
(*exclude_labels)[1] = false;
boost::shared_ptr<std::set<uint32_t> > exclude_labels = boost::make_shared<std::set<uint32_t> > ();
exclude_labels->insert (0);
euclidean_cluster_comparator->setExcludeLabels (exclude_labels);

OrganizedConnectedComponentSegmentation<PointT, Label> euclidean_segmentation (euclidean_cluster_comparator);
Expand Down
5 changes: 3 additions & 2 deletions apps/src/stereo_ground_segmentation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -393,9 +393,10 @@ class HRCSSegmentation
pcl::PointCloud<PointT>::CloudVectorType clusters;
if (ground_cloud->points.size () > 0)
{
boost::shared_ptr<std::map<uint32_t, bool> > plane_labels = boost::make_shared<std::map<uint32_t, bool> > ();
boost::shared_ptr<std::set<uint32_t> > plane_labels = boost::make_shared<std::set<uint32_t> > ();
for (size_t i = 0; i < region_indices.size (); ++i)
(*plane_labels)[i] = (region_indices[i].indices.size () > mps.getMinInliers ());
if ((region_indices[i].indices.size () > mps.getMinInliers ()))
plane_labels->insert (i);

pcl::EuclideanClusterComparator<PointT, pcl::Label>::Ptr euclidean_cluster_comparator_ (new pcl::EuclideanClusterComparator<PointT, pcl::Label> ());
euclidean_cluster_comparator_->setInputCloud (cloud);
Expand Down
19 changes: 19 additions & 0 deletions common/include/pcl/pcl_macros.h
Original file line number Diff line number Diff line change
Expand Up @@ -289,6 +289,25 @@ log2f (float x)
#define PCLAPI(rettype) PCL_EXTERN_C PCL_EXPORTS rettype PCL_CDECL
#endif

// Macro for pragma operator
#if (defined (__GNUC__) || defined(__clang__))
#define PCL_PRAGMA(x) _Pragma (#x)
#elif _MSC_VER
#define PCL_PRAGMA(x) __pragma (#x)
#else
#define PCL_PRAGMA
#endif

// Macro for emitting pragma warning
#if (defined (__GNUC__) || defined(__clang__))
#define PCL_PRAGMA_WARNING(x) PCL_PRAGMA (GCC warning x)
#elif _MSC_VER
#define PCL_PRAGMA_WARNING(x) PCL_PRAGMA (warning (x))
#else
#define PCL_PRAGMA_WARNING
#endif


// Macro to deprecate old functions
//
// Usage:
Expand Down
7 changes: 7 additions & 0 deletions common/include/pcl/point_traits.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,13 @@

namespace pcl
{
namespace deprecated
{
/** \class DeprecatedType
* \brief A dummy type to aid in template parameter deprecation
*/
struct T {};
}

namespace fields
{
Expand Down
Loading

0 comments on commit 47629c1

Please sign in to comment.