19 #ifndef _FOD_DETECTOR_H 20 #define _FOD_DETECTOR_H 35 FODDetector(PointCloudRGB::Ptr cloud,
double cluster_tolerance,
double min_fod_points);
70 void getFODIndices(std::vector<pcl::PointIndices>& fod_indices);
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...
double cluster_tolerance_
Tolerance to set as cluster tolerance.
void getFODIndices(std::vector< pcl::PointIndices > &fod_indices)
Get the FOD indices computed in clusterPossibleFODs()
PointCloudRGB::Ptr cloud_
Input cloud.
void setClusterTolerance(double tolerance)
Set the Cluster Tolerance object.
pcl::PointCloud< pcl::PointXYZRGB > PointCloudRGB
std::vector< pcl::PointIndices > cluster_indices_
Cluster indices to be identified as FODs.
void clusterPossibleFODs()
Extract cluster indices from input cloud with resolution set. Each cluster is a possible FOD...
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...
FODDetector(PointCloudRGB::Ptr cloud, double cluster_tolerance, double min_fod_points)
Construct a new FODDetector object with given tolerance and minimal fod points.
~FODDetector()
Destroy the FODDetector object.
void setMinFODpoints(double min_fod_points)
Set the Min FOD points object.
pcl::PointCloud< pcl::PointXYZ > PointCloudXYZ
double min_cluster_size_
Min number of points to identify a cluster.