FODDetector.h
Go to the documentation of this file.
1 
18 #pragma once
19 #ifndef _FOD_DETECTOR_H
20 #define _FOD_DETECTOR_H
21 
22 #include <Utils.h>
23 
25 {
26  typedef pcl::PointCloud<pcl::PointXYZ> PointCloudXYZ;
27  typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloudRGB;
28 
29 public:
35  FODDetector(PointCloudRGB::Ptr cloud, double cluster_tolerance, double min_fod_points);
36 
42 
48  void setClusterTolerance(double tolerance);
49 
55  void setMinFODpoints(double min_fod_points);
56 
63  void clusterPossibleFODs();
64 
70  void getFODIndices(std::vector<pcl::PointIndices>& fod_indices);
71 
81  int fodIndicesToROSMsg(std::vector<sensor_msgs::PointCloud2>& cluster_msg_array);
82 
92  int fodIndicesToPointCloud(std::vector<PointCloudRGB::Ptr>& cloud_array);
93 
94 private:
97 
100 
102  PointCloudRGB::Ptr cloud_;
103 
105  std::vector<pcl::PointIndices> cluster_indices_;
106 };
107 
108 #endif
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()
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
~FODDetector()
Destroy the FODDetector object.
Definition: FODDetector.h:41
void setMinFODpoints(double min_fod_points)
Set the Min FOD points object.
Definition: FODDetector.cpp:40
pcl::PointCloud< pcl::PointXYZ > PointCloudXYZ
Definition: FODDetector.h:26
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 Fri Feb 5 2021 03:20:30