test_wrappers.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-2011, 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 the copyright holder(s) 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_types.h>
00042 #include <pcl/point_cloud.h>
00043 #include <pcl/pcl_tests.h>
00044 
00045 using namespace pcl;
00046 using namespace pcl::test;
00047 
00048 PointCloud<PointXYZ> cloud;
00049 const size_t size = 10 * 480;
00050 
00051 TEST (PointCloud, size)
00052 {
00053   EXPECT_EQ(cloud.points.size (), cloud.size ());
00054 }
00055 
00056 TEST (PointCloud, sq_brackets_wrapper)
00057 {
00058   for (uint32_t i = 0; i < size; ++i)
00059     EXPECT_EQ_VECTORS (cloud.points[i].getVector3fMap (),
00060                        cloud[i].getVector3fMap ());
00061 }
00062 
00063 TEST (PointCloud, at)
00064 {
00065   for (uint32_t i = 0; i < size; ++i)
00066     EXPECT_EQ_VECTORS (cloud.points.at (i).getVector3fMap (),
00067                        cloud.at (i).getVector3fMap ());
00068 }
00069 
00070 TEST (PointCloud, front)
00071 {
00072   EXPECT_EQ_VECTORS (cloud.points.front ().getVector3fMap (),
00073                      cloud.front ().getVector3fMap ());
00074 }
00075 
00076 TEST (PointCloud, back)
00077 {
00078   EXPECT_EQ_VECTORS (cloud.points.back ().getVector3fMap (),
00079                      cloud.back ().getVector3fMap ());
00080 }
00081 
00082 TEST (PointCloud, constructor_with_allocation)
00083 {
00084   PointCloud<PointXYZ> cloud2 (5, 80);
00085   EXPECT_EQ (cloud2.width, 5);
00086   EXPECT_EQ (cloud2.height, 80);
00087   EXPECT_EQ (cloud2.size (), 5*80);
00088 }
00089 
00090 TEST (PointCloud, constructor_with_allocation_valued)
00091 {
00092   PointXYZ nan_point (0.1f, 0.2f, 0.3f);  
00093   PointCloud<PointXYZ> cloud2 (5, 80, nan_point);
00094   EXPECT_EQ (cloud2.width, 5);
00095   EXPECT_EQ (cloud2.height, 80);
00096   EXPECT_EQ (cloud2.size (), 5*80);
00097   for (PointCloud<PointXYZ>::const_iterator pit = cloud2.begin ();
00098        pit != cloud2.end ();
00099        ++pit)
00100   {
00101     EXPECT_NEAR (pit->x, 0.1, 1e-3);
00102     EXPECT_NEAR (pit->y, 0.2, 1e-3);
00103     EXPECT_NEAR (pit->z, 0.3, 1e-3);
00104   }
00105   
00106 }
00107 
00108 TEST (PointCloud, iterators)
00109 {
00110   EXPECT_EQ_VECTORS (cloud.begin ()->getVector3fMap (), 
00111                      cloud.points.begin ()->getVector3fMap ());
00112   EXPECT_EQ_VECTORS (cloud.end ()->getVector3fMap (), 
00113                      cloud.points.end ()->getVector3fMap ());
00114   PointCloud<PointXYZ>::const_iterator pit = cloud.begin ();
00115   PointCloud<PointXYZ>::VectorType::const_iterator pit2 = cloud.points.begin ();
00116   for (; pit < cloud.end (); ++pit2, ++pit)
00117     EXPECT_EQ_VECTORS (pit->getVector3fMap (), pit2->getVector3fMap ());
00118 }
00119 
00120 TEST (PointCloud, insert_range)
00121 {
00122   PointCloud<PointXYZ> cloud2 (10, 1);
00123   for (uint32_t i = 0; i < 10; ++i)
00124     cloud2[i] = PointXYZ (5.0f * static_cast<float>(i) + 0, 5.0f * static_cast<float> (i) + 1, 5.0f * static_cast<float> (i) + 2);
00125 
00126   uint32_t old_size = static_cast<uint32_t> (cloud.size ());
00127   cloud.insert (cloud.begin (), cloud2.begin (), cloud2.end ());
00128   EXPECT_EQ (cloud.width, cloud.size ());
00129   EXPECT_EQ (cloud.height, 1);
00130   EXPECT_EQ (cloud.width, old_size + cloud2.size ());
00131   PointCloud<PointXYZ>::const_iterator pit = cloud.begin ();
00132   PointCloud<PointXYZ>::const_iterator pit2 = cloud2.begin ();
00133   for (; pit2 < cloud2.end (); ++pit2, ++pit)
00134     EXPECT_EQ_VECTORS (pit->getVector3fMap (), pit2->getVector3fMap ());
00135 }
00136 
00137 int
00138 main (int argc, char** argv)
00139 {
00140   cloud.width = 10;
00141   cloud.height = 480;
00142   for (uint32_t i = 0; i < size; ++i)
00143     cloud.points.push_back (PointXYZ (3.0f * static_cast<float>(i) + 0, 3.0f * static_cast<float> (i) + 1, 3.0f * static_cast<float> (i) + 2));
00144 
00145   testing::InitGoogleTest (&argc, argv);
00146   return (RUN_ALL_TESTS ());
00147 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:36:20