test_io.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/PCLPointCloud2.h>
00042 #include <pcl/point_traits.h>
00043 #include <pcl/point_types.h>
00044 #include <pcl/common/io.h>
00045 #include <pcl/console/print.h>
00046 #include <pcl/io/pcd_io.h>
00047 #include <pcl/io/ply_io.h>
00048 #include <pcl/io/ascii_io.h>
00049 #include <fstream>
00050 #include <locale>
00051 #include <stdexcept>
00052 
00053 using namespace pcl;
00054 using namespace pcl::io;
00055 
00057 TEST (PCL, ComplexPCDFileASCII)
00058 {
00059   std::ofstream fs;
00060   fs.open ("complex_ascii.pcd");
00061   fs << "# .PCD v0.7 - Point Cloud Data file format\n"
00062         "VERSION 0.7\n"
00063         "FIELDS fpfh _ x y z\n"
00064         "SIZE 4 1 4 4 4\n"
00065         "TYPE F F F F F\n"
00066         "COUNT 33 10 1 1 1\n"
00067         "WIDTH 1\n"
00068         "HEIGHT 1\n"
00069         "VIEWPOINT 0 0 0 1 0 0 0\n"
00070         "POINTS 1\n"
00071         "DATA ascii\n"
00072         "0 0 0 0 0 100 0 0 0 0 0 0 0 0 0 0 100 0 0 0 0 0 0 0 0 0 0 100 0 0 0 0 0 1 1 1 1 1 1 1 1 1 1 -69.234001 -65.460999 19.173";
00073   fs.close ();
00074 
00075   pcl::PCLPointCloud2 blob;
00076   int res = loadPCDFile ("complex_ascii.pcd", blob);
00077   EXPECT_NE (int (res), -1);
00078   EXPECT_EQ (blob.width, 1);
00079   EXPECT_EQ (blob.height, 1);
00080   EXPECT_EQ (blob.is_dense, true);
00081   EXPECT_EQ (blob.data.size (), 4 * 33 + 10 * 1 + 4 * 3);
00082 
00083   // Check fields
00084   EXPECT_EQ (blob.fields[0].name, "fpfh");
00085   EXPECT_EQ (blob.fields[0].offset, 0);
00086   EXPECT_EQ (blob.fields[0].count, 33);
00087   EXPECT_EQ (blob.fields[0].datatype, pcl::PCLPointField::FLOAT32);
00088 
00089   EXPECT_EQ (blob.fields[1].name, "_");
00090   EXPECT_EQ (blob.fields[1].offset, 4 * 33);
00091   EXPECT_EQ (blob.fields[1].count, 10);
00092   EXPECT_EQ (blob.fields[1].datatype, pcl::PCLPointField::FLOAT32);
00093   
00094   EXPECT_EQ (blob.fields[2].name, "x");
00095   EXPECT_EQ (blob.fields[2].offset, 4 * 33 + 10 * 1);
00096   EXPECT_EQ (blob.fields[2].count, 1);
00097   EXPECT_EQ (blob.fields[2].datatype, pcl::PCLPointField::FLOAT32);
00098   
00099   EXPECT_EQ (blob.fields[3].name, "y");
00100   EXPECT_EQ (blob.fields[3].offset, 4 * 33 + 10 * 1 + 4);
00101   EXPECT_EQ (blob.fields[3].count, 1);
00102   EXPECT_EQ (blob.fields[3].datatype, pcl::PCLPointField::FLOAT32);
00103   
00104   EXPECT_EQ (blob.fields[4].name, "z");
00105   EXPECT_EQ (blob.fields[4].offset, 4 * 33 + 10 * 1 + 4 + 4);
00106   EXPECT_EQ (blob.fields[4].count, 1);
00107   EXPECT_EQ (blob.fields[4].datatype, pcl::PCLPointField::FLOAT32);
00108 
00109   int x_idx = pcl::getFieldIndex (blob, "x");
00110   EXPECT_EQ (x_idx, 2);
00111   float x, y, z;
00112   memcpy (&x, &blob.data[0 * blob.point_step + blob.fields[x_idx + 0].offset], sizeof (float));
00113   memcpy (&y, &blob.data[0 * blob.point_step + blob.fields[x_idx + 1].offset], sizeof (float));
00114   memcpy (&z, &blob.data[0 * blob.point_step + blob.fields[x_idx + 2].offset], sizeof (float));
00115   EXPECT_FLOAT_EQ (x, -69.234001f);
00116   EXPECT_FLOAT_EQ (y, -65.460999f);
00117   EXPECT_FLOAT_EQ (z, 19.173f);
00118 
00119   int fpfh_idx = pcl::getFieldIndex (blob, "fpfh");
00120   EXPECT_EQ (fpfh_idx, 0);
00121   float val[33];
00122   for (size_t i = 0; i < blob.fields[fpfh_idx].count; ++i)
00123     memcpy (&val[i], &blob.data[0 * blob.point_step + blob.fields[fpfh_idx + 0].offset + i * sizeof (float)], sizeof (float));
00124 
00125   EXPECT_EQ (val[0], 0); 
00126   EXPECT_EQ (val[1], 0); 
00127   EXPECT_EQ (val[2], 0); 
00128   EXPECT_EQ (val[3], 0); 
00129   EXPECT_EQ (val[4], 0); 
00130   EXPECT_EQ (val[5], 100); 
00131   EXPECT_EQ (val[6], 0); 
00132   EXPECT_EQ (val[7], 0); 
00133   EXPECT_EQ (val[8], 0); 
00134   EXPECT_EQ (val[9], 0); 
00135   EXPECT_EQ (val[10], 0); 
00136   EXPECT_EQ (val[11], 0); 
00137   EXPECT_EQ (val[12], 0); 
00138   EXPECT_EQ (val[13], 0); 
00139   EXPECT_EQ (val[14], 0); 
00140   EXPECT_EQ (val[15], 0); 
00141   EXPECT_EQ (val[16], 100); 
00142   EXPECT_EQ (val[17], 0); 
00143   EXPECT_EQ (val[18], 0); 
00144   EXPECT_EQ (val[19], 0); 
00145   EXPECT_EQ (val[20], 0); 
00146   EXPECT_EQ (val[21], 0); 
00147   EXPECT_EQ (val[22], 0); 
00148   EXPECT_EQ (val[23], 0); 
00149   EXPECT_EQ (val[24], 0); 
00150   EXPECT_EQ (val[25], 0); 
00151   EXPECT_EQ (val[26], 0); 
00152   EXPECT_EQ (val[27], 100); 
00153   EXPECT_EQ (val[28], 0); 
00154   EXPECT_EQ (val[29], 0); 
00155   EXPECT_EQ (val[30], 0); 
00156   EXPECT_EQ (val[31], 0); 
00157   EXPECT_EQ (val[32], 0); 
00158 }
00159 
00161 TEST (PCL, AllTypesPCDFile)
00162 {
00163   std::ofstream fs;
00164   fs.open ("all_types.pcd");
00165   fs << "# .PCD v0.7 - Point Cloud Data file format\n"
00166         "VERSION 0.7\n"
00167         "FIELDS a1 a2 a3 a4 a5 a6 a7 a8\n"
00168         "SIZE    1  1  2  2  4  4  4  8\n"
00169         "TYPE    I  U  I  U  I  U  F  F\n"
00170         "COUNT   1  2  1  2  1  2  1  2\n"
00171         "WIDTH 1\n"
00172         "HEIGHT 1\n"
00173         "VIEWPOINT 0 0 0 1 0 0 0\n"
00174         "POINTS 1\n"
00175         "DATA ascii\n"
00176         "-50 250 251 -250 2500 2501 -250000 250000 250001 250.05 -250.05 -251.05";
00177   fs.close ();
00178 
00179   pcl::PCLPointCloud2 blob;
00180   int res = loadPCDFile ("all_types.pcd", blob);
00181   EXPECT_NE (int (res), -1);
00182   EXPECT_EQ (blob.width, 1);
00183   EXPECT_EQ (blob.height, 1);
00184   EXPECT_EQ (blob.data.size (), 1 + 1 * 2 + 2 * 1 + 2 * 2 + 4 * 1 + 4 * 2 + 4 * 1 + 8 * 2);
00185   EXPECT_EQ (blob.is_dense, true);
00186 
00187   EXPECT_EQ (blob.fields.size (), 8);
00188   // Check fields
00189   EXPECT_EQ (blob.fields[0].name, "a1");
00190   EXPECT_EQ (blob.fields[1].name, "a2");
00191   EXPECT_EQ (blob.fields[2].name, "a3");
00192   EXPECT_EQ (blob.fields[3].name, "a4");
00193   EXPECT_EQ (blob.fields[4].name, "a5");
00194   EXPECT_EQ (blob.fields[5].name, "a6");
00195   EXPECT_EQ (blob.fields[6].name, "a7");
00196   EXPECT_EQ (blob.fields[7].name, "a8");
00197 
00198   EXPECT_EQ (blob.fields[0].offset, 0);
00199   EXPECT_EQ (blob.fields[1].offset, 1);
00200   EXPECT_EQ (blob.fields[2].offset, 1 + 1 * 2);
00201   EXPECT_EQ (blob.fields[3].offset, 1 + 1 * 2 + 2 * 1);
00202   EXPECT_EQ (blob.fields[4].offset, 1 + 1 * 2 + 2 * 1 + 2 * 2);
00203   EXPECT_EQ (blob.fields[5].offset, 1 + 1 * 2 + 2 * 1 + 2 * 2 + 4 * 1);
00204   EXPECT_EQ (blob.fields[6].offset, 1 + 1 * 2 + 2 * 1 + 2 * 2 + 4 * 1 + 4 * 2);
00205   EXPECT_EQ (blob.fields[7].offset, 1 + 1 * 2 + 2 * 1 + 2 * 2 + 4 * 1 + 4 * 2 + 4 * 1);
00206 
00207   EXPECT_EQ (blob.fields[0].count, 1);
00208   EXPECT_EQ (blob.fields[1].count, 2);
00209   EXPECT_EQ (blob.fields[2].count, 1);
00210   EXPECT_EQ (blob.fields[3].count, 2);
00211   EXPECT_EQ (blob.fields[4].count, 1);
00212   EXPECT_EQ (blob.fields[5].count, 2);
00213   EXPECT_EQ (blob.fields[6].count, 1);
00214   EXPECT_EQ (blob.fields[7].count, 2);
00215 
00216   EXPECT_EQ (blob.fields[0].datatype, pcl::PCLPointField::INT8);
00217   EXPECT_EQ (blob.fields[1].datatype, pcl::PCLPointField::UINT8);
00218   EXPECT_EQ (blob.fields[2].datatype, pcl::PCLPointField::INT16);
00219   EXPECT_EQ (blob.fields[3].datatype, pcl::PCLPointField::UINT16);
00220   EXPECT_EQ (blob.fields[4].datatype, pcl::PCLPointField::INT32);
00221   EXPECT_EQ (blob.fields[5].datatype, pcl::PCLPointField::UINT32);
00222   EXPECT_EQ (blob.fields[6].datatype, pcl::PCLPointField::FLOAT32);
00223   EXPECT_EQ (blob.fields[7].datatype, pcl::PCLPointField::FLOAT64);
00224 
00225   int8_t b1;
00226   uint8_t b2;
00227   int16_t b3;
00228   uint16_t b4;
00229   int32_t b5;
00230   uint32_t b6;
00231   float b7;
00232   double b8;
00233   memcpy (&b1, &blob.data[blob.fields[0].offset], sizeof (int8_t));
00234   EXPECT_FLOAT_EQ (b1, -50);
00235   memcpy (&b2, &blob.data[blob.fields[1].offset], sizeof (uint8_t));
00236   EXPECT_FLOAT_EQ (b2, 250);
00237   memcpy (&b2, &blob.data[blob.fields[1].offset + sizeof (uint8_t)], sizeof (uint8_t));
00238   EXPECT_FLOAT_EQ (b2, 251);
00239   memcpy (&b3, &blob.data[blob.fields[2].offset], sizeof (int16_t));
00240   EXPECT_FLOAT_EQ (b3, -250);
00241   memcpy (&b4, &blob.data[blob.fields[3].offset], sizeof (uint16_t));
00242   EXPECT_FLOAT_EQ (b4, 2500);
00243   memcpy (&b4, &blob.data[blob.fields[3].offset + sizeof (uint16_t)], sizeof (uint16_t));
00244   EXPECT_FLOAT_EQ (b4, 2501);
00245   memcpy (&b5, &blob.data[blob.fields[4].offset], sizeof (int32_t));
00246   EXPECT_FLOAT_EQ (float (b5), float (-250000));
00247   memcpy (&b6, &blob.data[blob.fields[5].offset], sizeof (uint32_t));
00248   EXPECT_FLOAT_EQ (float (b6), float (250000));
00249   memcpy (&b6, &blob.data[blob.fields[5].offset + sizeof (uint32_t)], sizeof (uint32_t));
00250   EXPECT_FLOAT_EQ (float (b6), float (250001));
00251   memcpy (&b7, &blob.data[blob.fields[6].offset], sizeof (float));
00252   EXPECT_FLOAT_EQ (b7, 250.05f);
00253   memcpy (&b8, &blob.data[blob.fields[7].offset], sizeof (double));
00254   EXPECT_FLOAT_EQ (float (b8), -250.05f);
00255   memcpy (&b8, &blob.data[blob.fields[7].offset + sizeof (double)], sizeof (double));
00256   EXPECT_FLOAT_EQ (float (b8), -251.05f);
00257 }
00258 
00260 TEST (PCL, ConcatenatePoints)
00261 {
00262   pcl::PointCloud<pcl::PointXYZ> cloud_a, cloud_b, cloud_c;
00263 
00264   // Fill in the cloud data
00265   cloud_a.width  = 5;
00266   cloud_b.width  = 3;
00267   cloud_a.height = cloud_b.height = 1;
00268   cloud_a.points.resize (cloud_a.width * cloud_a.height);
00269   cloud_b.points.resize (cloud_b.width * cloud_b.height);
00270 
00271   for (size_t i = 0; i < cloud_a.points.size (); ++i)
00272   {
00273     cloud_a.points[i].x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00274     cloud_a.points[i].y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00275     cloud_a.points[i].z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00276   }
00277 
00278   for (size_t i = 0; i < cloud_b.points.size (); ++i)
00279   {
00280     cloud_b.points[i].x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00281     cloud_b.points[i].y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00282     cloud_b.points[i].z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00283   }
00284 
00285   // Copy the point cloud data
00286   cloud_c  = cloud_a;
00287   cloud_c += cloud_b;
00288   EXPECT_EQ (cloud_c.points.size (), cloud_a.points.size () + cloud_b.points.size ());
00289   EXPECT_EQ (cloud_c.width, cloud_a.width + cloud_b.width);
00290   EXPECT_EQ (int (cloud_c.height), 1);
00291 
00292   for (size_t i = 0; i < cloud_a.points.size (); ++i)
00293   {
00294     EXPECT_FLOAT_EQ (cloud_c.points[i].x, cloud_a.points[i].x);
00295     EXPECT_FLOAT_EQ (cloud_c.points[i].y, cloud_a.points[i].y);
00296     EXPECT_FLOAT_EQ (cloud_c.points[i].z, cloud_a.points[i].z);
00297   }
00298   for (size_t i = cloud_a.points.size (); i < cloud_c.points.size (); ++i)
00299   {
00300     EXPECT_FLOAT_EQ (cloud_c.points[i].x, cloud_b.points[i - cloud_a.points.size ()].x);
00301     EXPECT_FLOAT_EQ (cloud_c.points[i].y, cloud_b.points[i - cloud_a.points.size ()].y);
00302     EXPECT_FLOAT_EQ (cloud_c.points[i].z, cloud_b.points[i - cloud_a.points.size ()].z);
00303   }
00304 }
00305 
00307 TEST (PCL, ConcatenateFields)
00308 {
00309   pcl::PointCloud<pcl::PointXYZ> cloud_a;
00310   pcl::PointCloud<pcl::Normal> cloud_b;
00311   pcl::PointCloud<pcl::PointNormal> cloud_c;
00312 
00313   // Fill in the cloud data
00314   cloud_a.width  = cloud_b.width  = 5;
00315   cloud_a.height = cloud_b.height = 1;
00316   cloud_a.points.resize (cloud_a.width * cloud_a.height);
00317   cloud_b.points.resize (cloud_b.width * cloud_b.height);
00318 
00319   for (size_t i = 0; i < cloud_a.points.size (); ++i)
00320   {
00321     cloud_a[i].x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00322     cloud_a[i].y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00323     cloud_a[i].z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00324   }
00325 
00326   for (size_t i = 0; i < cloud_b.points.size (); ++i)
00327   {
00328     cloud_b[i].normal_x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00329     cloud_b[i].normal_y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00330     cloud_b[i].normal_z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00331   }
00332 
00333   pcl::concatenateFields (cloud_a, cloud_b, cloud_c);
00334   EXPECT_EQ (cloud_c.points.size (), cloud_a.points.size ());
00335   EXPECT_EQ (cloud_c.width, cloud_a.width);
00336   EXPECT_EQ (cloud_c.height, cloud_a.height);
00337 
00338   for (size_t i = 0; i < cloud_a.points.size (); ++i)
00339   {
00340     EXPECT_FLOAT_EQ (cloud_c.points[i].x, cloud_a.points[i].x);
00341     EXPECT_FLOAT_EQ (cloud_c.points[i].y, cloud_a.points[i].y);
00342     EXPECT_FLOAT_EQ (cloud_c.points[i].z, cloud_a.points[i].z);
00343     EXPECT_FLOAT_EQ (cloud_c.points[i].normal[0], cloud_b.points[i].normal[0]);
00344     EXPECT_FLOAT_EQ (cloud_c.points[i].normal[1], cloud_b.points[i].normal[1]);
00345     EXPECT_FLOAT_EQ (cloud_c.points[i].normal[2], cloud_b.points[i].normal[2]);
00346   }
00347 }
00348 
00350 TEST (PCL, IO)
00351 {
00352   pcl::PCLPointCloud2 cloud_blob;
00353   PointCloud<PointXYZI> cloud;
00354 
00355   cloud.width  = 640;
00356   cloud.height = 480;
00357   cloud.points.resize (cloud.width * cloud.height);
00358   cloud.is_dense = true;
00359 
00360   srand (static_cast<unsigned int> (time (NULL)));
00361   size_t nr_p = cloud.points.size ();
00362   // Randomly create a new point cloud
00363   for (size_t i = 0; i < nr_p; ++i)
00364   {
00365     cloud[i].x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00366     cloud[i].y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00367     cloud[i].z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00368     cloud.points[i].intensity = static_cast<float> (i);
00369   }
00370   PointXYZI first, last;
00371   first.x = cloud.points[0].x;       first.y = cloud.points[0].y;       first.z = cloud.points[0].z;       first.intensity = cloud.points[0].intensity;
00372   last.x = cloud.points[nr_p - 1].x; last.y = cloud.points[nr_p - 1].y; last.z = cloud.points[nr_p - 1].z; last.intensity  = cloud.points[nr_p - 1].intensity;
00373 
00374   // Tests for PointCloud::operator()
00375   EXPECT_FLOAT_EQ (first.x, cloud (0, 0).x);
00376   EXPECT_FLOAT_EQ (first.y, cloud (0, 0).y);
00377   EXPECT_FLOAT_EQ (first.z, cloud (0, 0).z);
00378   EXPECT_FLOAT_EQ (first.intensity, 0.0f);
00379   EXPECT_FLOAT_EQ (last.x, cloud (cloud.width-1, cloud.height-1).x);
00380   EXPECT_FLOAT_EQ (last.y, cloud (cloud.width-1, cloud.height-1).y);
00381   EXPECT_FLOAT_EQ (last.z, cloud (cloud.width-1, cloud.height-1).z);
00382   EXPECT_FLOAT_EQ (last.intensity, static_cast<float> (nr_p - 1));
00383 
00384   // Test getFieldIndex
00385   std::vector<pcl::PCLPointField> fields;
00386   pcl::getFields (cloud, fields);
00387   EXPECT_EQ (fields.size (), size_t (4));
00388   int x_idx = pcl::getFieldIndex (cloud, "x", fields);
00389   EXPECT_EQ (x_idx, 0);
00390   EXPECT_EQ (fields[x_idx].offset, uint32_t (0));
00391   EXPECT_EQ (fields[x_idx].name, "x");
00392   EXPECT_EQ (fields[x_idx].datatype, pcl::PCLPointField::FLOAT32);
00393   EXPECT_EQ (fields[x_idx].count, uint32_t (1));
00394 
00395   int y_idx = pcl::getFieldIndex (cloud, "y", fields);
00396   EXPECT_EQ (y_idx, 1);
00397   EXPECT_EQ (fields[y_idx].offset, uint32_t (4));
00398   EXPECT_EQ (fields[y_idx].name, "y");
00399   EXPECT_EQ (fields[y_idx].datatype, pcl::PCLPointField::FLOAT32);
00400   EXPECT_EQ (fields[y_idx].count, uint32_t (1));
00401 
00402   int z_idx = pcl::getFieldIndex (cloud, "z", fields);
00403   EXPECT_EQ (z_idx, 2);
00404   EXPECT_EQ (fields[z_idx].offset, uint32_t (8));
00405   EXPECT_EQ (fields[z_idx].name, "z");
00406   EXPECT_EQ (fields[z_idx].datatype, pcl::PCLPointField::FLOAT32);
00407   EXPECT_EQ (fields[z_idx].count, uint32_t (1));
00408 
00409   int intensity_idx = pcl::getFieldIndex (cloud, "intensity", fields);
00410   EXPECT_EQ (intensity_idx, 3);
00411   EXPECT_EQ (fields[intensity_idx].offset, uint32_t (16));      // NOTE: intensity_idx.offset should be 12, but we are padding in PointXYZ (!)
00412   EXPECT_EQ (fields[intensity_idx].name, "intensity");
00413   EXPECT_EQ (fields[intensity_idx].datatype, pcl::PCLPointField::FLOAT32);
00414   EXPECT_EQ (fields[intensity_idx].count, uint32_t (1));
00415 
00416   // Convert from data type to blob
00417   toPCLPointCloud2 (cloud, cloud_blob);
00418 
00419   // Test getFieldIndex
00420   x_idx = pcl::getFieldIndex (cloud_blob, "x");
00421   EXPECT_EQ (x_idx, 0);
00422   EXPECT_EQ (cloud_blob.fields[x_idx].offset, uint32_t (0));
00423   EXPECT_EQ (cloud_blob.fields[x_idx].name, "x");
00424   EXPECT_EQ (cloud_blob.fields[x_idx].datatype, pcl::PCLPointField::FLOAT32);
00425   EXPECT_EQ (cloud_blob.fields[x_idx].count, uint32_t (1));
00426   y_idx = pcl::getFieldIndex (cloud_blob, "y");
00427   EXPECT_EQ (y_idx, 1);
00428   EXPECT_EQ (cloud_blob.fields[y_idx].offset, uint32_t (4));
00429   EXPECT_EQ (cloud_blob.fields[y_idx].name, "y");
00430   EXPECT_EQ (cloud_blob.fields[y_idx].datatype, pcl::PCLPointField::FLOAT32);
00431   EXPECT_EQ (cloud_blob.fields[y_idx].count, uint32_t (1));
00432   z_idx = pcl::getFieldIndex (cloud_blob, "z");
00433   EXPECT_EQ (z_idx, 2);
00434   EXPECT_EQ (cloud_blob.fields[z_idx].offset, uint32_t (8));
00435   EXPECT_EQ (cloud_blob.fields[z_idx].name, "z");
00436   EXPECT_EQ (cloud_blob.fields[z_idx].datatype, pcl::PCLPointField::FLOAT32);
00437   EXPECT_EQ (cloud_blob.fields[z_idx].count, uint32_t (1));
00438   intensity_idx = pcl::getFieldIndex (cloud_blob, "intensity");
00439   EXPECT_EQ (intensity_idx, 3);
00440   //EXPECT_EQ (cloud_blob.fields[intensity_idx].offset, (uint32_t)12);      // NOTE: the fields.offset is 16 in PointCloud<PointXYZI>, but we are obtaining the correct offset in toPCLPointCloud2
00441   EXPECT_EQ (cloud_blob.fields[intensity_idx].offset, uint32_t (16));      // NOTE: the fields.offset is 16 in PointCloud<PointXYZI>, but we are obtaining the correct offset in toPCLPointCloud2
00442   EXPECT_EQ (cloud_blob.fields[intensity_idx].name, "intensity");
00443   EXPECT_EQ (cloud_blob.fields[intensity_idx].datatype, pcl::PCLPointField::FLOAT32);
00444   EXPECT_EQ (cloud_blob.fields[intensity_idx].count, uint32_t (1));
00445   
00446   fromPCLPointCloud2 (cloud_blob, cloud);
00447   for (size_t i = 0; i < nr_p; ++i)
00448     EXPECT_EQ (cloud.points[i].intensity, i);
00449 
00450   EXPECT_EQ (uint32_t (cloud_blob.width), cloud.width);    // test for toPCLPointCloud2 ()
00451   EXPECT_EQ (uint32_t (cloud_blob.height), cloud.height);  // test for toPCLPointCloud2 ()
00452   EXPECT_EQ (bool (cloud_blob.is_dense), cloud.is_dense);  // test for toPCLPointCloud2 ()
00453   //EXPECT_EQ ((size_t)cloud_blob.data.size () * 2,         // PointXYZI is 16*2 (XYZ+1, Intensity+3)
00454   //           cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));  // test for toPCLPointCloud2 ()
00455   EXPECT_EQ (size_t (cloud_blob.data.size ()),             // PointXYZI is 16*2 (XYZ+1, Intensity+3)
00456              cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));  // test for toPCLPointCloud2 ()
00457 
00458   // Make sure we have permissions to write there
00459   PCDWriter w;
00460   int res = w.writeASCII ("test_pcl_io.pcd", cloud_blob, Eigen::Vector4f::Zero (), Eigen::Quaternionf::Identity (), 10);
00461   EXPECT_EQ (int (res), 0);                            // test for savePCDFileASCII ()
00462 
00463   // Please make sure that this file exists, otherwise the test will fail.
00464   res = loadPCDFile ("test_pcl_io.pcd", cloud_blob);
00465   EXPECT_NE (int (res), -1);                               // test for loadPCDFile ()
00466   EXPECT_EQ (uint32_t (cloud_blob.width), cloud.width);    // test for loadPCDFile ()
00467   EXPECT_EQ (uint32_t (cloud_blob.height), cloud.height);  // test for loadPCDFile ()
00468   EXPECT_EQ (bool (cloud_blob.is_dense), cloud.is_dense);  // test for loadPCDFile ()
00469   EXPECT_EQ (size_t (cloud_blob.data.size () * 2),         // PointXYZI is 16*2 (XYZ+1, Intensity+3)
00470               cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));  // test for loadPCDFile ()
00471 
00472   // Convert from blob to data type
00473   fromPCLPointCloud2 (cloud_blob, cloud);
00474 
00475   EXPECT_EQ (uint32_t (cloud.width), cloud_blob.width);    // test for fromPCLPointCloud2 ()
00476   EXPECT_EQ (uint32_t (cloud.height), cloud_blob.height);  // test for fromPCLPointCloud2 ()
00477   EXPECT_EQ (int (cloud.is_dense), cloud_blob.is_dense);   // test for fromPCLPointCloud2 ()
00478   EXPECT_EQ (size_t (cloud.points.size ()), nr_p);         // test for fromPCLPointCloud2 ()
00479 
00480   EXPECT_FLOAT_EQ (cloud.points[0].x, first.x);     // test for fromPCLPointCloud2 ()
00481   EXPECT_FLOAT_EQ (cloud.points[0].y, first.y);     // test for fromPCLPointCloud2 ()
00482   EXPECT_FLOAT_EQ (cloud.points[0].z, first.z);     // test for fromPCLPointCloud2 ()
00483   EXPECT_FLOAT_EQ (cloud.points[0].intensity, first.intensity);  // test for fromPCLPointCloud2 ()
00484 
00485   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].x, last.x);    // test for fromPCLPointCloud2 ()
00486   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].y, last.y);    // test for fromPCLPointCloud2 ()
00487   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].z, last.z);    // test for fromPCLPointCloud2 ()
00488   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].intensity, last.intensity); // test for fromPCLPointCloud2 ()
00489 
00490   // Make sure we have permissions to write there
00491   res = savePCDFile ("test_pcl_io.pcd", cloud_blob, Eigen::Vector4f::Zero (), Eigen::Quaternionf::Identity (), true);
00492   EXPECT_EQ (int (res), 0);                            // test for savePCDFileBinary ()
00493 
00494   // Please make sure that this file exists, otherwise the test will fail.
00495   res = loadPCDFile ("test_pcl_io.pcd", cloud_blob);
00496   EXPECT_NE (int (res), -1);                               // test for loadPCDFile ()
00497   EXPECT_EQ (uint32_t (cloud_blob.width), cloud.width);    // test for loadPCDFile ()
00498   EXPECT_EQ (uint32_t (cloud_blob.height), cloud.height);  // test for loadPCDFile ()
00499   EXPECT_EQ (bool (cloud_blob.is_dense), cloud.is_dense);
00500   EXPECT_EQ (size_t (cloud_blob.data.size () * 2),         // PointXYZI is 16*2 (XYZ+1, Intensity+3)
00501               cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));  // test for loadPCDFile ()
00502 
00503   // Convert from blob to data type
00504   fromPCLPointCloud2 (cloud_blob, cloud);
00505 
00506   EXPECT_EQ (uint32_t (cloud.width), cloud_blob.width);    // test for fromPCLPointCloud2 ()
00507   EXPECT_EQ (uint32_t (cloud.height), cloud_blob.height);  // test for fromPCLPointCloud2 ()
00508   EXPECT_EQ (int (cloud.is_dense), cloud_blob.is_dense);   // test for fromPCLPointCloud2 ()
00509   EXPECT_EQ (size_t (cloud.points.size ()), nr_p);         // test for fromPCLPointCloud2 ()
00510 
00511   EXPECT_FLOAT_EQ (cloud.points[0].x, first.x);     // test for fromPCLPointCloud2 ()
00512   EXPECT_FLOAT_EQ (cloud.points[0].y, first.y);     // test for fromPCLPointCloud2 ()
00513   EXPECT_FLOAT_EQ (cloud.points[0].z, first.z);     // test for fromPCLPointCloud2 ()
00514   EXPECT_FLOAT_EQ (cloud.points[0].intensity, first.intensity);  // test for fromPCLPointCloud2 ()
00515 
00516   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].x, last.x);    // test for fromPCLPointCloud2 ()
00517   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].y, last.y);    // test for fromPCLPointCloud2 ()
00518   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].z, last.z);    // test for fromPCLPointCloud2 ()
00519   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].intensity, last.intensity); // test for fromPCLPointCloud2 ()
00520 
00521   // Save as ASCII
00522   try
00523   {
00524     w.write<PointXYZI> ("test_pcl_io_binary.pcd", cloud, true);
00525   }
00526   catch (pcl::IOException &e)
00527   {
00528     std::cerr << e.detailedMessage () << std::endl;
00529   }
00530   res = loadPCDFile ("test_pcl_io_binary.pcd", cloud_blob);
00531   EXPECT_NE (int (res), -1);                               // test for loadPCDFile ()
00532   EXPECT_EQ (uint32_t (cloud_blob.width), cloud.width);    // test for loadPCDFile ()
00533   EXPECT_EQ (uint32_t (cloud_blob.height), cloud.height);  // test for loadPCDFile ()
00534   EXPECT_EQ (bool (cloud_blob.is_dense), cloud.is_dense);
00535   EXPECT_EQ (size_t (cloud_blob.data.size () * 2),         // PointXYZI is 16*2 (XYZ+1, Intensity+3)
00536               cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));  // test for loadPCDFile ()
00537 
00538   // Convert from blob to data type
00539   fromPCLPointCloud2 (cloud_blob, cloud);
00540 
00541   EXPECT_EQ (uint32_t (cloud.width), cloud_blob.width);    // test for fromPCLPointCloud2 ()
00542   EXPECT_EQ (uint32_t (cloud.height), cloud_blob.height);  // test for fromPCLPointCloud2 ()
00543   EXPECT_EQ (int (cloud.is_dense), cloud_blob.is_dense);   // test for fromPCLPointCloud2 ()
00544   EXPECT_EQ (size_t (cloud.points.size ()), nr_p);         // test for fromPCLPointCloud2 ()
00545 
00546   EXPECT_FLOAT_EQ (cloud.points[0].x, first.x);     // test for fromPCLPointCloud2 ()
00547   EXPECT_FLOAT_EQ (cloud.points[0].y, first.y);     // test for fromPCLPointCloud2 ()
00548   EXPECT_FLOAT_EQ (cloud.points[0].z, first.z);     // test for fromPCLPointCloud2 ()
00549   EXPECT_FLOAT_EQ (cloud.points[0].intensity, first.intensity);  // test for fromPCLPointCloud2 ()
00550 
00551   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].x, last.x);    // test for fromPCLPointCloud2 ()
00552   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].y, last.y);    // test for fromPCLPointCloud2 ()
00553   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].z, last.z);    // test for fromPCLPointCloud2 ()
00554   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].intensity, last.intensity); // test for fromPCLPointCloud2 ()
00555 
00556   // Save as ASCII
00557   try
00558   {
00559     w.write<PointXYZI> ("test_pcl_io_ascii.pcd", cloud, false);
00560   }
00561   catch (pcl::IOException &e)
00562   {
00563     std::cerr << e.detailedMessage () << std::endl;
00564   }
00565   res = loadPCDFile ("test_pcl_io_ascii.pcd", cloud_blob);
00566   EXPECT_NE (int (res), -1);                               // test for loadPCDFile ()
00567   EXPECT_EQ (uint32_t (cloud_blob.width), cloud.width);    // test for loadPCDFile ()
00568   EXPECT_EQ (uint32_t (cloud_blob.height), cloud.height);  // test for loadPCDFile ()
00569   EXPECT_EQ (bool (cloud_blob.is_dense), true);
00570   EXPECT_EQ (size_t (cloud_blob.data.size () * 2),         // PointXYZI is 16*2 (XYZ+1, Intensity+3)
00571               cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));  // test for loadPCDFile ()
00572 
00573   // Convert from blob to data type
00574   fromPCLPointCloud2 (cloud_blob, cloud);
00575 
00576   EXPECT_EQ (uint32_t (cloud.width), cloud_blob.width);    // test for fromPCLPointCloud2 ()
00577   EXPECT_EQ (uint32_t (cloud.height), cloud_blob.height);  // test for fromPCLPointCloud2 ()
00578   EXPECT_EQ (int (cloud.is_dense), cloud_blob.is_dense);   // test for fromPCLPointCloud2 ()
00579   EXPECT_EQ (size_t (cloud.points.size ()), nr_p);         // test for fromPCLPointCloud2 ()
00580 
00581   EXPECT_FLOAT_EQ (cloud.points[0].x, first.x);     // test for fromPCLPointCloud2 ()
00582   EXPECT_FLOAT_EQ (cloud.points[0].y, first.y);     // test for fromPCLPointCloud2 ()
00583   EXPECT_FLOAT_EQ (cloud.points[0].z, first.z);     // test for fromPCLPointCloud2 ()
00584   EXPECT_FLOAT_EQ (cloud.points[0].intensity, first.intensity);  // test for fromPCLPointCloud2 ()
00585 
00586   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].x, last.x);    // test for fromPCLPointCloud2 ()
00587   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].y, last.y);    // test for fromPCLPointCloud2 ()
00588   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].z, last.z);    // test for fromPCLPointCloud2 ()
00589   EXPECT_FLOAT_EQ (float (cloud.points[nr_p - 1].intensity), float (last.intensity)); // test for fromPCLPointCloud2 ()
00590 
00591   std::vector<int> indices (cloud.width * cloud.height / 2);
00592   for (int i = 0; i < static_cast<int> (indices.size ()); ++i) indices[i] = i;
00593   // Save as ASCII
00594   try
00595   {
00596     w.write<PointXYZI> ("test_pcl_io_binary.pcd", cloud, indices, true);
00597   }
00598   catch (pcl::IOException &e)
00599   {
00600     std::cerr << e.detailedMessage () << std::endl;
00601   }
00602   res = loadPCDFile ("test_pcl_io_binary.pcd", cloud_blob);
00603   EXPECT_NE (int (res), -1);                               // test for loadPCDFile ()
00604   EXPECT_EQ (uint32_t (cloud_blob.width), cloud.width * cloud.height / 2);    // test for loadPCDFile ()
00605   EXPECT_EQ (uint32_t (cloud_blob.height), 1);  // test for loadPCDFile ()
00606   EXPECT_EQ (bool (cloud_blob.is_dense), cloud.is_dense);
00607   EXPECT_EQ (size_t (cloud_blob.data.size () * 2),         // PointXYZI is 16*2 (XYZ+1, Intensity+3)
00608               cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));  // test for loadPCDFile ()
00609 
00610   // Convert from blob to data type
00611   fromPCLPointCloud2 (cloud_blob, cloud);
00612 
00613   EXPECT_EQ (uint32_t (cloud.width), cloud_blob.width);    // test for fromPCLPointCloud2 ()
00614   EXPECT_EQ (uint32_t (cloud.height), cloud_blob.height);  // test for fromPCLPointCloud2 ()
00615   EXPECT_EQ (int (cloud.is_dense), cloud_blob.is_dense);   // test for fromPCLPointCloud2 ()
00616   EXPECT_EQ (size_t (cloud.points.size ()), nr_p / 2);         // test for fromPCLPointCloud2 ()
00617 
00618   EXPECT_FLOAT_EQ (cloud.points[0].x, first.x);     // test for fromPCLPointCloud2 ()
00619   EXPECT_FLOAT_EQ (cloud.points[0].y, first.y);     // test for fromPCLPointCloud2 ()
00620   EXPECT_FLOAT_EQ (cloud.points[0].z, first.z);     // test for fromPCLPointCloud2 ()
00621   EXPECT_FLOAT_EQ (float (cloud.points[0].intensity), float (first.intensity));  // test for fromPCLPointCloud2 ()
00622 
00623   indices.resize (cloud.width * cloud.height / 2);
00624   for (int i = 0; i < static_cast<int> (indices.size ()); ++i) indices[i] = i;
00625   // Save as ASCII
00626   try
00627   {
00628     w.write<PointXYZI> ("test_pcl_io_ascii.pcd", cloud, indices, false);
00629   }
00630   catch (pcl::IOException &e)
00631   {
00632     std::cerr << e.detailedMessage () << std::endl;
00633   }
00634   res = loadPCDFile ("test_pcl_io_ascii.pcd", cloud_blob);
00635   EXPECT_NE (int (res), -1);                               // test for loadPCDFile ()
00636   EXPECT_EQ (uint32_t (cloud_blob.width), cloud.width * cloud.height / 2);    // test for loadPCDFile ()
00637   EXPECT_EQ (uint32_t (cloud_blob.height), 1);  // test for loadPCDFile ()
00638   EXPECT_EQ (bool (cloud_blob.is_dense), true);
00639   EXPECT_EQ (size_t (cloud_blob.data.size () * 2),         // PointXYZI is 16*2 (XYZ+1, Intensity+3)
00640               cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));  // test for loadPCDFile ()
00641 
00642   // Convert from blob to data type
00643   fromPCLPointCloud2 (cloud_blob, cloud);
00644 
00645   EXPECT_EQ (uint32_t (cloud.width), cloud_blob.width);    // test for fromPCLPointCloud2 ()
00646   EXPECT_EQ (uint32_t (cloud.height), cloud_blob.height);  // test for fromPCLPointCloud2 ()
00647   EXPECT_EQ (int (cloud.is_dense), cloud_blob.is_dense);   // test for fromPCLPointCloud2 ()
00648   EXPECT_EQ (size_t (cloud.points.size ()), nr_p / 4);         // test for fromPCLPointCloud2 ()
00649 
00650   EXPECT_FLOAT_EQ (cloud.points[0].x, first.x);     // test for fromPCLPointCloud2 ()
00651   EXPECT_FLOAT_EQ (cloud.points[0].y, first.y);     // test for fromPCLPointCloud2 ()
00652   EXPECT_FLOAT_EQ (cloud.points[0].z, first.z);     // test for fromPCLPointCloud2 ()
00653   EXPECT_FLOAT_EQ (cloud.points[0].intensity, first.intensity);  // test for fromPCLPointCloud2 ()
00654 }
00655 
00657 TEST (PCL, PCDReaderWriter)
00658 {
00659   pcl::PCLPointCloud2 cloud_blob;
00660   PointCloud<PointXYZI> cloud;
00661 
00662   cloud.width  = 640;
00663   cloud.height = 480;
00664   cloud.points.resize (cloud.width * cloud.height);
00665   cloud.is_dense = true;
00666 
00667   srand (static_cast<unsigned int> (time (NULL)));
00668   size_t nr_p = cloud.points.size ();
00669   // Randomly create a new point cloud
00670   for (size_t i = 0; i < nr_p; ++i)
00671   {
00672     cloud.points[i].x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00673     cloud.points[i].y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00674     cloud.points[i].z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00675     cloud.points[i].intensity = static_cast<float> (i);
00676   }
00677   PointXYZI first, last;
00678   first.x = cloud.points[0].x;       first.y = cloud.points[0].y;       first.z = cloud.points[0].z;       first.intensity = cloud.points[0].intensity;
00679   last.x = cloud.points[nr_p - 1].x; last.y = cloud.points[nr_p - 1].y; last.z = cloud.points[nr_p - 1].z; last.intensity  = cloud.points[nr_p - 1].intensity;
00680 
00681   // Convert from data type to blob
00682   toPCLPointCloud2 (cloud, cloud_blob);
00683 
00684   EXPECT_EQ (uint32_t (cloud_blob.width), cloud.width);    // test for toPCLPointCloud2 ()
00685   EXPECT_EQ (uint32_t (cloud_blob.height), cloud.height);  // test for toPCLPointCloud2 ()
00686   EXPECT_EQ (bool (cloud_blob.is_dense), cloud.is_dense);  // test for toPCLPointCloud2 ()
00687   //EXPECT_EQ ((size_t)cloud_blob.data.size () * 2,         // PointXYZI is 16*2 (XYZ+1, Intensity+3)
00688   //           cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));  // test for toPCLPointCloud2 ()
00689   EXPECT_EQ (size_t (cloud_blob.data.size ()),         // PointXYZI is 16*2 (XYZ+1, Intensity+3)
00690              cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));  // test for toPCLPointCloud2 ()
00691 
00692   PCDWriter writer;
00693   writer.write ("test_pcl_io.pcd", cloud_blob, Eigen::Vector4f::Zero (), Eigen::Quaternionf::Identity (), true);
00694 
00695   PCDReader reader;
00696   reader.read ("test_pcl_io.pcd", cloud_blob);
00697   EXPECT_EQ (uint32_t (cloud_blob.width), cloud.width);
00698   EXPECT_EQ (uint32_t (cloud_blob.height), cloud.height);
00699   EXPECT_EQ (bool (cloud_blob.is_dense), cloud.is_dense);
00700   //EXPECT_EQ ((size_t)cloud_blob.data.size () * 2,         // PointXYZI is 16*2 (XYZ+1, Intensity+3)
00701   //           cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));  // test for loadPCDFile ()
00702   EXPECT_EQ (size_t (cloud_blob.data.size ()),         // PointXYZI is 16*2 (XYZ+1, Intensity+3)
00703              cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));  // test for loadPCDFile ()
00704 
00705   // Convert from blob to data type
00706   fromPCLPointCloud2 (cloud_blob, cloud);
00707 
00708   EXPECT_EQ (uint32_t (cloud.width), cloud_blob.width);    // test for fromPCLPointCloud2 ()
00709   EXPECT_EQ (uint32_t (cloud.height), cloud_blob.height);  // test for fromPCLPointCloud2 ()
00710   EXPECT_EQ (int (cloud.is_dense), cloud_blob.is_dense);   // test for fromPCLPointCloud2 ()
00711   EXPECT_EQ (size_t (cloud.points.size ()), nr_p);         // test for fromPCLPointCloud2 ()
00712 
00713   EXPECT_FLOAT_EQ (cloud.points[0].x, first.x);     // test for fromPCLPointCloud2 ()
00714   EXPECT_FLOAT_EQ (cloud.points[0].y, first.y);     // test for fromPCLPointCloud2 ()
00715   EXPECT_FLOAT_EQ (cloud.points[0].z, first.z);     // test for fromPCLPointCloud2 ()
00716   EXPECT_FLOAT_EQ (cloud.points[0].intensity, first.intensity);  // test for fromPCLPointCloud2 ()
00717 
00718   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].x, last.x);    // test for fromPCLPointCloud2 ()
00719   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].y, last.y);    // test for fromPCLPointCloud2 ()
00720   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].z, last.z);    // test for fromPCLPointCloud2 ()
00721   EXPECT_FLOAT_EQ (cloud.points[nr_p - 1].intensity, last.intensity); // test for fromPCLPointCloud2 ()
00722 }
00723 
00724 TEST (PCL, PCDReaderWriterASCIIColorPrecision)
00725 {
00726   PointCloud<PointXYZRGB> cloud;
00727   for (size_t r_i = 0; r_i < 256; r_i += 5)
00728     for (size_t g_i = 0; g_i < 256; g_i += 5)
00729       for (size_t b_i = 0; b_i < 256; b_i += 5)
00730       {
00731         PointXYZRGB p;
00732         p.r = static_cast<unsigned char> (r_i);
00733         p.g = static_cast<unsigned char> (g_i);
00734         p.b = static_cast<unsigned char> (b_i);
00735         p.x = p.y = p.z = 0.f;
00736 
00737         cloud.push_back (p);
00738       }
00739   cloud.height = 1;
00740   cloud.width = uint32_t (cloud.size ());
00741   cloud.is_dense = true;
00742 
00743   io::savePCDFile ("temp_binary_color.pcd", cloud, true);
00744   PointCloud<PointXYZRGB> cloud_binary;
00745   io::loadPCDFile ("temp_binary_color.pcd", cloud_binary);
00746   for (size_t i = 0; i < cloud.size (); ++i)
00747   {
00748     EXPECT_EQ (cloud[i].r, cloud_binary[i].r);
00749     EXPECT_EQ (cloud[i].g, cloud_binary[i].g);
00750     EXPECT_EQ (cloud[i].b, cloud_binary[i].b);
00751   }
00752 
00753   io::savePCDFile ("temp_ascii_color.pcd", cloud, false);
00754   PointCloud<PointXYZRGB> cloud_ascii;
00755   io::loadPCDFile ("temp_ascii_color.pcd", cloud_ascii);
00756   for (size_t i = 0; i < cloud.size (); ++i)
00757   {
00758     EXPECT_EQ (cloud[i].r, cloud_ascii[i].r);
00759     EXPECT_EQ (cloud[i].g, cloud_ascii[i].g);
00760     EXPECT_EQ (cloud[i].b, cloud_ascii[i].b);
00761   }
00762 }
00763 
00766 TEST (PCL, ASCIIReader)
00767 {
00768   PointCloud<PointXYZI> cloud, rcloud;
00769 
00770   cloud.width  = 300;
00771   cloud.height = 1;
00772   cloud.points.resize (cloud.width * cloud.height);
00773   cloud.is_dense = true;
00774 
00775 
00776   std::fstream afile ("test_pcd.txt", std::iostream::out);
00777 
00778   afile<< std::setprecision(10);
00779 
00780   srand (static_cast<unsigned int> (time (NULL)));
00781   size_t nr_p = cloud.points.size ();
00782   // Randomly create a new point cloud
00783   for (size_t i = 0; i < nr_p; ++i)
00784   {
00785     cloud.points[i].x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00786     cloud.points[i].y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00787     cloud.points[i].z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00788     cloud.points[i].intensity = static_cast<float> (i);
00789    afile << cloud.points[i].x << " , " << cloud.points[i].y  << " , " << cloud.points[i].z << " , "  << cloud.points[i].intensity << " \n";
00790   }
00791   afile.close();
00792 
00793   ASCIIReader reader;
00794   reader.setInputFields( pcl::PointXYZI() );
00795 
00796   EXPECT_GE(reader.read("test_pcd.txt", rcloud), 0);
00797   EXPECT_EQ(cloud.points.size(), rcloud.points.size() );
00798 
00799   for(int i=0;i < rcloud.points.size(); i++){
00800     EXPECT_FLOAT_EQ(cloud.points[i].x, rcloud.points[i].x);
00801     EXPECT_FLOAT_EQ(cloud.points[i].y,rcloud.points[i].y);
00802     EXPECT_FLOAT_EQ(cloud.points[i].z, rcloud.points[i].z);
00803     EXPECT_FLOAT_EQ(cloud.points[i].intensity, rcloud.points[i].intensity);
00804   }
00805 
00806 }
00807 
00809 TEST (PCL, PLYReaderWriter)
00810 {
00811   pcl::PCLPointCloud2 cloud_blob, cloud_blob2;
00812   PointCloud<PointXYZI> cloud, cloud2;
00813 
00814   cloud.width  = 640;
00815   cloud.height = 480;
00816   cloud.resize (cloud.width * cloud.height);
00817   cloud.is_dense = true;
00818 
00819   srand (static_cast<unsigned int> (time (NULL)));
00820   size_t nr_p = cloud.size ();
00821   // Randomly create a new point cloud
00822   for (size_t i = 0; i < nr_p; ++i)
00823   {
00824     cloud[i].x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00825     cloud[i].y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00826     cloud[i].z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00827     cloud[i].intensity = static_cast<float> (i);
00828   }
00829 
00830   // Convert from data type to blob
00831   toPCLPointCloud2 (cloud, cloud_blob);
00832 
00833   EXPECT_EQ (cloud_blob.width, cloud.width);    // test for toPCLPointCloud2 ()
00834   EXPECT_EQ (cloud_blob.height, cloud.height);  // test for toPCLPointCloud2 ()
00835   EXPECT_EQ (cloud_blob.is_dense, cloud.is_dense);  // test for toPCLPointCloud2 ()
00836   EXPECT_EQ (cloud_blob.data.size (), 
00837              cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));  
00838 
00839   // test for toPCLPointCloud2 ()
00840   PLYWriter writer;
00841   writer.write ("test_pcl_io.ply", cloud_blob, Eigen::Vector4f::Zero (), Eigen::Quaternionf::Identity (), true, true);
00842 
00843   PLYReader reader;
00844   reader.read ("test_pcl_io.ply", cloud_blob2);
00845   //PLY DOES preserve organiziation
00846   EXPECT_EQ (cloud_blob.width * cloud_blob.height, cloud_blob2.width * cloud_blob2.height);
00847   EXPECT_EQ (cloud_blob.is_dense, cloud.is_dense);   
00848   EXPECT_EQ (size_t (cloud_blob2.data.size ()),         // PointXYZI is 16*2 (XYZ+1, Intensity+3)
00849              cloud_blob2.width * cloud_blob2.height * sizeof (PointXYZ));  // test for loadPLYFile ()
00850 
00851   // Convert from blob to data type
00852   fromPCLPointCloud2 (cloud_blob2, cloud2);
00853 
00854   // EXPECT_EQ (cloud.width, cloud2.width);    // test for fromPCLPointCloud2 ()
00855   // EXPECT_EQ (cloud.height, cloud2.height);  // test for fromPCLPointCloud2 ()
00856   // EXPECT_EQ (cloud.is_dense, cloud2.is_dense);   // test for fromPCLPointCloud2 ()
00857   EXPECT_EQ (cloud.size (), cloud2.size ());         // test for fromPCLPointCloud2 ()
00858 
00859   for (uint32_t counter = 0; counter < cloud.size (); ++counter)
00860   {
00861     EXPECT_FLOAT_EQ (cloud[counter].x, cloud2[counter].x);     // test for fromPCLPointCloud2 ()
00862     EXPECT_FLOAT_EQ (cloud[counter].y, cloud2[counter].y);     // test for fromPCLPointCloud2 ()
00863     EXPECT_FLOAT_EQ (cloud[counter].z, cloud2[counter].z);     // test for fromPCLPointCloud2 ()
00864     EXPECT_FLOAT_EQ (cloud[counter].intensity, cloud2[counter].intensity);  // test for fromPCLPointCloud2 ()
00865   }
00866 }
00867 
00869 
00870 struct PointXYZFPFH33
00871 {
00872   float x, y, z;
00873   float histogram[33];
00874 };
00875 POINT_CLOUD_REGISTER_POINT_STRUCT (PointXYZFPFH33,
00876     (float, x, x) (float, y, y) (float, z, z)
00877     (float[33], histogram, fpfh))
00878 
00879 inline std::ostream& operator << (std::ostream& os, const PointXYZFPFH33& p)
00880 {
00881   os << "(" << p.x << "," << p.y << "," << p.z << ")";
00882   for (int i = 0; i < 33; ++i) 
00883     os << (i == 0 ? "(" :"") << p.histogram[i] << (i < 32 ? ", " : ")");
00884   return os;
00885 }
00886 
00888 TEST (PCL, ExtendedIO)
00889 {
00890   PointCloud<PointXYZFPFH33> cloud;
00891   cloud.width = 2; cloud.height = 1;
00892   cloud.points.resize (2);
00893 
00894   cloud.points[0].x = cloud.points[0].y = cloud.points[0].z = 1;
00895   cloud.points[1].x = cloud.points[1].y = cloud.points[1].z = 2;
00896   for (int i = 0; i < 33; ++i)
00897   {
00898     cloud.points[0].histogram[i] = static_cast<float> (i);
00899     cloud.points[1].histogram[i] = 33.0f - static_cast<float> (i);
00900   }
00901 
00902   savePCDFile ("v.pcd", cloud);
00903   cloud.points.clear ();
00904   loadPCDFile ("v.pcd", cloud);
00905 
00906   EXPECT_EQ (int (cloud.width), 2);
00907   EXPECT_EQ (int (cloud.height), 1);
00908   EXPECT_EQ (cloud.is_dense, true);
00909   EXPECT_EQ (int (cloud.points.size ()), 2);
00910   
00911   EXPECT_EQ (cloud.points[0].x, 1); EXPECT_EQ (cloud.points[0].y, 1); EXPECT_EQ (cloud.points[0].z, 1);
00912   EXPECT_EQ (cloud.points[1].x, 2); EXPECT_EQ (cloud.points[1].y, 2); EXPECT_EQ (cloud.points[1].z, 2);
00913   for (int i = 0; i < 33; ++i)
00914   {
00915     ASSERT_EQ (cloud.points[0].histogram[i], i);
00916     ASSERT_EQ (cloud.points[1].histogram[i], 33-i);
00917   }
00918 }
00919 
00920 
00922 TEST (PCL, EigenConversions)
00923 {
00924   PointCloud<PointXYZ> cloud;
00925   cloud.points.resize (5);
00926 
00927   for (int i = 0; i < int (cloud.points.size ()); ++i)
00928     cloud.points[i].x = cloud.points[i].y = cloud.points[i].z = static_cast<float> (i);
00929 
00930   pcl::PCLPointCloud2 blob;
00931   toPCLPointCloud2 (cloud, blob);
00932 
00933   Eigen::MatrixXf mat;
00934   getPointCloudAsEigen (blob, mat);
00935   EXPECT_EQ (mat.cols (), int (cloud.points.size ()));
00936   EXPECT_EQ (mat.rows (), 4);
00937   
00938   for (size_t i = 0; i < cloud.points.size (); ++i)
00939   {
00940     EXPECT_EQ (mat (0, i), cloud.points[i].x);
00941     EXPECT_EQ (mat (1, i), cloud.points[i].y);
00942     EXPECT_EQ (mat (2, i), cloud.points[i].z);
00943     EXPECT_EQ (mat (3, i), 1);
00944   }
00945   
00946   getEigenAsPointCloud (mat, blob);
00947   fromPCLPointCloud2 (blob, cloud);
00948   for (size_t i = 0; i < cloud.points.size (); ++i)
00949   {
00950     EXPECT_EQ (cloud.points[i].x, i);
00951     EXPECT_EQ (cloud.points[i].y, i);
00952     EXPECT_EQ (cloud.points[i].z, i);
00953   }
00954 
00955   getPointCloudAsEigen (blob, mat);
00956   EXPECT_EQ (mat.cols (), int (cloud.points.size ()));
00957   EXPECT_EQ (mat.rows (), 4);
00958   
00959   for (size_t i = 0; i < cloud.points.size (); ++i)
00960   {
00961     EXPECT_EQ (mat (0, i), cloud.points[i].x);
00962     EXPECT_EQ (mat (1, i), cloud.points[i].y);
00963     EXPECT_EQ (mat (2, i), cloud.points[i].z);
00964     EXPECT_EQ (mat (3, i), 1);
00965   }
00966 }
00967 
00969 TEST (PCL, CopyPointCloud)
00970 {
00971   pcl::PointCloud<pcl::PointXYZ> cloud_a;
00972   pcl::PointCloud<pcl::PointXYZRGBA> cloud_b;
00973 
00974   // Fill in the cloud data
00975   cloud_a.width  = cloud_b.width  = 3;
00976   cloud_a.height = cloud_b.height = 1;
00977   cloud_a.points.resize (cloud_a.width * cloud_a.height);
00978   cloud_b.points.resize (cloud_b.width * cloud_b.height);
00979 
00980   for (size_t i = 0; i < cloud_a.points.size (); ++i)
00981   {
00982     cloud_a.points[i].x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00983     cloud_a.points[i].y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00984     cloud_a.points[i].z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00985     cloud_b.points[i].rgba = 255;
00986   }
00987 
00988   pcl::copyPointCloud<pcl::PointXYZ, pcl::PointXYZRGBA> (cloud_a, cloud_b);
00989 
00990   for (size_t i = 0; i < cloud_a.points.size (); ++i)
00991   {
00992     EXPECT_EQ (cloud_b.points[i].x, cloud_a.points[i].x);
00993     EXPECT_EQ (cloud_b.points[i].y, cloud_a.points[i].y);
00994     EXPECT_EQ (cloud_b.points[i].z, cloud_a.points[i].z);
00995     EXPECT_EQ (cloud_b.points[i].rgba, 255);
00996     cloud_a.points[i].x = cloud_a.points[i].y = cloud_a.points[i].z = 0;
00997   }
00998 
00999   pcl::copyPointCloud<pcl::PointXYZRGBA, pcl::PointXYZ> (cloud_b, cloud_a);
01000 
01001   for (size_t i = 0; i < cloud_a.points.size (); ++i)
01002   {
01003     EXPECT_EQ (cloud_b.points[i].x, cloud_a.points[i].x);
01004     EXPECT_EQ (cloud_b.points[i].y, cloud_a.points[i].y);
01005     EXPECT_EQ (cloud_b.points[i].z, cloud_a.points[i].z);
01006     EXPECT_EQ (cloud_b.points[i].rgba, 255);
01007   }
01008 }
01009 
01011 TEST (PCL, LZF)
01012 {
01013   PointCloud<PointXYZ> cloud, cloud2;
01014   cloud.width  = 640;
01015   cloud.height = 480;
01016   cloud.points.resize (cloud.width * cloud.height);
01017   cloud.is_dense = true;
01018 
01019   srand (static_cast<unsigned int> (time (NULL)));
01020   size_t nr_p = cloud.points.size ();
01021   // Randomly create a new point cloud
01022   for (size_t i = 0; i < nr_p; ++i)
01023   {
01024     cloud.points[i].x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
01025     cloud.points[i].y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
01026     cloud.points[i].z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
01027   }
01028   PCDWriter writer;
01029   int res = writer.writeBinaryCompressed<PointXYZ> ("test_pcl_io_compressed.pcd", cloud);
01030   EXPECT_EQ (res, 0);
01031 
01032   PCDReader reader;
01033   reader.read<PointXYZ> ("test_pcl_io_compressed.pcd", cloud2);
01034 
01035   EXPECT_EQ (cloud2.width, cloud.width);
01036   EXPECT_EQ (cloud2.height, cloud.height);
01037   EXPECT_EQ (cloud2.is_dense, cloud.is_dense);
01038   EXPECT_EQ (cloud2.points.size (), cloud.points.size ());
01039 
01040   for (size_t i = 0; i < cloud2.points.size (); ++i)
01041   {
01042     ASSERT_EQ (cloud2.points[i].x, cloud.points[i].x);
01043     ASSERT_EQ (cloud2.points[i].y, cloud.points[i].y);
01044     ASSERT_EQ (cloud2.points[i].z, cloud.points[i].z);
01045   }
01046 
01047   pcl::PCLPointCloud2 blob;
01048   pcl::toPCLPointCloud2 (cloud, blob);
01049   res = writer.writeBinaryCompressed ("test_pcl_io_compressed.pcd", blob);
01050   EXPECT_EQ (res, 0);
01051 
01052   reader.read<PointXYZ> ("test_pcl_io_compressed.pcd", cloud2);
01053 
01054   EXPECT_EQ (cloud2.width, blob.width);
01055   EXPECT_EQ (cloud2.height, blob.height);
01056   EXPECT_EQ (cloud2.is_dense, cloud.is_dense);
01057   EXPECT_EQ (cloud2.points.size (), cloud.points.size ());
01058 
01059   for (size_t i = 0; i < cloud2.points.size (); ++i)
01060   {
01061     EXPECT_EQ (cloud2.points[i].x, cloud.points[i].x);
01062     EXPECT_EQ (cloud2.points[i].y, cloud.points[i].y);
01063     EXPECT_EQ (cloud2.points[i].z, cloud.points[i].z);
01064   }
01065 }
01066 
01068 TEST (PCL, LZFExtended)
01069 {
01070   PointCloud<PointXYZRGBNormal> cloud, cloud2;
01071   cloud.width  = 640;
01072   cloud.height = 480;
01073   cloud.points.resize (cloud.width * cloud.height);
01074   cloud.is_dense = true;
01075 
01076   srand (static_cast<unsigned int> (time (NULL)));
01077   size_t nr_p = cloud.points.size ();
01078   // Randomly create a new point cloud
01079   for (size_t i = 0; i < nr_p; ++i)
01080   {
01081     cloud.points[i].x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
01082     cloud.points[i].y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
01083     cloud.points[i].z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
01084     cloud.points[i].normal_x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
01085     cloud.points[i].normal_y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
01086     cloud.points[i].normal_z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
01087     cloud.points[i].rgb = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
01088   }
01089 
01090   pcl::PCLPointCloud2 blob;
01091   pcl::toPCLPointCloud2 (cloud, blob);
01092 
01093   PCDWriter writer;
01094   int res = writer.writeBinaryCompressed ("test_pcl_io_compressed.pcd", blob);
01095   EXPECT_EQ (res, 0);
01096 
01097   PCDReader reader;
01098   reader.read<PointXYZRGBNormal> ("test_pcl_io_compressed.pcd", cloud2);
01099 
01100   EXPECT_EQ (cloud2.width, blob.width);
01101   EXPECT_EQ (cloud2.height, blob.height);
01102   EXPECT_EQ (cloud2.is_dense, cloud.is_dense);
01103   EXPECT_EQ (cloud2.points.size (), cloud.points.size ());
01104 
01105   for (size_t i = 0; i < cloud2.points.size (); ++i)
01106   {
01107     EXPECT_EQ (cloud2.points[i].x, cloud.points[i].x);
01108     EXPECT_EQ (cloud2.points[i].y, cloud.points[i].y);
01109     EXPECT_EQ (cloud2.points[i].z, cloud.points[i].z);
01110     EXPECT_EQ (cloud2.points[i].normal_x, cloud.points[i].normal_x);
01111     EXPECT_EQ (cloud2.points[i].normal_y, cloud.points[i].normal_y);
01112     EXPECT_EQ (cloud2.points[i].normal_z, cloud.points[i].normal_z);
01113     EXPECT_EQ (cloud2.points[i].rgb, cloud.points[i].rgb);
01114   }
01115 }
01116 
01118 TEST (PCL, Locale)
01119 {
01120 #ifndef __APPLE__
01121   try
01122   {
01123     PointCloud<PointXYZ> cloud, cloud2;
01124     cloud.width  = 640;
01125     cloud.height = 480;
01126     cloud.points.resize (cloud.width * cloud.height);
01127     cloud.is_dense = true;
01128 
01129     srand (static_cast<unsigned int> (time (NULL)));
01130     size_t nr_p = cloud.points.size ();
01131     // Randomly create a new point cloud
01132     cloud.points[0].x = std::numeric_limits<float>::quiet_NaN ();
01133     cloud.points[0].y = std::numeric_limits<float>::quiet_NaN ();
01134     cloud.points[0].z = std::numeric_limits<float>::quiet_NaN ();
01135   
01136     for (size_t i = 1; i < nr_p; ++i)
01137     {
01138       cloud.points[i].x = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
01139       cloud.points[i].y = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
01140       cloud.points[i].z = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
01141     }
01142     PCDWriter writer;
01143     try
01144     {
01145 #ifdef _WIN32
01146       std::locale::global (std::locale ("German_germany"));
01147 #else
01148       std::locale::global (std::locale ("de_DE.UTF-8"));
01149 #endif
01150     }
01151     catch (std::runtime_error e)
01152     {
01153       PCL_WARN ("Failed to set locale, skipping test.\n");
01154     }
01155     int res = writer.writeASCII<PointXYZ> ("test_pcl_io_ascii.pcd", cloud);
01156     EXPECT_EQ (res, 0);
01157 
01158     PCDReader reader;
01159     try
01160     {
01161 #ifdef _WIN32
01162       std::locale::global (std::locale ("English_US"));
01163 #else
01164       std::locale::global (std::locale ("en_US.UTF-8"));
01165 #endif
01166     }
01167     catch (std::runtime_error e)
01168     {
01169       PCL_WARN ("Failed to set locale, skipping test.\n");
01170     }
01171     reader.read<PointXYZ> ("test_pcl_io_ascii.pcd", cloud2);
01172     std::locale::global (std::locale::classic ());
01173 
01174     EXPECT_EQ (cloud2.width, cloud.width);
01175     EXPECT_EQ (cloud2.height, cloud.height);
01176     EXPECT_EQ (cloud2.is_dense, false);
01177     EXPECT_EQ (cloud2.points.size (), cloud.points.size ());
01178   
01179     EXPECT_TRUE (pcl_isnan(cloud2.points[0].x));
01180     EXPECT_TRUE (pcl_isnan(cloud2.points[0].y));
01181     EXPECT_TRUE (pcl_isnan(cloud2.points[0].z));
01182     for (size_t i = 1; i < cloud2.points.size (); ++i)
01183     {
01184       ASSERT_FLOAT_EQ (cloud2.points[i].x, cloud.points[i].x);
01185       ASSERT_FLOAT_EQ (cloud2.points[i].y, cloud.points[i].y);
01186       ASSERT_FLOAT_EQ (cloud2.points[i].z, cloud.points[i].z);
01187     }
01188   }
01189   catch(std::exception& e)
01190   {
01191   }
01192 #endif
01193 }
01194 
01195 /* ---[ */
01196 int
01197   main (int argc, char** argv)
01198 {
01199   testing::InitGoogleTest (&argc, argv);
01200   return (RUN_ALL_TESTS ());
01201 }
01202 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:35:02