#include <FODDetector.h>
Definition at line 24 of file FODDetector.h.
FODDetector::FODDetector |
( |
PointCloudRGB::Ptr |
cloud, |
|
|
double |
cluster_tolerance, |
|
|
double |
min_fod_points |
|
) |
| |
FODDetector::~FODDetector |
( |
| ) |
|
|
inline |
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 | ) |
|
void FODDetector::setClusterTolerance |
( |
double |
tolerance | ) |
|
Set the Cluster Tolerance object.
- Parameters
-
Definition at line 28 of file FODDetector.cpp.
void FODDetector::setMinFODpoints |
( |
double |
min_fod_points | ) |
|
Set the Min FOD points object.
- Parameters
-
Definition at line 40 of file FODDetector.cpp.
PointCloudRGB::Ptr FODDetector::cloud_ |
|
private |
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: