Public Member Functions | Private Types | Private Attributes | List of all members
FODDetector Class Reference

#include <FODDetector.h>

Public Member Functions

void clusterPossibleFODs ()
 Extract cluster indices from input cloud with resolution set. Each cluster is a possible FOD. More...
 
 FODDetector (PointCloudRGB::Ptr cloud, double cluster_tolerance, double min_fod_points)
 Construct a new FODDetector object with given tolerance and minimal fod points. More...
 
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.
Returns the number of possible FODs. More...
 
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.
Returns the number of possible FODs. More...
 
void getFODIndices (std::vector< pcl::PointIndices > &fod_indices)
 Get the FOD indices computed in clusterPossibleFODs() More...
 
void setClusterTolerance (double tolerance)
 Set the Cluster Tolerance object. More...
 
void setMinFODpoints (double min_fod_points)
 Set the Min FOD points object. More...
 
 ~FODDetector ()
 Destroy the FODDetector object. More...
 

Private Types

typedef pcl::PointCloud< pcl::PointXYZRGB > PointCloudRGB
 
typedef pcl::PointCloud< pcl::PointXYZ > PointCloudXYZ
 

Private Attributes

PointCloudRGB::Ptr cloud_
 Input cloud. More...
 
std::vector< pcl::PointIndices > cluster_indices_
 Cluster indices to be identified as FODs. More...
 
double cluster_tolerance_
 Tolerance to set as cluster tolerance. More...
 
double min_cluster_size_
 Min number of points to identify a cluster. More...
 

Detailed Description

Definition at line 24 of file FODDetector.h.

Member Typedef Documentation

typedef pcl::PointCloud<pcl::PointXYZRGB> FODDetector::PointCloudRGB
private

Definition at line 27 of file FODDetector.h.

typedef pcl::PointCloud<pcl::PointXYZ> FODDetector::PointCloudXYZ
private

Definition at line 26 of file FODDetector.h.

Constructor & Destructor Documentation

FODDetector::FODDetector ( PointCloudRGB::Ptr  cloud,
double  cluster_tolerance,
double  min_fod_points 
)

Construct a new FODDetector object with given tolerance and minimal fod points.

Parameters
tolerance

Definition at line 21 of file FODDetector.cpp.

FODDetector::~FODDetector ( )
inline

Destroy the FODDetector object.

Definition at line 41 of file FODDetector.h.

Member Function Documentation

void FODDetector::clusterPossibleFODs ( )

Extract cluster indices from input cloud with resolution set. Each cluster is a possible FOD.

Parameters
[in]cloud
[out]cluster_indices

Definition at line 45 of file FODDetector.cpp.

int FODDetector::fodIndicesToPointCloud ( std::vector< PointCloudRGB::Ptr > &  cloud_array)

Save each cluster (possible FOD) in a pcl::PointCloudRGB. Give back an array of all generated clouds.
Returns the number of possible FODs.

Parameters
[in]cluster_indices
[in]cloud
[out]cluster_msg_array
Returns
int number_of_fod

Definition at line 60 of file FODDetector.cpp.

int FODDetector::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.
Returns the number of possible FODs.

Parameters
[in]cluster_indices
[in]cloud
[out]cluster_msg_array
Returns
int number_of_fod

Definition at line 80 of file FODDetector.cpp.

void FODDetector::getFODIndices ( std::vector< pcl::PointIndices > &  fod_indices)

Get the FOD indices computed in clusterPossibleFODs()

Parameters
fod_indices

Definition at line 112 of file FODDetector.cpp.

void FODDetector::setClusterTolerance ( double  tolerance)

Set the Cluster Tolerance object.

Parameters
tolerance

Definition at line 28 of file FODDetector.cpp.

void FODDetector::setMinFODpoints ( double  min_fod_points)

Set the Min FOD points object.

Parameters
min_fod_points

Definition at line 40 of file FODDetector.cpp.

Member Data Documentation

PointCloudRGB::Ptr FODDetector::cloud_
private

Input cloud.

Definition at line 102 of file FODDetector.h.

std::vector<pcl::PointIndices> FODDetector::cluster_indices_
private

Cluster indices to be identified as FODs.

Definition at line 105 of file FODDetector.h.

double FODDetector::cluster_tolerance_
private

Tolerance to set as cluster tolerance.

Definition at line 96 of file FODDetector.h.

double FODDetector::min_cluster_size_
private

Min number of points to identify a cluster.

Definition at line 99 of file FODDetector.h.


The documentation for this class was generated from the following files:


leica_point_cloud_processing
Author(s): Ines Lara Sicilia
autogenerated on Fri Feb 5 2021 03:20:30