00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00039 #include <gtest/gtest.h>
00040 #include <sensor_msgs/PointCloud2.h>
00041 #include "pcl/ros/point_traits.h"
00042 #include "pcl/point_types.h"
00043 #include "pcl/io/io.h"
00044 #include "pcl/io/pcd_io.h"
00045
00046 using namespace pcl;
00047 using namespace pcl::io;
00048
00050 TEST (PCL, ConcatenatePoints)
00051 {
00052 pcl::PointCloud<pcl::PointXYZ> cloud_a, cloud_b, cloud_c;
00053
00054
00055 cloud_a.width = 5;
00056 cloud_b.width = 3;
00057 cloud_a.height = cloud_b.height = 1;
00058 cloud_a.points.resize (cloud_a.width * cloud_a.height);
00059 cloud_b.points.resize (cloud_b.width * cloud_b.height);
00060
00061 for (size_t i = 0; i < cloud_a.points.size (); ++i)
00062 {
00063 cloud_a.points[i].x = 1024 * rand () / (RAND_MAX + 1.0);
00064 cloud_a.points[i].y = 1024 * rand () / (RAND_MAX + 1.0);
00065 cloud_a.points[i].z = 1024 * rand () / (RAND_MAX + 1.0);
00066 }
00067
00068 for (size_t i = 0; i < cloud_b.points.size (); ++i)
00069 {
00070 cloud_b.points[i].x = 1024 * rand () / (RAND_MAX + 1.0);
00071 cloud_b.points[i].y = 1024 * rand () / (RAND_MAX + 1.0);
00072 cloud_b.points[i].z = 1024 * rand () / (RAND_MAX + 1.0);
00073 }
00074
00075
00076 cloud_c = cloud_a;
00077 cloud_c += cloud_b;
00078 EXPECT_EQ (cloud_c.points.size (), cloud_a.points.size () + cloud_b.points.size ());
00079 EXPECT_EQ (cloud_c.width, cloud_a.width + cloud_b.width);
00080 EXPECT_EQ ((int)cloud_c.height, 1);
00081
00082 for (size_t i = 0; i < cloud_a.points.size (); ++i)
00083 {
00084 EXPECT_EQ (cloud_c.points[i].x, cloud_a.points[i].x);
00085 EXPECT_EQ (cloud_c.points[i].y, cloud_a.points[i].y);
00086 EXPECT_EQ (cloud_c.points[i].z, cloud_a.points[i].z);
00087 }
00088 for (size_t i = cloud_a.points.size (); i < cloud_c.points.size (); ++i)
00089 {
00090 EXPECT_EQ (cloud_c.points[i].x, cloud_b.points[i - cloud_a.points.size ()].x);
00091 EXPECT_EQ (cloud_c.points[i].y, cloud_b.points[i - cloud_a.points.size ()].y);
00092 EXPECT_EQ (cloud_c.points[i].z, cloud_b.points[i - cloud_a.points.size ()].z);
00093 }
00094 }
00095
00097 TEST (PCL, ConcatenateFields)
00098 {
00099 pcl::PointCloud<pcl::PointXYZ> cloud_a;
00100 pcl::PointCloud<pcl::Normal> cloud_b;
00101 pcl::PointCloud<pcl::PointNormal> cloud_c;
00102
00103
00104 cloud_a.width = cloud_b.width = 5;
00105 cloud_a.height = cloud_b.height = 1;
00106 cloud_a.points.resize (cloud_a.width * cloud_a.height);
00107 cloud_b.points.resize (cloud_b.width * cloud_b.height);
00108
00109 for (size_t i = 0; i < cloud_a.points.size (); ++i)
00110 {
00111 cloud_a.points[i].x = 1024 * rand () / (RAND_MAX + 1.0);
00112 cloud_a.points[i].y = 1024 * rand () / (RAND_MAX + 1.0);
00113 cloud_a.points[i].z = 1024 * rand () / (RAND_MAX + 1.0);
00114 }
00115
00116 for (size_t i = 0; i < cloud_b.points.size (); ++i)
00117 {
00118 cloud_b.points[i].normal[0] = 1024 * rand () / (RAND_MAX + 1.0);
00119 cloud_b.points[i].normal[1] = 1024 * rand () / (RAND_MAX + 1.0);
00120 cloud_b.points[i].normal[2] = 1024 * rand () / (RAND_MAX + 1.0);
00121 }
00122
00123 pcl::concatenateFields (cloud_a, cloud_b, cloud_c);
00124 EXPECT_EQ (cloud_c.points.size (), cloud_a.points.size ());
00125 EXPECT_EQ (cloud_c.width, cloud_a.width);
00126 EXPECT_EQ (cloud_c.height, cloud_a.height);
00127
00128 for (size_t i = 0; i < cloud_a.points.size (); ++i)
00129 {
00130 EXPECT_EQ (cloud_c.points[i].x, cloud_a.points[i].x);
00131 EXPECT_EQ (cloud_c.points[i].y, cloud_a.points[i].y);
00132 EXPECT_EQ (cloud_c.points[i].z, cloud_a.points[i].z);
00133 EXPECT_EQ (cloud_c.points[i].normal[0], cloud_b.points[i].normal[0]);
00134 EXPECT_EQ (cloud_c.points[i].normal[1], cloud_b.points[i].normal[1]);
00135 EXPECT_EQ (cloud_c.points[i].normal[2], cloud_b.points[i].normal[2]);
00136 }
00137 }
00138
00140 TEST (PCL, IO)
00141 {
00142 sensor_msgs::PointCloud2 cloud_blob;
00143 PointCloud<PointXYZI> cloud;
00144
00145 cloud.width = 640;
00146 cloud.height = 480;
00147 cloud.points.resize (cloud.width * cloud.height);
00148 cloud.is_dense = true;
00149
00150 srand (time (NULL));
00151 size_t nr_p = cloud.points.size ();
00152
00153 for (size_t i = 0; i < nr_p; ++i)
00154 {
00155 cloud.points[i].x = 1024 * rand () / (RAND_MAX + 1.0);
00156 cloud.points[i].y = 1024 * rand () / (RAND_MAX + 1.0);
00157 cloud.points[i].z = 1024 * rand () / (RAND_MAX + 1.0);
00158 cloud.points[i].intensity = i;
00159 }
00160 PointXYZI first, last;
00161 first.x = cloud.points[0].x; first.y = cloud.points[0].y; first.z = cloud.points[0].z; first.intensity = cloud.points[0].intensity;
00162 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;
00163
00164
00165 EXPECT_EQ (first.x, cloud (0, 0).x);
00166 EXPECT_EQ (first.y, cloud (0, 0).y);
00167 EXPECT_EQ (first.z, cloud (0, 0).z);
00168 EXPECT_EQ (first.intensity, (float)0);
00169 EXPECT_EQ (last.x, cloud (cloud.width-1, cloud.height-1).x);
00170 EXPECT_EQ (last.y, cloud (cloud.width-1, cloud.height-1).y);
00171 EXPECT_EQ (last.z, cloud (cloud.width-1, cloud.height-1).z);
00172 EXPECT_EQ (last.intensity, nr_p - 1);
00173
00174
00175 std::vector<sensor_msgs::PointField> fields;
00176 pcl::getFields (cloud, fields);
00177 EXPECT_EQ (fields.size (), (size_t)4);
00178 int x_idx = pcl::getFieldIndex (cloud, "x", fields);
00179 EXPECT_EQ (x_idx, 0);
00180 EXPECT_EQ (fields[x_idx].offset, (uint32_t)0);
00181 EXPECT_EQ (fields[x_idx].name, "x");
00182 EXPECT_EQ (fields[x_idx].datatype, sensor_msgs::PointField::FLOAT32);
00183 EXPECT_EQ (fields[x_idx].count, (uint32_t)1);
00184
00185 int y_idx = pcl::getFieldIndex (cloud, "y", fields);
00186 EXPECT_EQ (y_idx, 1);
00187 EXPECT_EQ (fields[y_idx].offset, (uint32_t)4);
00188 EXPECT_EQ (fields[y_idx].name, "y");
00189 EXPECT_EQ (fields[y_idx].datatype, sensor_msgs::PointField::FLOAT32);
00190 EXPECT_EQ (fields[y_idx].count, (uint32_t)1);
00191
00192 int z_idx = pcl::getFieldIndex (cloud, "z", fields);
00193 EXPECT_EQ (z_idx, 2);
00194 EXPECT_EQ (fields[z_idx].offset, (uint32_t)8);
00195 EXPECT_EQ (fields[z_idx].name, "z");
00196 EXPECT_EQ (fields[z_idx].datatype, sensor_msgs::PointField::FLOAT32);
00197 EXPECT_EQ (fields[z_idx].count, (uint32_t)1);
00198
00199 int intensity_idx = pcl::getFieldIndex (cloud, "intensity", fields);
00200 EXPECT_EQ (intensity_idx, 3);
00201 EXPECT_EQ (fields[intensity_idx].offset, (uint32_t)16);
00202 EXPECT_EQ (fields[intensity_idx].name, "intensity");
00203 EXPECT_EQ (fields[intensity_idx].datatype, sensor_msgs::PointField::FLOAT32);
00204 EXPECT_EQ (fields[intensity_idx].count, (uint32_t)1);
00205
00206
00207 toROSMsg (cloud, cloud_blob);
00208
00209
00210 x_idx = pcl::getFieldIndex (cloud_blob, "x");
00211 EXPECT_EQ (x_idx, 0);
00212 EXPECT_EQ (cloud_blob.fields[x_idx].offset, (uint32_t)0);
00213 EXPECT_EQ (cloud_blob.fields[x_idx].name, "x");
00214 EXPECT_EQ (cloud_blob.fields[x_idx].datatype, sensor_msgs::PointField::FLOAT32);
00215 EXPECT_EQ (cloud_blob.fields[x_idx].count, (uint32_t)1);
00216 y_idx = pcl::getFieldIndex (cloud_blob, "y");
00217 EXPECT_EQ (y_idx, 1);
00218 EXPECT_EQ (cloud_blob.fields[y_idx].offset, (uint32_t)4);
00219 EXPECT_EQ (cloud_blob.fields[y_idx].name, "y");
00220 EXPECT_EQ (cloud_blob.fields[y_idx].datatype, sensor_msgs::PointField::FLOAT32);
00221 EXPECT_EQ (cloud_blob.fields[y_idx].count, (uint32_t)1);
00222 z_idx = pcl::getFieldIndex (cloud_blob, "z");
00223 EXPECT_EQ (z_idx, 2);
00224 EXPECT_EQ (cloud_blob.fields[z_idx].offset, (uint32_t)8);
00225 EXPECT_EQ (cloud_blob.fields[z_idx].name, "z");
00226 EXPECT_EQ (cloud_blob.fields[z_idx].datatype, sensor_msgs::PointField::FLOAT32);
00227 EXPECT_EQ (cloud_blob.fields[z_idx].count, (uint32_t)1);
00228 intensity_idx = pcl::getFieldIndex (cloud_blob, "intensity");
00229 EXPECT_EQ (intensity_idx, 3);
00230
00231 EXPECT_EQ (cloud_blob.fields[intensity_idx].offset, (uint32_t)16);
00232 EXPECT_EQ (cloud_blob.fields[intensity_idx].name, "intensity");
00233 EXPECT_EQ (cloud_blob.fields[intensity_idx].datatype, sensor_msgs::PointField::FLOAT32);
00234 EXPECT_EQ (cloud_blob.fields[intensity_idx].count, (uint32_t)1);
00235
00236 fromROSMsg (cloud_blob, cloud);
00237 for (size_t i = 0; i < nr_p; ++i)
00238 EXPECT_EQ (cloud.points[i].intensity, i);
00239
00240 EXPECT_EQ ((uint32_t)cloud_blob.width, cloud.width);
00241 EXPECT_EQ ((uint32_t)cloud_blob.height, cloud.height);
00242 EXPECT_EQ ((bool)cloud_blob.is_dense, cloud.is_dense);
00243
00244
00245 EXPECT_EQ ((size_t)cloud_blob.data.size (),
00246 cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));
00247
00248
00249 PCDWriter w;
00250 int res = w.writeASCII ("/tmp/test_pcl_io.pcd", cloud_blob, Eigen::Vector4f::Zero (), Eigen::Quaternionf::Identity (), 10);
00251 EXPECT_EQ ((int)res, 0);
00252
00253
00254 res = loadPCDFile ("/tmp/test_pcl_io.pcd", cloud_blob);
00255 EXPECT_NE ((int)res, -1);
00256 EXPECT_EQ ((uint32_t)cloud_blob.width, cloud.width);
00257 EXPECT_EQ ((uint32_t)cloud_blob.height, cloud.height);
00258 EXPECT_EQ ((bool)cloud_blob.is_dense, cloud.is_dense);
00259 EXPECT_EQ ((size_t)cloud_blob.data.size () * 2,
00260 cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));
00261
00262
00263 fromROSMsg (cloud_blob, cloud);
00264
00265 EXPECT_EQ ((uint32_t)cloud.width, cloud_blob.width);
00266 EXPECT_EQ ((uint32_t)cloud.height, cloud_blob.height);
00267 EXPECT_EQ ((int)cloud.is_dense, cloud_blob.is_dense);
00268 EXPECT_EQ ((size_t)cloud.points.size (), nr_p);
00269
00270 EXPECT_NEAR ((float)cloud.points[0].x, first.x, 1e-5);
00271 EXPECT_NEAR ((float)cloud.points[0].y, first.y, 1e-5);
00272 EXPECT_NEAR ((float)cloud.points[0].z, first.z, 1e-5);
00273 EXPECT_NEAR ((uint32_t)cloud.points[0].intensity, first.intensity, 1e-5);
00274
00275 EXPECT_NEAR ((float)cloud.points[nr_p - 1].x, last.x, 1e-5);
00276 EXPECT_NEAR ((float)cloud.points[nr_p - 1].y, last.y, 1e-5);
00277 EXPECT_NEAR ((float)cloud.points[nr_p - 1].z, last.z, 1e-5);
00278 EXPECT_NEAR ((uint32_t)cloud.points[nr_p - 1].intensity, last.intensity, 1e-5);
00279
00280
00281 res = savePCDFile ("/tmp/test_pcl_io.pcd", cloud_blob, Eigen::Vector4f::Zero (), Eigen::Quaternionf::Identity (), true);
00282 EXPECT_EQ ((int)res, 0);
00283
00284
00285 res = loadPCDFile ("/tmp/test_pcl_io.pcd", cloud_blob);
00286 EXPECT_NE ((int)res, -1);
00287 EXPECT_EQ ((uint32_t)cloud_blob.width, cloud.width);
00288 EXPECT_EQ ((uint32_t)cloud_blob.height, cloud.height);
00289 EXPECT_EQ ((bool)cloud_blob.is_dense, false);
00290 EXPECT_EQ ((size_t)cloud_blob.data.size () * 2,
00291 cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));
00292
00293
00294 fromROSMsg (cloud_blob, cloud);
00295
00296 EXPECT_EQ ((uint32_t)cloud.width, cloud_blob.width);
00297 EXPECT_EQ ((uint32_t)cloud.height, cloud_blob.height);
00298 EXPECT_EQ ((int)cloud.is_dense, cloud_blob.is_dense);
00299 EXPECT_EQ ((size_t)cloud.points.size (), nr_p);
00300
00301 EXPECT_NEAR ((float)cloud.points[0].x, first.x, 1e-5);
00302 EXPECT_NEAR ((float)cloud.points[0].y, first.y, 1e-5);
00303 EXPECT_NEAR ((float)cloud.points[0].z, first.z, 1e-5);
00304 EXPECT_NEAR ((uint32_t)cloud.points[0].intensity, first.intensity, 1e-5);
00305
00306 EXPECT_NEAR ((float)cloud.points[nr_p - 1].x, last.x, 1e-5);
00307 EXPECT_NEAR ((float)cloud.points[nr_p - 1].y, last.y, 1e-5);
00308 EXPECT_NEAR ((float)cloud.points[nr_p - 1].z, last.z, 1e-5);
00309 EXPECT_NEAR ((uint32_t)cloud.points[nr_p - 1].intensity, last.intensity, 1e-5);
00310 }
00311
00313 TEST (PCL, PCDReaderWriter)
00314 {
00315 sensor_msgs::PointCloud2 cloud_blob;
00316 PointCloud<PointXYZI> cloud;
00317
00318 cloud.width = 640;
00319 cloud.height = 480;
00320 cloud.points.resize (cloud.width * cloud.height);
00321 cloud.is_dense = true;
00322
00323 srand (time (NULL));
00324 size_t nr_p = cloud.points.size ();
00325
00326 for (size_t i = 0; i < nr_p; ++i)
00327 {
00328 cloud.points[i].x = 1024 * rand () / (RAND_MAX + 1.0);
00329 cloud.points[i].y = 1024 * rand () / (RAND_MAX + 1.0);
00330 cloud.points[i].z = 1024 * rand () / (RAND_MAX + 1.0);
00331 cloud.points[i].intensity = i;
00332 }
00333 PointXYZI first, last;
00334 first.x = cloud.points[0].x; first.y = cloud.points[0].y; first.z = cloud.points[0].z; first.intensity = cloud.points[0].intensity;
00335 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;
00336
00337
00338 toROSMsg (cloud, cloud_blob);
00339
00340 EXPECT_EQ ((uint32_t)cloud_blob.width, cloud.width);
00341 EXPECT_EQ ((uint32_t)cloud_blob.height, cloud.height);
00342 EXPECT_EQ ((bool)cloud_blob.is_dense, cloud.is_dense);
00343
00344
00345 EXPECT_EQ ((size_t)cloud_blob.data.size (),
00346 cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));
00347
00348 PCDWriter writer;
00349 writer.write ("/tmp/test_pcl_io.pcd", cloud_blob, Eigen::Vector4f::Zero (), Eigen::Quaternionf::Identity (), true);
00350
00351 PCDReader reader;
00352 reader.read ("/tmp/test_pcl_io.pcd", cloud_blob);
00353 EXPECT_EQ ((uint32_t)cloud_blob.width, cloud.width);
00354 EXPECT_EQ ((uint32_t)cloud_blob.height, cloud.height);
00355 EXPECT_EQ ((bool)cloud_blob.is_dense, false);
00356
00357
00358 EXPECT_EQ ((size_t)cloud_blob.data.size (),
00359 cloud_blob.width * cloud_blob.height * sizeof (PointXYZI));
00360
00361
00362 fromROSMsg (cloud_blob, cloud);
00363
00364 EXPECT_EQ ((uint32_t)cloud.width, cloud_blob.width);
00365 EXPECT_EQ ((uint32_t)cloud.height, cloud_blob.height);
00366 EXPECT_EQ ((int)cloud.is_dense, cloud_blob.is_dense);
00367 EXPECT_EQ ((size_t)cloud.points.size (), nr_p);
00368
00369 EXPECT_NEAR ((float)cloud.points[0].x, first.x, 1e-5);
00370 EXPECT_NEAR ((float)cloud.points[0].y, first.y, 1e-5);
00371 EXPECT_NEAR ((float)cloud.points[0].z, first.z, 1e-5);
00372 EXPECT_NEAR ((uint32_t)cloud.points[0].intensity, first.intensity, 1e-5);
00373
00374 EXPECT_NEAR ((float)cloud.points[nr_p - 1].x, last.x, 1e-5);
00375 EXPECT_NEAR ((float)cloud.points[nr_p - 1].y, last.y, 1e-5);
00376 EXPECT_NEAR ((float)cloud.points[nr_p - 1].z, last.z, 1e-5);
00377 EXPECT_NEAR ((uint32_t)cloud.points[nr_p - 1].intensity, last.intensity, 1e-5);
00378 }
00379
00380 struct PointXYZFPFH33
00381 {
00382 float x, y, z;
00383 float histogram[33];
00384 };
00385 POINT_CLOUD_REGISTER_POINT_STRUCT (PointXYZFPFH33,
00386 (float, x, x) (float, y, y) (float, z, z)
00387 (float[33], histogram, fpfh));
00388
00389 inline std::ostream& operator << (std::ostream& os, const PointXYZFPFH33& p)
00390 {
00391 os << "(" << p.x << "," << p.y << "," << p.z << ")";
00392 for (int i = 0; i < 33; ++i)
00393 os << (i == 0 ? "(" :"") << p.histogram[i] << (i < 32 ? ", " : ")");
00394 return os;
00395 }
00396
00398 TEST (PCL, ExtendedIO)
00399 {
00400 PointCloud<PointXYZFPFH33> cloud;
00401 cloud.points.resize (2);
00402
00403 cloud.points[0].x = cloud.points[0].y = cloud.points[0].z = 1;
00404 cloud.points[1].x = cloud.points[1].y = cloud.points[1].z = 2;
00405 for (int i = 0; i < 33; ++i)
00406 {
00407 cloud.points[0].histogram[i] = i;
00408 cloud.points[1].histogram[i] = 33 - i;
00409 }
00410
00411 savePCDFile ("/tmp/v.pcd", cloud);
00412 cloud.points.clear ();
00413 loadPCDFile ("/tmp/v.pcd", cloud);
00414
00415 EXPECT_EQ ((int)cloud.width, 2);
00416 EXPECT_EQ ((int)cloud.height, 1);
00417 EXPECT_EQ (cloud.is_dense, true);
00418 EXPECT_EQ ((int)cloud.points.size (), 2);
00419
00420 EXPECT_EQ (cloud.points[0].x, 1); EXPECT_EQ (cloud.points[0].y, 1); EXPECT_EQ (cloud.points[0].z, 1);
00421 EXPECT_EQ (cloud.points[1].x, 2); EXPECT_EQ (cloud.points[1].y, 2); EXPECT_EQ (cloud.points[1].z, 2);
00422 for (int i = 0; i < 33; ++i)
00423 {
00424 EXPECT_EQ (cloud.points[0].histogram[i], i);
00425 EXPECT_EQ (cloud.points[1].histogram[i], 33-i);
00426 }
00427 }
00428
00430 TEST (PCL, EigenConversions)
00431 {
00432 PointCloud<PointXYZ> cloud;
00433 cloud.points.resize (5);
00434
00435 for (size_t i = 0; i < cloud.points.size (); ++i)
00436 cloud.points[i].x = cloud.points[i].y = cloud.points[i].z = i;
00437
00438 sensor_msgs::PointCloud2 blob;
00439 toROSMsg (cloud, blob);
00440
00441 Eigen::MatrixXf mat;
00442 getPointCloudAsEigen (blob, mat);
00443 EXPECT_EQ (mat.cols (), (int)cloud.points.size ());
00444 EXPECT_EQ (mat.rows (), 4);
00445
00446 for (size_t i = 0; i < cloud.points.size (); ++i)
00447 {
00448 EXPECT_EQ (mat (0, i), cloud.points[i].x);
00449 EXPECT_EQ (mat (1, i), cloud.points[i].y);
00450 EXPECT_EQ (mat (2, i), cloud.points[i].z);
00451 EXPECT_EQ (mat (3, i), 1);
00452 }
00453
00454 getEigenAsPointCloud (mat, blob);
00455 fromROSMsg (blob, cloud);
00456 for (size_t i = 0; i < cloud.points.size (); ++i)
00457 {
00458 EXPECT_EQ (cloud.points[i].x, i);
00459 EXPECT_EQ (cloud.points[i].y, i);
00460 EXPECT_EQ (cloud.points[i].z, i);
00461 }
00462
00463 getPointCloudAsEigen (blob, mat);
00464 EXPECT_EQ (mat.cols (), (int)cloud.points.size ());
00465 EXPECT_EQ (mat.rows (), 4);
00466
00467 for (size_t i = 0; i < cloud.points.size (); ++i)
00468 {
00469 EXPECT_EQ (mat (0, i), cloud.points[i].x);
00470 EXPECT_EQ (mat (1, i), cloud.points[i].y);
00471 EXPECT_EQ (mat (2, i), cloud.points[i].z);
00472 EXPECT_EQ (mat (3, i), 1);
00473 }
00474 }
00475
00476
00477 int
00478 main (int argc, char** argv)
00479 {
00480 testing::InitGoogleTest (&argc, argv);
00481 return (RUN_ALL_TESTS ());
00482 }
00483