test_bilateral.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) 2009-2012, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id: test_filters.cpp 7683 2012-10-23 02:49:03Z rusu $
00038  *
00039  */
00040 
00041 #include <gtest/gtest.h>
00042 #include <pcl/io/pcd_io.h>
00043 #include <pcl/filters/fast_bilateral.h>
00044 #include <pcl/filters/fast_bilateral_omp.h>
00045 #include <pcl/console/time.h>
00046 
00047 using namespace pcl;
00048 
00049 PointCloud<PointXYZ>::Ptr cloud (new PointCloud<PointXYZ>);
00050 
00052 TEST (FastBilateralFilter, Filters_Bilateral)
00053 {
00054   FastBilateralFilter<PointXYZ> fbf;
00055   fbf.setInputCloud (cloud);
00056   fbf.setSigmaS (5);
00057   fbf.setSigmaR (0.03f);
00058   PointCloud<PointXYZ>::Ptr cloud_filtered (new PointCloud<PointXYZ> ());
00059   fbf.filter (*cloud_filtered);
00060 
00061   Eigen::Vector3f p_65558 (-0.058448f, -0.189095f, 0.723415f),
00062       p_84737 (-0.088929f, -0.152957f, 0.746095f),
00063       p_57966 (0.123646f, -0.397528f, 1.393187f),
00064       p_39543 (0.560287f, -0.545020f, 1.602833f),
00065       p_17766 (0.557854f, -0.711976f, 1.762013f),
00066       p_70202 (0.150500f, -0.160329f, 0.646596f),
00067       p_102219 (0.175637f, -0.101353f, 0.661631f),
00068       p_81765 (0.223189f, -0.151714f, 0.708332f);
00069 
00070   for (size_t dim = 0; dim < 3; ++dim)
00071   {
00072     EXPECT_NEAR (p_84737[dim], (*cloud_filtered)[84737].getVector3fMap ()[dim], 1e-3);
00073     EXPECT_NEAR (p_57966[dim], (*cloud_filtered)[57966].getVector3fMap ()[dim], 1e-3);
00074     EXPECT_NEAR (p_39543[dim], (*cloud_filtered)[39543].getVector3fMap ()[dim], 1e-3);
00075     EXPECT_NEAR (p_17766[dim], (*cloud_filtered)[17766].getVector3fMap ()[dim], 1e-3);
00076     EXPECT_NEAR (p_70202[dim], (*cloud_filtered)[70202].getVector3fMap ()[dim], 1e-3);
00077     EXPECT_NEAR (p_102219[dim], (*cloud_filtered)[102219].getVector3fMap ()[dim], 1e-3);
00078     EXPECT_NEAR (p_81765[dim], (*cloud_filtered)[81765].getVector3fMap ()[dim], 1e-3);
00079   }
00080 }
00081 
00083 TEST (FastBilateralFilterOMP, Filters_Bilateral)
00084 {
00085   std::vector<float> sigma_s; 
00086   sigma_s.push_back (2.341f);
00087   sigma_s.push_back (5.2342f);
00088   sigma_s.push_back (10.29380f);
00089   std::vector<float> sigma_r; 
00090   sigma_r.push_back (0.0123f);
00091   sigma_r.push_back (0.023f);
00092   sigma_r.push_back (0.0345f);
00093   pcl::console::TicToc tt;
00094   for (size_t i = 0; i < 3; i++)
00095   {
00096     FastBilateralFilter<PointXYZ> fbf;
00097     fbf.setInputCloud (cloud);
00098     fbf.setSigmaS (sigma_s[i]);
00099     fbf.setSigmaR (sigma_r[i]);
00100     PointCloud<PointXYZ>::Ptr cloud_filtered (new PointCloud<PointXYZ> ());
00101     tt.tic ();
00102     fbf.filter (*cloud_filtered);
00103     PCL_INFO ("[FastBilateralFilter] filtering took %f ms\n", tt.toc ());
00104 
00105     FastBilateralFilterOMP<PointXYZ> fbf_omp (0);
00106     fbf_omp.setInputCloud (cloud);
00107     fbf_omp.setSigmaS (sigma_s[i]);
00108     fbf_omp.setSigmaR (sigma_r[i]);
00109     PointCloud<PointXYZ>::Ptr cloud_filtered_omp (new PointCloud<PointXYZ> ());
00110     tt.tic ();
00111     fbf_omp.filter (*cloud_filtered_omp);
00112     PCL_INFO ("[FastBilateralFilterOMP] filtering took %f ms\n", tt.toc ());
00113 
00114     EXPECT_EQ (cloud_filtered_omp->points.size (), cloud_filtered->points.size ());
00115     for (size_t j = 0; j < cloud_filtered_omp->size (); ++j)
00116     {
00117       if (pcl_isnan (cloud_filtered_omp->at (j).x))
00118         EXPECT_TRUE (pcl_isnan (cloud_filtered->at (j).x));
00119       else
00120       {
00121         EXPECT_NEAR (cloud_filtered_omp->at (j).x, cloud_filtered->at (j).x, 1e-3);
00122         EXPECT_NEAR (cloud_filtered_omp->at (j).y, cloud_filtered->at (j).y, 1e-3);
00123         EXPECT_NEAR (cloud_filtered_omp->at (j).z, cloud_filtered->at (j).z, 1e-3);
00124       }
00125     }
00126   }
00127 
00128 }
00129 
00130 /* ---[ */
00131 int
00132 main (int argc,
00133       char** argv)
00134 {
00135   // Load a standard PCD file from disk
00136   if (argc < 2)
00137   {
00138     std::cerr << "No test file given. Please download `milk_cartoon_all_small_clorox.pcd` and pass its path to the test." << std::endl;
00139     return (-1);
00140   }
00141 
00142   char* file_name = argv[1];
00143   // Load a standard PCD file from disk
00144   io::loadPCDFile (file_name, *cloud);
00145 
00146   testing::InitGoogleTest (&argc, argv);
00147   return (RUN_ALL_TESTS ());
00148 }
00149 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:34:22