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
00038 #include <gtest/gtest.h>
00039
00040 #include <pcl/point_types.h>
00041 #include <pcl/io/pcd_io.h>
00042 #include <pcl/kdtree/kdtree_flann.h>
00043
00044 #include <pcl/keypoints/sift_keypoint.h>
00045
00046 using namespace pcl;
00047 using namespace pcl::io;
00048 using namespace std;
00049
00050 struct KeypointT
00051 {
00052 float x, y, z, scale;
00053 };
00054
00056 TEST (PCL, SIFTKeypoint)
00057 {
00058 PointCloud<PointXYZI>::Ptr cloud_xyzi (new PointCloud<PointXYZI> ());
00059 PointCloud<KeypointT> keypoints;
00060
00061
00062 io::loadPCDFile ("./test/cturtle.pcd", *cloud_xyzi);
00063
00064
00065 SIFTKeypoint<PointXYZI, KeypointT> sift_detector;
00066 sift_detector.setSearchMethod (boost::make_shared<KdTreeFLANN<PointXYZI> > ());
00067 sift_detector.setScales (0.02, 5, 3);
00068 sift_detector.setMinimumContrast (0.03);
00069
00070 sift_detector.setInputCloud (cloud_xyzi);
00071 sift_detector.compute (keypoints);
00072
00073 EXPECT_EQ ((int)keypoints.points.size (), 169);
00074
00075
00076 sift_detector.setScales (0.05, 5, 3);
00077 sift_detector.setMinimumContrast (0.06);
00078 sift_detector.compute (keypoints);
00079
00080
00081 const int correct_nr_keypoints = 5;
00082 const float correct_keypoints[correct_nr_keypoints][4] =
00083 {
00084
00085 {-0.9425, -0.6381, 1.6445, 0.0794},
00086 {-0.5083, -0.5587, 1.8519, 0.0500},
00087 { 1.0265, 0.0500, 1.7154, 0.1000},
00088 { 0.3005, -0.3007, 1.9526, 0.2000},
00089 {-0.1002, -0.1002, 1.9933, 0.3175}
00090 };
00091
00092 ASSERT_EQ ((int)keypoints.points.size (), correct_nr_keypoints);
00093 for (int i = 0; i < correct_nr_keypoints; ++i)
00094 {
00095 EXPECT_NEAR (keypoints.points[i].x, correct_keypoints[i][0], 1e-4);
00096 EXPECT_NEAR (keypoints.points[i].y, correct_keypoints[i][1], 1e-4);
00097 EXPECT_NEAR (keypoints.points[i].z, correct_keypoints[i][2], 1e-4);
00098 EXPECT_NEAR (keypoints.points[i].scale, correct_keypoints[i][3], 1e-4);
00099 }
00100
00101 }
00102
00103
00104 int
00105 main (int argc, char** argv)
00106 {
00107 testing::InitGoogleTest (&argc, argv);
00108 return (RUN_ALL_TESTS ());
00109 }
00110