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/point_cloud.h>
00042 #include <pcl/features/rift.h>
00043 
00044 using namespace pcl;
00045 using namespace std;
00046 
00048 TEST (PCL, RIFTEstimation)
00049 {
00050   
00051   PointCloud<PointXYZI> cloud_xyzi;
00052   cloud_xyzi.height = 1;
00053   cloud_xyzi.is_dense = true;
00054   for (float x = -10.0f; x <= 10.0f; x += 1.0f)
00055   {
00056     for (float y = -10.0f; y <= 10.0f; y += 1.0f)
00057     {
00058       PointXYZI p;
00059       p.x = x;
00060       p.y = y;
00061       p.z = sqrtf (400 - x * x - y * y);
00062       p.intensity = expf ((-powf (x - 3.0f, 2.0f) + powf (y + 2.0f, 2.0f)) / (2.0f * 25.0f)) + expf ((-powf (x + 5.0f, 2.0f) + powf (y - 5.0f, 2.0f))
00063                                                                                  / (2.0f * 4.0f));
00064 
00065       cloud_xyzi.points.push_back (p);
00066     }
00067   }
00068   cloud_xyzi.width = static_cast<uint32_t> (cloud_xyzi.points.size ());
00069 
00070   
00071   PointCloud<IntensityGradient> gradient;
00072   gradient.height = 1;
00073   gradient.width = static_cast<uint32_t> (cloud_xyzi.points.size ());
00074   gradient.is_dense = true;
00075   gradient.points.resize (gradient.width);
00076   for (size_t i = 0; i < cloud_xyzi.points.size (); ++i)
00077   {
00078     const PointXYZI &p = cloud_xyzi.points[i];
00079 
00080     
00081     float nx = p.x;
00082     float ny = p.y;
00083     float nz = p.z;
00084     float magnitude = sqrtf (nx * nx + ny * ny + nz * nz);
00085     nx /= magnitude;
00086     ny /= magnitude;
00087     nz /= magnitude;
00088 
00089     
00090     float tmpx = -(p.x + 5.0f) / 4.0f / expf ((powf (p.x + 5.0f, 2.0f) + powf (p.y - 5.0f, 2.0f)) / 8.0f) - (p.x - 3.0f) / 25.0f
00091         / expf ((powf (p.x - 3.0f, 2.0f) + powf (p.y + 2.0f, 2.0f)) / 50.0f);
00092     float tmpy = -(p.y - 5.0f) / 4.0f / expf ((powf (p.x + 5.0f, 2.0f) + powf (p.y - 5.0f, 2.0f)) / 8.0f) - (p.y + 2.0f) / 25.0f
00093         / expf ((powf (p.x - 3.0f, 2.0f) + powf (p.y + 2.0f, 2.0f)) / 50.0f);
00094     float tmpz = 0.0f;
00095     
00096     float gx = (1 - nx * nx) * tmpx + (-nx * ny) * tmpy + (-nx * nz) * tmpz;
00097     float gy = (-ny * nx) * tmpx + (1 - ny * ny) * tmpy + (-ny * nz) * tmpz;
00098     float gz = (-nz * nx) * tmpx + (-nz * ny) * tmpy + (1 - nz * nz) * tmpz;
00099 
00100     gradient.points[i].gradient[0] = gx;
00101     gradient.points[i].gradient[1] = gy;
00102     gradient.points[i].gradient[2] = gz;
00103   }
00104 
00105   
00106   typedef Histogram<32> RIFTDescriptor;
00107   RIFTEstimation<PointXYZI, IntensityGradient, RIFTDescriptor> rift_est;
00108   search::KdTree<PointXYZI>::Ptr treept4 (new search::KdTree<PointXYZI> (false));
00109   rift_est.setSearchMethod (treept4);
00110   rift_est.setRadiusSearch (10.0);
00111   rift_est.setNrDistanceBins (4);
00112   rift_est.setNrGradientBins (8);
00113 
00114   rift_est.setInputCloud (cloud_xyzi.makeShared ());
00115   rift_est.setInputGradient (gradient.makeShared ());
00116   PointCloud<RIFTDescriptor> rift_output;
00117   rift_est.compute (rift_output);
00118 
00119   
00120   const RIFTDescriptor &rift = rift_output.points[220];
00121   const float correct_rift_feature_values[32] = {0.0187f, 0.0349f, 0.0647f, 0.0881f, 0.0042f, 0.0131f, 0.0346f, 0.0030f,
00122                                                  0.0076f, 0.0218f, 0.0463f, 0.0030f, 0.0087f, 0.0288f, 0.0920f, 0.0472f,
00123                                                  0.0076f, 0.0420f, 0.0726f, 0.0669f, 0.0090f, 0.0901f, 0.1274f, 0.2185f,
00124                                                  0.0147f, 0.1222f, 0.3568f, 0.4348f, 0.0149f, 0.0806f, 0.2787f, 0.6864f};
00125   for (int i = 0; i < 32; ++i)
00126     EXPECT_NEAR (rift.histogram[i], correct_rift_feature_values[i], 1e-4);
00127 }
00128 
00129 
00130 int
00131 main (int argc, char** argv)
00132 {
00133   testing::InitGoogleTest (&argc, argv);
00134   return (RUN_ALL_TESTS ());
00135 }
00136