test_rift_estimation.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2012, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id$
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 
00047 #ifndef PCL_ONLY_CORE_POINT_TYPES
00048 
00049   TEST (PCL, RIFTEstimation)
00050   {
00051     // Generate a sample point cloud
00052     PointCloud<PointXYZI> cloud_xyzi;
00053     cloud_xyzi.height = 1;
00054     cloud_xyzi.is_dense = true;
00055     for (float x = -10.0f; x <= 10.0f; x += 1.0f)
00056     {
00057       for (float y = -10.0f; y <= 10.0f; y += 1.0f)
00058       {
00059         PointXYZI p;
00060         p.x = x;
00061         p.y = y;
00062         p.z = sqrtf (400 - x * x - y * y);
00063         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))
00064                                                                                    / (2.0f * 4.0f));
00065 
00066         cloud_xyzi.points.push_back (p);
00067       }
00068     }
00069     cloud_xyzi.width = static_cast<uint32_t> (cloud_xyzi.points.size ());
00070 
00071     // Generate the intensity gradient data
00072     PointCloud<IntensityGradient> gradient;
00073     gradient.height = 1;
00074     gradient.width = static_cast<uint32_t> (cloud_xyzi.points.size ());
00075     gradient.is_dense = true;
00076     gradient.points.resize (gradient.width);
00077     for (size_t i = 0; i < cloud_xyzi.points.size (); ++i)
00078     {
00079       const PointXYZI &p = cloud_xyzi.points[i];
00080 
00081       // Compute the surface normal analytically.
00082       float nx = p.x;
00083       float ny = p.y;
00084       float nz = p.z;
00085       float magnitude = sqrtf (nx * nx + ny * ny + nz * nz);
00086       nx /= magnitude;
00087       ny /= magnitude;
00088       nz /= magnitude;
00089 
00090       // Compute the intensity gradient analytically...
00091       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
00092           / expf ((powf (p.x - 3.0f, 2.0f) + powf (p.y + 2.0f, 2.0f)) / 50.0f);
00093       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
00094           / expf ((powf (p.x - 3.0f, 2.0f) + powf (p.y + 2.0f, 2.0f)) / 50.0f);
00095       float tmpz = 0.0f;
00096       // ...and project the 3-D gradient vector onto the surface's tangent plane.
00097       float gx = (1 - nx * nx) * tmpx + (-nx * ny) * tmpy + (-nx * nz) * tmpz;
00098       float gy = (-ny * nx) * tmpx + (1 - ny * ny) * tmpy + (-ny * nz) * tmpz;
00099       float gz = (-nz * nx) * tmpx + (-nz * ny) * tmpy + (1 - nz * nz) * tmpz;
00100 
00101       gradient.points[i].gradient[0] = gx;
00102       gradient.points[i].gradient[1] = gy;
00103       gradient.points[i].gradient[2] = gz;
00104     }
00105 
00106     // Compute the RIFT features
00107     typedef Histogram<32> RIFTDescriptor;
00108     RIFTEstimation<PointXYZI, IntensityGradient, RIFTDescriptor> rift_est;
00109     search::KdTree<PointXYZI>::Ptr treept4 (new search::KdTree<PointXYZI> (false));
00110     rift_est.setSearchMethod (treept4);
00111     rift_est.setRadiusSearch (10.0);
00112     rift_est.setNrDistanceBins (4);
00113     rift_est.setNrGradientBins (8);
00114 
00115     rift_est.setInputCloud (cloud_xyzi.makeShared ());
00116     rift_est.setInputGradient (gradient.makeShared ());
00117     PointCloud<RIFTDescriptor> rift_output;
00118     rift_est.compute (rift_output);
00119 
00120     // Compare to independently verified values
00121     const RIFTDescriptor &rift = rift_output.points[220];
00122     const float correct_rift_feature_values[32] = {0.0187f, 0.0349f, 0.0647f, 0.0881f, 0.0042f, 0.0131f, 0.0346f, 0.0030f,
00123                                                    0.0076f, 0.0218f, 0.0463f, 0.0030f, 0.0087f, 0.0288f, 0.0920f, 0.0472f,
00124                                                    0.0076f, 0.0420f, 0.0726f, 0.0669f, 0.0090f, 0.0901f, 0.1274f, 0.2185f,
00125                                                    0.0147f, 0.1222f, 0.3568f, 0.4348f, 0.0149f, 0.0806f, 0.2787f, 0.6864f};
00126     for (int i = 0; i < 32; ++i)
00127       EXPECT_NEAR (rift.histogram[i], correct_rift_feature_values[i], 1e-4);
00128   }
00129 
00131   TEST (PCL, RIFTEstimationEigen)
00132   {
00133     // Generate a sample point cloud
00134     PointCloud<PointXYZI> cloud_xyzi;
00135     cloud_xyzi.height = 1;
00136     cloud_xyzi.is_dense = true;
00137     for (float x = -10.0f; x <= 10.0f; x += 1.0f)
00138     {
00139       for (float y = -10.0f; y <= 10.0f; y += 1.0f)
00140       {
00141         PointXYZI p;
00142         p.x = x;
00143         p.y = y;
00144         p.z = sqrtf (400 - x * x - y * y);
00145         p.intensity = expf ((-powf (x - 3.0f, 2.0f) + pow (y + 2.0f, 2.0f)) / (2.0f * 25.0f)) + expf ((-powf (x + 5.0f, 2.0f) + powf (y - 5.0f, 2.0f))
00146                                                                                    / (2.0f * 4.0f));
00147 
00148         cloud_xyzi.points.push_back (p);
00149       }
00150     }
00151     cloud_xyzi.width = static_cast<uint32_t> (cloud_xyzi.points.size ());
00152 
00153     // Generate the intensity gradient data
00154     PointCloud<IntensityGradient> gradient;
00155     gradient.height = 1;
00156     gradient.width = static_cast<uint32_t> (cloud_xyzi.points.size ());
00157     gradient.is_dense = true;
00158     gradient.points.resize (gradient.width);
00159     for (size_t i = 0; i < cloud_xyzi.points.size (); ++i)
00160     {
00161       const PointXYZI &p = cloud_xyzi.points[i];
00162 
00163       // Compute the surface normal analytically.
00164       float nx = p.x;
00165       float ny = p.y;
00166       float nz = p.z;
00167       float magnitude = sqrtf (nx * nx + ny * ny + nz * nz);
00168       nx /= magnitude;
00169       ny /= magnitude;
00170       nz /= magnitude;
00171 
00172       // Compute the intensity gradient analytically...
00173       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
00174           / expf ((powf (p.x - 3.0f, 2.0f) + powf (p.y + 2.0f, 2.0f)) / 50.0f);
00175       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
00176           / expf ((powf (p.x - 3.0f, 2.0f) + powf (p.y + 2.0f, 2.0f)) / 50.0f);
00177       float tmpz = 0.0f;
00178       // ...and project the 3-D gradient vector onto the surface's tangent plane.
00179       float gx = (1.0f - nx * nx) * tmpx + (-nx * ny) * tmpy + (-nx * nz) * tmpz;
00180       float gy = (-ny * nx) * tmpx + (1.0f - ny * ny) * tmpy + (-ny * nz) * tmpz;
00181       float gz = (-nz * nx) * tmpx + (-nz * ny) * tmpy + (1.0f - nz * nz) * tmpz;
00182 
00183       gradient.points[i].gradient[0] = gx;
00184       gradient.points[i].gradient[1] = gy;
00185       gradient.points[i].gradient[2] = gz;
00186     }
00187 
00188     // Compute the RIFT features
00189     RIFTEstimation<PointXYZI, IntensityGradient, Eigen::MatrixXf> rift_est;
00190     search::KdTree<PointXYZI>::Ptr treept4 (new search::KdTree<PointXYZI> (false));
00191     rift_est.setSearchMethod (treept4);
00192     rift_est.setRadiusSearch (10.0);
00193     rift_est.setNrDistanceBins (4);
00194     rift_est.setNrGradientBins (8);
00195 
00196     rift_est.setInputCloud (cloud_xyzi.makeShared ());
00197     rift_est.setInputGradient (gradient.makeShared ());
00198     PointCloud<Eigen::MatrixXf> rift_output;
00199     rift_est.computeEigen (rift_output);
00200 
00201     // Compare to independently verified values
00202     Eigen::VectorXf rift = rift_output.points.row (220);
00203     const float correct_rift_feature_values[32] = {0.0187f, 0.0349f, 0.0647f, 0.0881f, 0.0042f, 0.0131f, 0.0346f, 0.0030f,
00204                                                    0.0076f, 0.0218f, 0.0463f, 0.0030f, 0.0087f, 0.0288f, 0.0920f, 0.0472f,
00205                                                    0.0076f, 0.0420f, 0.0726f, 0.0669f, 0.0090f, 0.0901f, 0.1274f, 0.2185f,
00206                                                    0.0147f, 0.1222f, 0.3568f, 0.4348f, 0.0149f, 0.0806f, 0.2787f, 0.6864f};
00207     for (int i = 0; i < 32; ++i)
00208       ASSERT_NEAR (rift[i], correct_rift_feature_values[i], 1e-4);
00209   }
00210 #endif
00211 
00212 /* ---[ */
00213 int
00214 main (int argc, char** argv)
00215 {
00216   testing::InitGoogleTest (&argc, argv);
00217   return (RUN_ALL_TESTS ());
00218 }
00219 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:18:30