FODDetector.cpp
Go to the documentation of this file.
1 
18 #include <FODDetector.h>
19 #include <pcl/segmentation/extract_clusters.h>
20 
21 FODDetector::FODDetector(PointCloudRGB::Ptr cloud, double cluster_tolerance, double min_fod_points)
22  : cloud_(cloud)
23 {
24  setClusterTolerance(cluster_tolerance);
25  setMinFODpoints(min_fod_points);
26 }
27 
28 void FODDetector::setClusterTolerance(double tolerance)
29 {
30  if(tolerance == 0)
31  {
32  ROS_WARN("FODDetector: invalid tolerance value: %f", tolerance);
33  cluster_tolerance_ = 4e-3; //default
34  }
35  else
36  cluster_tolerance_ = tolerance;
37  ROS_INFO("FODDetector: cluster tolerance set to: %f", cluster_tolerance_);
38 }
39 
40 void FODDetector::setMinFODpoints(double min_fod_points)
41 {
42  min_cluster_size_ = min_fod_points;
43 }
44 
46 {
47  pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZRGB>);
48  tree->setInputCloud(cloud_);
49 
50  pcl::EuclideanClusterExtraction<pcl::PointXYZRGB> ec;
51  ec.setClusterTolerance(cluster_tolerance_);
52  ec.setMinClusterSize(min_cluster_size_);
53  // ec.setMaxClusterSize(1000);
54  ec.setSearchMethod(tree);
55  ec.setInputCloud(cloud_);
56  ec.extract(cluster_indices_);
57  ROS_INFO("cluster_indices_size: %zd", cluster_indices_.size());
58 }
59 
60 int FODDetector::fodIndicesToPointCloud(std::vector<PointCloudRGB::Ptr>& fod_cloud_array)
61 {
62  int n_fods = 0;
63 
64  for (std::vector<pcl::PointIndices>::const_iterator it=cluster_indices_.begin(); it!=cluster_indices_.end(); ++it)
65  {
66  PointCloudRGB::Ptr cloud_cluster(new PointCloudRGB);
67  for (std::vector<int>::const_iterator pit = it->indices.begin(); pit != it->indices.end(); ++pit)
68  cloud_cluster->points.push_back(cloud_->points[*pit]);
69  cloud_cluster->width = cloud_cluster->points.size();
70  cloud_cluster->height = 1;
71  cloud_cluster->is_dense = true;
72  ROS_INFO("cluster_size: %zd", cloud_cluster->points.size());
73 
74  fod_cloud_array.push_back(cloud_cluster);
75  n_fods++;
76  }
77  return n_fods;
78 }
79 
80 int FODDetector::fodIndicesToROSMsg(std::vector<sensor_msgs::PointCloud2>& fod_msg_array)
81 {
82  std::vector<PointCloudRGB::Ptr> fod_cloud_array;
83  int n_fods = fodIndicesToPointCloud(fod_cloud_array);
84 
85  sensor_msgs::PointCloud2 cluster_msg;
86  for (const auto &cloud : fod_cloud_array)
87  {
88  Utils::cloudToROSMsg(cloud, cluster_msg);
89  fod_msg_array.push_back(cluster_msg);
90  }
91 
92  ROS_INFO("n_fods: %d", n_fods);
93  ROS_INFO("msg_size: %zd", fod_msg_array.size());
94 
95  // int n_fods = 0;
96 
97  // for (std::vector<pcl::PointIndices>::const_iterator it=cluster_indices_.begin(); it!=cluster_indices_.end(); ++it)
98  // {
99  // PointCloudRGB::Ptr cloud_cluster(new PointCloudRGB);
100  // for (std::vector<int>::const_iterator pit = it->indices.begin(); pit != it->indices.end(); ++pit)
101  // cloud_cluster->points.push_back(cloud_->points[*pit]);
102  // cloud_cluster->width = cloud_cluster->points.size();
103  // cloud_cluster->height = 1;
104  // cloud_cluster->is_dense = true;
105 
106  // n_fods++;
107 
108  // }
109  return n_fods;
110 }
111 
112 void FODDetector::getFODIndices(std::vector<pcl::PointIndices>& fod_indices)
113 {
114  fod_indices = cluster_indices_;
115 }
int fodIndicesToPointCloud(std::vector< PointCloudRGB::Ptr > &cloud_array)
Save each cluster (possible FOD) in a pcl::PointCloudRGB. Give back an array of all generated clouds...
Definition: FODDetector.cpp:60
double cluster_tolerance_
Tolerance to set as cluster tolerance.
Definition: FODDetector.h:96
void getFODIndices(std::vector< pcl::PointIndices > &fod_indices)
Get the FOD indices computed in clusterPossibleFODs()
#define ROS_WARN(...)
static void cloudToROSMsg(PointCloudRGB::Ptr cloud, sensor_msgs::PointCloud2 &cloud_msg, const std::string &frameid="world")
Convert XYZRGB cloud to PointCloud2.
Definition: Utils.cpp:100
#define ROS_INFO(...)
PointCloudRGB::Ptr cloud_
Input cloud.
Definition: FODDetector.h:102
void setClusterTolerance(double tolerance)
Set the Cluster Tolerance object.
Definition: FODDetector.cpp:28
pcl::PointCloud< pcl::PointXYZRGB > PointCloudRGB
Definition: FODDetector.h:27
std::vector< pcl::PointIndices > cluster_indices_
Cluster indices to be identified as FODs.
Definition: FODDetector.h:105
void clusterPossibleFODs()
Extract cluster indices from input cloud with resolution set. Each cluster is a possible FOD...
Definition: FODDetector.cpp:45
int fodIndicesToROSMsg(std::vector< sensor_msgs::PointCloud2 > &cluster_msg_array)
Save each cluster (possible FOD) in a PointCloud2 msg. Give back an array of all generated msgs...
Definition: FODDetector.cpp:80
FODDetector(PointCloudRGB::Ptr cloud, double cluster_tolerance, double min_fod_points)
Construct a new FODDetector object with given tolerance and minimal fod points.
Definition: FODDetector.cpp:21
void setMinFODpoints(double min_fod_points)
Set the Min FOD points object.
Definition: FODDetector.cpp:40
double min_cluster_size_
Min number of points to identify a cluster.
Definition: FODDetector.h:99


leica_point_cloud_processing
Author(s): Ines Lara Sicilia
autogenerated on Mon Feb 28 2022 22:40:47