Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #include <gtest/gtest.h>
00041 #include <pcl/kdtree/kdtree_flann.h>
00042 #include <pcl/point_types.h>
00043 #include <pcl/point_cloud.h>
00044 #include <pcl/io/pcd_io.h>
00045
00046 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00047 #include <pcl/segmentation/segment_differences.h>
00048
00049 using namespace pcl;
00050 using namespace pcl::io;
00051
00052 PointCloud<PointXYZ>::Ptr cloud_;
00053 PointCloud<PointXYZ>::Ptr cloud_t_;
00054 KdTree<PointXYZ>::Ptr tree_;
00055
00057 TEST (SegmentDifferences, Segmentation)
00058 {
00059 SegmentDifferences<PointXYZ> sd;
00060 sd.setInputCloud (cloud_);
00061 sd.setDistanceThreshold (0.00005);
00062
00063
00064 sd.setTargetCloud (cloud_);
00065
00066 PointCloud<PointXYZ> output;
00067 sd.segment (output);
00068
00069 EXPECT_EQ (static_cast<int> (output.points.size ()), 0);
00070
00071
00072 sd.setTargetCloud (cloud_t_);
00073 sd.segment (output);
00074 EXPECT_EQ (static_cast<int> (output.points.size ()), 126);
00075
00076
00077
00078 sd.setInputCloud (cloud_t_);
00079 sd.setTargetCloud (cloud_);
00080 sd.segment (output);
00081 EXPECT_EQ (static_cast<int> (output.points.size ()), 127);
00082
00083 }
00084
00086 TEST (ExtractPolygonalPrism, Segmentation)
00087 {
00088 PointCloud<PointXYZ>::Ptr hull (new PointCloud<PointXYZ>);
00089 hull->points.resize (5);
00090
00091 for (size_t i = 0; i < hull->points.size (); ++i)
00092 {
00093 hull->points[i].x = hull->points[i].y = static_cast<float> (i);
00094 hull->points[i].z = 0.0f;
00095 }
00096
00097 ExtractPolygonalPrismData<PointXYZ> ex;
00098 ex.setInputCloud (cloud_);
00099 ex.setInputPlanarHull (hull);
00100
00101 PointIndices output;
00102 ex.segment (output);
00103
00104 EXPECT_EQ (static_cast<int> (output.indices.size ()), 0);
00105 }
00106
00107
00108 int
00109 main (int argc, char** argv)
00110 {
00111 if (argc < 2)
00112 {
00113 std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00114 return (-1);
00115 }
00116
00117
00118 PointCloud<PointXYZ> cloud, cloud_t;
00119 if (loadPCDFile (argv[1], cloud) < 0)
00120 {
00121 std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00122 return (-1);
00123 }
00124
00125
00126 cloud_t = cloud;
00127 for (size_t i = 0; i < cloud.points.size (); ++i)
00128 cloud_t.points[i].x += 0.01f;
00129
00130 cloud_ = cloud.makeShared ();
00131 cloud_t_ = cloud_t.makeShared ();
00132
00133 testing::InitGoogleTest (&argc, argv);
00134 return (RUN_ALL_TESTS ());
00135 }
00136