Typedefs | Functions | Variables
test_shot_estimation.cpp File Reference
#include <gtest/gtest.h>
#include <pcl/point_cloud.h>
#include <pcl/features/normal_3d_omp.h>
#include <pcl/io/pcd_io.h>
#include <pcl/features/shot.h>
#include <pcl/features/shot_omp.h>
#include <pcl/features/3dsc.h>
#include <pcl/features/usc.h>
Include dependency graph for test_shot_estimation.cpp:

Go to the source code of this file.

Typedefs

typedef search::KdTree
< PointXYZ >::Ptr 
KdTreePtr

Functions

template<typename FeatureEstimation , typename PointT , typename NormalT , typename OutputT >
FeatureEstimation createSHOTDesc (const typename PointCloud< NormalT >::Ptr &normals, const int nr_shape_bins=10, const int=30, const bool=true, const bool=false)
template<typename FeatureEstimation , typename NormalT , typename OutputT >
FeatureEstimation createSHOTDesc (const typename PointCloud< NormalT >::Ptr &normals, const int nr_shape_bins=10, const int nr_color_bins=30, const bool describe_shape=true, const bool describe_color=false)
template<>
ShapeContext3DEstimation
< PointXYZ, Normal, SHOT
createSHOTDesc< ShapeContext3DEstimation< PointXYZ, Normal, SHOT >, PointXYZ, Normal, SHOT > (const PointCloud< Normal >::Ptr &normals, const int, const int, const bool, const bool)
template<>
UniqueShapeContext< PointXYZ,
SHOT
createSHOTDesc< UniqueShapeContext< PointXYZ, SHOT >, PointXYZ, Normal, SHOT > (const PointCloud< Normal >::Ptr &, const int, const int, const bool, const bool)
int main (int argc, char **argv)
void shotCopyPointCloud (const PointCloud< SHOT > &cloud_in, const std::vector< int > &indices, PointCloud< SHOT > &cloud_out)
 TEST (PCL, SHOTShapeEstimation)
 TEST (PCL, GenericSHOTShapeEstimation)
 TEST (PCL, SHOTShapeAndColorEstimation)
 TEST (PCL, SHOTShapeEstimationOpenMP)
 TEST (PCL, SHOTShapeAndColorEstimationOpenMP)
 TEST (PCL, 3DSCEstimation)
 TEST (PCL, USCEstimation)
 TEST (PCL, SHOTShapeEstimationEigen)
 TEST (PCL, GenericSHOTShapeEstimationEigen)
 TEST (PCL, SHOTShapeAndColorEstimationEigen)
 TEST (PCL, 3DSCEstimationEigen)
 TEST (PCL, USCEstimationEigen)
template<typename FeatureEstimation , typename PointT , typename NormalT , typename OutputT >
void testSHOTIndicesAndSearchSurface (const typename PointCloud< PointT >::Ptr &points, const typename PointCloud< NormalT >::Ptr &normals, const boost::shared_ptr< vector< int > > &indices, const int nr_shape_bins=10, const int nr_color_bins=30, const bool describe_shape=true, const bool describe_color=false)
template<typename FeatureEstimation , typename PointT , typename NormalT >
void testSHOTIndicesAndSearchSurfaceEigen (const typename PointCloud< PointT >::Ptr &points, const typename PointCloud< NormalT >::Ptr &normals, const boost::shared_ptr< vector< int > > &indices, const int nr_shape_bins=10, const int nr_color_bins=30, const bool describe_shape=true, const bool describe_color=false)

Variables

PointCloud< PointXYZcloud
vector< int > indices
KdTreePtr tree

Typedef Documentation

Definition at line 53 of file test_shot_estimation.cpp.


Function Documentation

template<typename FeatureEstimation , typename PointT , typename NormalT , typename OutputT >
FeatureEstimation createSHOTDesc ( const typename PointCloud< NormalT >::Ptr &  normals,
const int  nr_shape_bins = 10,
const int  = 30,
const bool  = true,
const bool  = false 
)

Definition at line 88 of file test_shot_estimation.cpp.

template<typename FeatureEstimation , typename NormalT , typename OutputT >
FeatureEstimation createSHOTDesc ( const typename PointCloud< NormalT >::Ptr &  normals,
const int  nr_shape_bins = 10,
const int  nr_color_bins = 30,
const bool  describe_shape = true,
const bool  describe_color = false 
)

