#include <pcl/search/kdtree.h>
#include <pcl/segmentation/extract_clusters.h>
Go to the source code of this file.
|
void | Velodyne::addRange (pcl::PointCloud< Velodyne::Point > &pc) |
|
void | colourCenters (const std::vector< pcl::PointXYZ > pc, pcl::PointCloud< pcl::PointXYZI >::Ptr coloured) |
|
void | comb (int N, int K, std::vector< std::vector< int >> &groups) |
|
const std::string | currentDateTime () |
|
void | getCenterClusters (pcl::PointCloud< pcl::PointXYZ >::Ptr cloud_in, pcl::PointCloud< pcl::PointXYZ >::Ptr centers_cloud, double cluster_tolerance=0.10, int min_cluster_size=15, int max_cluster_size=200, bool verbosity=true) |
|
vector< vector< Point * > > | Velodyne::getRings (pcl::PointCloud< Velodyne::Point > &pc, int rings_count) |
|
Eigen::Affine3f | getRotationMatrix (Eigen::Vector3f source, Eigen::Vector3f target) |
|
void | Velodyne::normalizeIntensity (pcl::PointCloud< Point > &pc, float minv, float maxv) |
|
| POINT_CLOUD_REGISTER_POINT_STRUCT (Velodyne::Point,(float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(std::uint16_t, ring, ring)(float, range, range)) |
|
void | sortPatternCenters (pcl::PointCloud< pcl::PointXYZ >::Ptr pc, vector< pcl::PointXYZ > &v) |
|
#define GEOMETRY_TOLERANCE 0.06 |
#define PCL_NO_PRECOMPILE |
#define TARGET_NUM_CIRCLES 4 |
#define TARGET_RADIUS 0.12 |
void colourCenters |
( |
const std::vector< pcl::PointXYZ > |
pc, |
|
|
pcl::PointCloud< pcl::PointXYZI >::Ptr |
coloured |
|
) |
| |
void comb |
( |
int |
N, |
|
|
int |
K, |
|
|
std::vector< std::vector< int >> & |
groups |
|
) |
| |
const std::string currentDateTime |
( |
| ) |
|
void getCenterClusters |
( |
pcl::PointCloud< pcl::PointXYZ >::Ptr |
cloud_in, |
|
|
pcl::PointCloud< pcl::PointXYZ >::Ptr |
centers_cloud, |
|
|
double |
cluster_tolerance = 0.10 , |
|
|
int |
min_cluster_size = 15 , |
|
|
int |
max_cluster_size = 200 , |
|
|
bool |
verbosity = true |
|
) |
| |
Eigen::Affine3f getRotationMatrix |
( |
Eigen::Vector3f |
source, |
|
|
Eigen::Vector3f |
target |
|
) |
| |
POINT_CLOUD_REGISTER_POINT_STRUCT |
( |
Velodyne::Point |
, |
|
|
(float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(std::uint16_t, ring, ring)(float, range, range) |
|
|
) |
| |
void sortPatternCenters |
( |
pcl::PointCloud< pcl::PointXYZ >::Ptr |
pc, |
|
|
vector< pcl::PointXYZ > & |
v |
|
) |
| |