#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/shot_lrf.h"
#include <pcl/features/3dsc.h>
#include <pcl/features/usc.h>
Go to the source code of this file.
Classes | |
struct | createSHOTDesc< FeatureEstimation, PointT, NormalT, OutputT > |
struct | createSHOTDesc< FeatureEstimation, PointT, NormalT, SHOT1344 > |
struct | createSHOTDesc< FeatureEstimation, PointT, NormalT, SHOT352 > |
struct | createSHOTDesc< ShapeContext3DEstimation< PointT, NormalT, OutputT >, PointT, NormalT, OutputT > |
struct | createSHOTDesc< UniqueShapeContext< PointT, OutputT >, PointT, NormalT, OutputT > |
Typedefs | |
typedef search::KdTree < PointXYZ >::Ptr | KdTreePtr |
Functions | |
template<typename PointT > | |
void | checkDesc (const pcl::PointCloud< PointT > &d0, const pcl::PointCloud< PointT > &d1) |
template<> | |
void | checkDesc< ShapeContext1980 > (const pcl::PointCloud< ShapeContext1980 > &d0, const pcl::PointCloud< ShapeContext1980 > &d1) |
template<> | |
void | checkDesc< SHOT1344 > (const pcl::PointCloud< SHOT1344 > &d0, const pcl::PointCloud< SHOT1344 > &d1) |
template<> | |
void | checkDesc< SHOT352 > (const pcl::PointCloud< SHOT352 > &d0, const pcl::PointCloud< SHOT352 > &d1) |
int | main (int argc, char **argv) |
template<typename PointT > | |
void | shotCopyPointCloud (const PointCloud< PointT > &cloud_in, const std::vector< int > &indices, PointCloud< PointT > &cloud_out) |
TEST (PCL, SHOTShapeEstimation) | |
TEST (PCL, SHOTShapeAndColorEstimation) | |
TEST (PCL, SHOTShapeEstimationOpenMP) | |
TEST (PCL, SHOTShapeAndColorEstimationOpenMP) | |
TEST (PCL, 3DSCEstimation) | |
TEST (PCL, USCEstimation) | |
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 , typename OutputT > | |
void | testSHOTLocalReferenceFrame (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< PointXYZ > | cloud |
vector< int > | indices |
KdTreePtr | tree |
typedef search::KdTree<PointXYZ>::Ptr KdTreePtr |
Definition at line 54 of file test_shot_estimation.cpp.
void checkDesc | ( | const pcl::PointCloud< PointT > & | d0, |
const pcl::PointCloud< PointT > & | d1 | ||
) |
Definition at line 70 of file test_shot_estimation.cpp.
void checkDesc< ShapeContext1980 > | ( | const pcl::PointCloud< ShapeContext1980 > & | d0, |
const pcl::PointCloud< ShapeContext1980 > & | d1 | ||
) |
Definition at line 100 of file test_shot_estimation.cpp.
void checkDesc< SHOT1344 > | ( | const pcl::PointCloud< SHOT1344 > & | d0, |
const pcl::PointCloud< SHOT1344 > & | d1 | ||
) |
Definition at line 90 of file test_shot_estimation.cpp.
void checkDesc< SHOT352 > | ( | const pcl::PointCloud< SHOT352 > & | d0, |
const pcl::PointCloud< SHOT352 > & | d1 | ||
) |
Definition at line 80 of file test_shot_estimation.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 982 of file test_shot_estimation.cpp.
void shotCopyPointCloud | ( | const PointCloud< PointT > & | cloud_in, |
const std::vector< int > & | indices, | ||
PointCloud< PointT > & | cloud_out | ||
) |
Definition at line 62 of file test_shot_estimation.cpp.
TEST | ( | PCL | , |
SHOTShapeEstimation | |||
) |
Definition at line 339 of file test_shot_estimation.cpp.
TEST | ( | PCL | , |
SHOTShapeAndColorEstimation | |||
) |
Definition at line 495 of file test_shot_estimation.cpp.
TEST | ( | PCL | , |
SHOTShapeEstimationOpenMP | |||
) |
Definition at line 619 of file test_shot_estimation.cpp.
TEST | ( | PCL | , |
SHOTShapeAndColorEstimationOpenMP | |||
) |
Definition at line 711 of file test_shot_estimation.cpp.
TEST | ( | PCL | , |
3DSCEstimation | |||
) |
Definition at line 839 of file test_shot_estimation.cpp.
TEST | ( | PCL | , |
USCEstimation | |||
) |
Definition at line 920 of file test_shot_estimation.cpp.
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 202 of file test_shot_estimation.cpp.
void testSHOTLocalReferenceFrame | ( | 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 274 of file test_shot_estimation.cpp.
Definition at line 56 of file test_shot_estimation.cpp.
vector<int> indices |
Definition at line 57 of file test_shot_estimation.cpp.
Definition at line 58 of file test_shot_estimation.cpp.