test_generator.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010-2011, 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$
00035  *
00036  */
00037 
00038 #include <gtest/gtest.h>
00039 #include <pcl/pcl_tests.h>
00040 #include <pcl/point_types.h>
00041 #include <pcl/common/random.h>
00042 #include <pcl/common/generate.h>
00043 
00044 TEST (UniformCloudGenerator, PointXYZ)
00045 {
00046   using namespace pcl::common;
00047   CloudGenerator<pcl::PointXYZ,  UniformGenerator<float> > generator;
00048   UniformGenerator<float>::Parameters x_params;
00049   generator.setParametersForX (x_params);
00050   UniformGenerator<float>::Parameters y_params (-1.f, 1.f);
00051   generator.setParametersForY (y_params);
00052   UniformGenerator<float>::Parameters z_params (-2.5, 1.5f);
00053   generator.setParametersForZ (z_params);
00054 
00055   pcl::PointCloud<pcl::PointXYZ> output;
00056   int result = generator.fill (480, 640, output);
00057   EXPECT_EQ (result, 0);
00058   EXPECT_EQ (output.height, 640);
00059   EXPECT_EQ (output.width, 480);
00060   EXPECT_EQ (output.size (), 480*640);
00061   for(pcl::PointCloud<pcl::PointXYZ>::const_iterator points_it = output.begin ();
00062       points_it != output.end ();
00063       ++points_it)
00064   {
00065     EXPECT_GE (points_it->x, 0);
00066     EXPECT_LT (points_it->x, 1);
00067     EXPECT_GE (points_it->y, -1);
00068     EXPECT_LT (points_it->y, 1);
00069     EXPECT_GE (points_it->z, -2.5);
00070     EXPECT_LT (points_it->z, 1.5);
00071   }
00072 }
00073 
00074 TEST (UniformCloudGenerator, PointXY)
00075 {
00076   using namespace pcl::common;
00077   CloudGenerator<pcl::PointXY,  UniformGenerator<float> > generator;
00078   UniformGenerator<float>::Parameters x_params;
00079   generator.setParametersForX (x_params);
00080   UniformGenerator<float>::Parameters y_params (-1.f, 1.f);
00081   generator.setParametersForY (y_params);
00082 
00083   pcl::PointCloud<pcl::PointXY> output;
00084   int result = generator.fill (480, 640, output);
00085   EXPECT_EQ (result, 0);
00086   EXPECT_EQ (output.height, 640);
00087   EXPECT_EQ (output.width, 480);
00088   EXPECT_EQ (output.size (), 480*640);
00089   for(pcl::PointCloud<pcl::PointXY>::const_iterator points_it = output.begin ();
00090       points_it != output.end ();
00091       ++points_it)
00092   {
00093     EXPECT_GE (points_it->x, 0);
00094     EXPECT_LT (points_it->x, 1);
00095     EXPECT_GE (points_it->y, -1);
00096     EXPECT_LT (points_it->y, 1);
00097   }
00098 }
00099 
00100 TEST (UniformCloudGenerator, Cube)
00101 {
00102   using namespace pcl::common;
00103   CloudGenerator<pcl::PointXYZ,  UniformGenerator<float> > generator;
00104   UniformGenerator<float>::Parameters params (-3, 3, 1);
00105   generator.setParameters (params);
00106 
00107   pcl::PointCloud<pcl::PointXYZ> output;
00108   int result = generator.fill (480, 640, output);
00109   EXPECT_EQ (result, 0);
00110   EXPECT_EQ (output.height, 640);
00111   EXPECT_EQ (output.width, 480);
00112   EXPECT_EQ (output.size (), 480*640);
00113   for(pcl::PointCloud<pcl::PointXYZ>::const_iterator points_it = output.begin ();
00114       points_it != output.end ();
00115       ++points_it)
00116   {
00117     EXPECT_GE (points_it->x, -3);
00118     EXPECT_LT (points_it->x, 3);
00119     EXPECT_GE (points_it->y, -3);
00120     EXPECT_LT (points_it->y, 3);
00121     EXPECT_GE (points_it->z, -3);
00122     EXPECT_LT (points_it->z, 3);
00123   }
00124 }
00125 
00126 TEST (UniformCloudGenerator, Square)
00127 {
00128   using namespace pcl::common;
00129   CloudGenerator<pcl::PointXY,  UniformGenerator<float> > generator;
00130   UniformGenerator<float>::Parameters params (-3, 3, 1);
00131   generator.setParameters (params);
00132 
00133   pcl::PointCloud<pcl::PointXY> output;
00134   int result = generator.fill (480, 640, output);
00135   EXPECT_EQ (result, 0);
00136   EXPECT_EQ (output.height, 640);
00137   EXPECT_EQ (output.width, 480);
00138   EXPECT_EQ (output.size (), 480*640);
00139   for(pcl::PointCloud<pcl::PointXY>::const_iterator points_it = output.begin ();
00140       points_it != output.end ();
00141       ++points_it)
00142   {
00143     EXPECT_GE (points_it->x, -3);
00144     EXPECT_LT (points_it->x, 3);
00145     EXPECT_GE (points_it->y, -3);
00146     EXPECT_LT (points_it->y, 3);
00147   }
00148 }
00149 
00150 int
00151 main (int argc, char** argv)
00152 {
00153   testing::InitGoogleTest (&argc, argv);
00154   return (RUN_ALL_TESTS ());
00155 }


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