#include <vector>
#include <cmath>
#include <unistd.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/kdtree/kdtree.h>
#include <pcl/segmentation/extract_clusters.h>
#include <pcl/common/eigen.h>
#include <pcl/common/transforms.h>
#include <ros/ros.h>
Go to the source code of this file.
|
void | Velodyne::addRange (pcl::PointCloud< Velodyne::Point > &pc) |
|
void | colourCenters (const pcl::PointCloud< pcl::PointXYZ >::Ptr pc, pcl::PointCloud< pcl::PointXYZI >::Ptr coloured) |
|
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) |
|
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)(uint16_t, ring, ring)(float, range, range)) |
|
void | sortPatternCentersXY (pcl::PointCloud< pcl::PointXYZ >::Ptr pc, vector< pcl::PointXYZ > &v) |
|
void | sortPatternCentersYZ (pcl::PointCloud< pcl::PointXYZ >::Ptr pc, vector< pcl::PointXYZ > &v) |
|
#define PCL_NO_PRECOMPILE |
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)(uint16_t, ring, ring)(float, range, range) |
|
|
) |
| |
void sortPatternCentersXY |
( |
pcl::PointCloud< pcl::PointXYZ >::Ptr |
pc, |
|
|
vector< pcl::PointXYZ > & |
v |
|
) |
| |
void sortPatternCentersYZ |
( |
pcl::PointCloud< pcl::PointXYZ >::Ptr |
pc, |
|
|
vector< pcl::PointXYZ > & |
v |
|
) |
| |
const int RINGS_COUNT = 16 |
|
static |