Definition at line 101 of file test_shot_estimation.cpp.

template<>
ShapeContext3DEstimation<PointXYZ, Normal, SHOT> createSHOTDesc< ShapeContext3DEstimation< PointXYZ, Normal, SHOT >, PointXYZ, Normal, SHOT > ( const PointCloud< Normal >::Ptr &  normals,
const int  ,
const int  ,
const bool  ,
const bool   
)

Definition at line 114 of file test_shot_estimation.cpp.

template<>
UniqueShapeContext<PointXYZ, SHOT> createSHOTDesc< UniqueShapeContext< PointXYZ, SHOT >, PointXYZ, Normal, SHOT > ( const PointCloud< Normal >::Ptr &  ,
const int  ,
const int  ,
const bool  ,
const bool   
)

Definition at line 133 of file test_shot_estimation.cpp.

int main ( int  argc,
char **  argv 
)

Definition at line 1187 of file test_shot_estimation.cpp.

void shotCopyPointCloud ( const PointCloud< SHOT > &  cloud_in,
const std::vector< int > &  indices,
PointCloud< SHOT > &  cloud_out 
)

Definition at line 61 of file test_shot_estimation.cpp.

TEST ( PCL  ,
SHOTShapeEstimation   
)

Definition at line 234 of file test_shot_estimation.cpp.

TEST ( PCL  ,
GenericSHOTShapeEstimation   
)

Definition at line 298 of file test_shot_estimation.cpp.

TEST ( PCL  ,
SHOTShapeAndColorEstimation   
)

Definition at line 353 of file test_shot_estimation.cpp.

TEST ( PCL  ,
SHOTShapeEstimationOpenMP   
)

Definition at line 432 of file test_shot_estimation.cpp.

TEST ( PCL  ,
SHOTShapeAndColorEstimationOpenMP   
)

Definition at line 484 of file test_shot_estimation.cpp.

TEST ( PCL  ,
3DSCEstimation   
)

Definition at line 566 of file test_shot_estimation.cpp.

TEST ( PCL  ,
USCEstimation   
)

Definition at line 651 of file test_shot_estimation.cpp.

TEST ( PCL  ,
SHOTShapeEstimationEigen   
)

Definition at line 837 of file test_shot_estimation.cpp.

TEST ( PCL  ,
GenericSHOTShapeEstimationEigen   
)

Definition at line 900 of file test_shot_estimation.cpp.

TEST ( PCL  ,
SHOTShapeAndColorEstimationEigen   
)

Definition at line 955 of file test_shot_estimation.cpp.

TEST ( PCL  ,
3DSCEstimationEigen   
)

Definition at line 1034 of file test_shot_estimation.cpp.

TEST ( PCL  ,
USCEstimationEigen   
)

Definition at line 1121 of file test_shot_estimation.cpp.

template<typename FeatureEstimation , typename PointT , typename NormalT , typename OutputT >
void testSHOTIndicesAndSearchSurface ( const typename PointCloud< PointT >::Ptr &  points,
const typename PointCloud< NormalT >::Ptr &  normals,
const boost::shared_ptr< vector< int > > &  indices,
const int  nr_shape_bins = 10,
const int  nr_color_bins = 30,
const bool  describe_shape = true,
const bool  describe_color = false 
)

Definition at line 152 of file test_shot_estimation.cpp.

template<typename FeatureEstimation , typename PointT , typename NormalT >
void testSHOTIndicesAndSearchSurfaceEigen ( const typename PointCloud< PointT >::Ptr &  points,
const typename PointCloud< NormalT >::Ptr &  normals,
const boost::shared_ptr< vector< int > > &  indices,
const int  nr_shape_bins = 10,
const int  nr_color_bins = 30,
const bool  describe_shape = true,
const bool  describe_color = false 
)

Definition at line 755 of file test_shot_estimation.cpp.


Variable Documentation

Definition at line 55 of file test_shot_estimation.cpp.

vector<int> indices

Definition at line 56 of file test_shot_estimation.cpp.

Definition at line 57 of file test_shot_estimation.cpp.



pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:14