test_spring.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: test_spring.cpp 4251 2012-02-04 00:33:47Z nizar $
00035  */
00036 
00037 #include <gtest/gtest.h>
00038 #include <pcl/pcl_config.h>
00039 #include <pcl/pcl_tests.h>
00040 #include <pcl/point_types.h>
00041 #include <pcl/common/spring.h>
00042 
00043 using namespace pcl;
00044 using namespace pcl::test;
00045 
00046 PointCloud<PointXYZ>::Ptr cloud_ptr (new PointCloud<PointXYZ> (4, 5));
00047 const size_t size = 5 * 4;
00048 const int amount = 2;
00049 
00050 // TEST (PointCloudSpring, vertical)
00051 // {
00052 //   PointCloudSpring<PointXYZ> spring;
00053 //   spring.setInputCloud (cloud_ptr);
00054 //   spring.setAmount (2);
00055 //   spring.setDirection (PointCloudSpring<PointXYZ>::VERTICAL);
00056 //   spring.setExpandPolicy (PointCloudSpring<PointXYZ>::MIRROR);
00057 
00058 //   PointXYZ xyz;
00059 //   xyz.x = 0; xyz.y = 0; xyz.z = 0;
00060 //   int old_height (cloud_ptr->height);
00061 //   spring.expand (xyz);
00062 //   EXPECT_EQ (cloud_ptr->height, old_height +2*2);
00063 // }
00064 
00065 // TEST (PointCloudSpring, horizontal)
00066 // {
00067 //   PointCloudSpring<PointXYZ> spring;
00068 //   spring.setInputCloud (cloud_ptr);
00069 //   spring.setAmount (2);
00070 //   spring.setDirection (PointCloudSpring<PointXYZ>::HORIZONTAL);
00071 //   spring.setExpandPolicy (PointCloudSpring<PointXYZ>::MIRROR);
00072 
00073 //   PointXYZ xyz;
00074 //   xyz.x = 0; xyz.y = 0; xyz.z = 0;
00075 //   int old_width (cloud_ptr->width);
00076 //   for (int i = 0; i < cloud_ptr->height; i++)    
00077 //   {
00078 //     std::cout << (*cloud_ptr) (0, i) << std::endl;
00079 //   }
00080 //   spring.expand (xyz);
00081 //   for (int i = 0; i < cloud_ptr->height; i++)    
00082 //   {
00083 //     std::cout << (*cloud_ptr) (0, i) << std::endl;
00084 //   }
00085 //   EXPECT_EQ (cloud_ptr->width, old_width +2*2);
00086 // }
00087 
00088 TEST (PointCloudSpring, duplicateRows)
00089 {
00090   PointCloud<PointXYZ>::Ptr output (new PointCloud<PointXYZ> ());
00091   pcl::common::duplicateRows (*cloud_ptr, *output, amount);
00092   int w = output->width;
00093   EXPECT_EQ (output->height, cloud_ptr->height + 2*amount);
00094 
00095   for (int i = 0; i < w; ++i)
00096   {
00097     EXPECT_EQ_VECTORS ((*output) (i, 0).getVector3fMap (), 
00098            (*output) (i, 1).getVector3fMap ());
00099     EXPECT_EQ_VECTORS ((*output) (i, 0).getVector3fMap (), 
00100            (*output) (i, 2).getVector3fMap ());
00101     EXPECT_EQ_VECTORS ((*output) (i, output->height - 3).getVector3fMap (), 
00102            (*output) (i, output->height - 1).getVector3fMap ());
00103     EXPECT_EQ_VECTORS ((*output) (i, output->height - 3).getVector3fMap (), 
00104            (*output) (i, output->height - 2).getVector3fMap ());
00105   }
00106 }
00107 
00108 TEST (PointCloudSpring, duplicateColumns)
00109 {
00110   PointCloud<PointXYZ>::Ptr output (new PointCloud<PointXYZ> ());
00111   pcl::common::duplicateColumns (*cloud_ptr, *output, amount);
00112   int h = output->height;
00113   int w = output->width;
00114   EXPECT_EQ (output->width, cloud_ptr->width +2*amount);
00115 
00116   for (int i = 0; i < h; ++i)
00117   {
00118     EXPECT_EQ_VECTORS ((*output) (0, i).getVector3fMap (), 
00119            (*output) (1, i).getVector3fMap ());
00120     EXPECT_EQ_VECTORS ((*output) (0, i).getVector3fMap (), 
00121            (*output) (2, i).getVector3fMap ());
00122     EXPECT_EQ_VECTORS ((*output) (w - 3, i).getVector3fMap (), 
00123            (*output) (w - 1, i).getVector3fMap ());
00124     EXPECT_EQ_VECTORS ((*output) (w - 3, i).getVector3fMap (), 
00125            (*output) (w - 2, i).getVector3fMap ());
00126   }
00127 }
00128 
00129 TEST (PointCloudSpring, mirrorRows)
00130 {
00131   PointCloud<PointXYZ>::Ptr output (new PointCloud<PointXYZ> ());
00132   pcl::common::mirrorRows (*cloud_ptr, *output, amount);
00133   int w = output->width;
00134   int h = output->height;
00135   EXPECT_EQ (output->height, cloud_ptr->height + 2*amount);
00136 
00137   for (int i = 0; i < w; ++i)
00138   {
00139     EXPECT_EQ_VECTORS ((*output) (i, 1).getVector3fMap (), 
00140            (*output) (i, 2).getVector3fMap ());
00141     EXPECT_EQ_VECTORS ((*output) (i, 0).getVector3fMap (), 
00142            (*output) (i, 3).getVector3fMap ());
00143     EXPECT_EQ_VECTORS ((*output) (i, h - 3).getVector3fMap (), 
00144            (*output) (i, h - 2).getVector3fMap ());
00145     EXPECT_EQ_VECTORS ((*output) (i, h - 4).getVector3fMap (), 
00146            (*output) (i, h - 1).getVector3fMap ());
00147   }
00148 }
00149 
00150 TEST (PointCloudSpring, mirrorColumns)
00151 {
00152   PointCloud<PointXYZ>::Ptr output (new PointCloud<PointXYZ> ());
00153   pcl::common::mirrorColumns (*cloud_ptr, *output, amount);
00154   int w = output->width;
00155   int h = output->height;
00156 
00157   EXPECT_EQ (output->width, cloud_ptr->width +2*amount);
00158 
00159   for (int j = 0; j < h; ++j)
00160   {
00161     EXPECT_EQ_VECTORS ((*output) (0, j).getVector3fMap (), 
00162            (*output) (3, j).getVector3fMap ());
00163     EXPECT_EQ_VECTORS ((*output) (1, j).getVector3fMap (), 
00164            (*output) (2, j).getVector3fMap ());
00165     EXPECT_EQ_VECTORS ((*output) (w - 3, j).getVector3fMap (), 
00166            (*output) (w - 2, j).getVector3fMap ());
00167     EXPECT_EQ_VECTORS ((*output) (w - 4, j).getVector3fMap (), 
00168            (*output) (w - 1, j).getVector3fMap ());
00169   }
00170 }
00171 
00172 TEST (PointCloudSpring, deleteRows)
00173 {
00174   PointCloud<PointXYZ>::Ptr output (new PointCloud<PointXYZ> ());
00175   pcl::common::mirrorRows (*cloud_ptr, *output, amount);
00176   EXPECT_EQ (output->height, cloud_ptr->height +2*amount);
00177   pcl::common::deleteRows (*output, *output, amount);
00178   EXPECT_EQ (output->height, cloud_ptr->height);
00179 
00180   for (uint32_t i = 0; i < cloud_ptr->width; i++)
00181     for (uint32_t j = 0; j < cloud_ptr->height; j++)
00182     {
00183       EXPECT_EQ_VECTORS ((*output) (i, j).getVector3fMap (),
00184                          (*cloud_ptr) (i, j).getVector3fMap ());
00185     }
00186 }
00187 
00188 TEST (PointCloudSpring, deleteCols)
00189 {
00190   PointCloud<PointXYZ>::Ptr output (new PointCloud<PointXYZ> ());
00191   pcl::common::duplicateColumns (*cloud_ptr, *output, amount);
00192   EXPECT_EQ (output->width, cloud_ptr->width +2*amount);
00193   pcl::common::deleteCols (*output, *output, amount);
00194   EXPECT_EQ (output->width, cloud_ptr->width);
00195 
00196   for (uint32_t i = 0; i < cloud_ptr->width; i++)
00197     for (uint32_t j = 0; j < cloud_ptr->height; j++)
00198     {
00199       EXPECT_EQ_VECTORS ((*output) (i, j).getVector3fMap (),
00200                          (*cloud_ptr) (i, j).getVector3fMap ());
00201     }
00202 }
00203 
00204 int
00205 main (int argc, char** argv)
00206 {
00207   for (uint32_t i = 0; i < size; ++i)
00208     (*cloud_ptr)[i]  = PointXYZ (3*i+0, 3*i+1, 3*i+2);
00209   testing::InitGoogleTest (&argc, argv);
00210   return (RUN_ALL_TESTS ());
00211 }


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