Public Member Functions | |
void | computeForOneCloud (pcl::PointCloud< PointT >::ConstPtr cloud) |
void | computeForOneCloud (PointCloud< PointXYZRGB >::ConstPtr cloud) |
PerformanceTester () | |
PerformanceTester () | |
Private Attributes | |
ST::Graph::Ptr | g |
PointCloud< PointLabel >::Ptr | l |
PointCloud< Normal >::Ptr | n |
cob_3d_features::OrganizedNormalEstimationOMP < PointXYZRGB, Normal, PointLabel > | one |
pcl::PointCloud< PointT >::Ptr | p_vox |
PlaneExtraction | pe |
cob_3d_segmentation::DepthSegmentation < ST::Graph, ST::Point, ST::Normal, ST::Label > | seg |
std::vector< pcl::PointCloud < PointT > , Eigen::aligned_allocator < pcl::PointCloud< PointT > > > | v_cloud_hull |
std::vector < pcl::ModelCoefficients > | v_coefficients_plane |
std::vector< std::vector < pcl::Vertices > > | v_hull_polygons |
pcl::VoxelGrid< PointT > | voxel |
Definition at line 79 of file profile_depth_seg.cpp.
PerformanceTester::PerformanceTester | ( | ) | [inline] |
Definition at line 82 of file profile_depth_seg.cpp.
PerformanceTester::PerformanceTester | ( | ) | [inline] |
Definition at line 80 of file profile_plane_extraction.cpp.
void PerformanceTester::computeForOneCloud | ( | pcl::PointCloud< PointT >::ConstPtr | cloud | ) | [inline] |
Definition at line 91 of file profile_plane_extraction.cpp.
void PerformanceTester::computeForOneCloud | ( | PointCloud< PointXYZRGB >::ConstPtr | cloud | ) | [inline] |
Definition at line 96 of file profile_depth_seg.cpp.
ST::Graph::Ptr PerformanceTester::g [private] |
Definition at line 113 of file profile_depth_seg.cpp.
PointCloud<PointLabel>::Ptr PerformanceTester::l [private] |
Definition at line 111 of file profile_depth_seg.cpp.
PointCloud<Normal>::Ptr PerformanceTester::n [private] |
Definition at line 112 of file profile_depth_seg.cpp.
cob_3d_features::OrganizedNormalEstimationOMP<PointXYZRGB, Normal, PointLabel> PerformanceTester::one [private] |
Definition at line 115 of file profile_depth_seg.cpp.
pcl::PointCloud<PointT>::Ptr PerformanceTester::p_vox [private] |
Definition at line 104 of file profile_plane_extraction.cpp.
PlaneExtraction PerformanceTester::pe [private] |
Definition at line 110 of file profile_plane_extraction.cpp.
cob_3d_segmentation::DepthSegmentation<ST::Graph, ST::Point, ST::Normal, ST::Label> PerformanceTester::seg [private] |
Definition at line 114 of file profile_depth_seg.cpp.
std::vector<pcl::PointCloud<PointT>, Eigen::aligned_allocator<pcl::PointCloud<PointT> > > PerformanceTester::v_cloud_hull [private] |
Definition at line 105 of file profile_plane_extraction.cpp.
std::vector<pcl::ModelCoefficients> PerformanceTester::v_coefficients_plane [private] |
Definition at line 107 of file profile_plane_extraction.cpp.
std::vector<std::vector<pcl::Vertices> > PerformanceTester::v_hull_polygons [private] |
Definition at line 106 of file profile_plane_extraction.cpp.
pcl::VoxelGrid<PointT> PerformanceTester::voxel [private] |
Definition at line 109 of file profile_plane_extraction.cpp.