Classes | Namespaces | Macros | Functions | Variables
velo2cam_utils.h File Reference
#include <pcl/search/kdtree.h>
#include <pcl/segmentation/extract_clusters.h>
Include dependency graph for velo2cam_utils.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  Velodyne::Point
 
class  Square
 

Namespaces

 Velodyne
 

Macros

#define DEBUG   0
 
#define GEOMETRY_TOLERANCE   0.06
 
#define PCL_NO_PRECOMPILE
 
#define TARGET_NUM_CIRCLES   4
 
#define TARGET_RADIUS   0.12
 

Functions

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)
 

Variables

struct Velodyne::Point Velodyne::EIGEN_ALIGN16
 

Macro Definition Documentation

#define DEBUG   0

Definition at line 30 of file velo2cam_utils.h.

#define GEOMETRY_TOLERANCE   0.06

Definition at line 37 of file velo2cam_utils.h.

#define PCL_NO_PRECOMPILE

Definition at line 29 of file velo2cam_utils.h.

#define TARGET_NUM_CIRCLES   4

Definition at line 35 of file velo2cam_utils.h.

#define TARGET_RADIUS   0.12

Definition at line 36 of file velo2cam_utils.h.

Function Documentation

void colourCenters ( const std::vector< pcl::PointXYZ >  pc,
pcl::PointCloud< pcl::PointXYZI >::Ptr  coloured 
)

Definition at line 185 of file velo2cam_utils.h.

void comb ( int  N,
int  K,
std::vector< std::vector< int >> &  groups 
)

Definition at line 343 of file velo2cam_utils.h.

const std::string currentDateTime ( )

Definition at line 375 of file velo2cam_utils.h.

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 
)

Definition at line 200 of file velo2cam_utils.h.

Eigen::Affine3f getRotationMatrix ( Eigen::Vector3f  source,
Eigen::Vector3f  target 
)

Definition at line 240 of file velo2cam_utils.h.

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 
)

Definition at line 93 of file velo2cam_utils.h.



velo2cam_calibration
Author(s): Jorge Beltran , Carlos Guindel
autogenerated on Fri Feb 26 2021 03:40:57