system.cpp
Go to the documentation of this file.
00001 // Copyright (C) 2018, 2019 Kevin Hallenbeck, Joshua Whitley
00002 // All rights reserved.
00003 //
00004 // Software License Agreement (BSD License 2.0)
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions
00008 // are met:
00009 //
00010 //  * Redistributions of source code must retain the above copyright
00011 //    notice, this list of conditions and the following disclaimer.
00012 //  * Redistributions in binary form must reproduce the above
00013 //    copyright notice, this list of conditions and the following
00014 //    disclaimer in the documentation and/or other materials provided
00015 //    with the distribution.
00016 //  * Neither the name of {copyright_holder} nor the names of its
00017 //    contributors may be used to endorse or promote products derived
00018 //    from this software without specific prior written permission.
00019 //
00020 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 // POSSIBILITY OF SUCH DAMAGE.
00032 
00033 #include <gtest/gtest.h>
00034 
00035 #include <ros/ros.h>
00036 #include <sensor_msgs/PointCloud2.h>
00037 #include <sensor_msgs/LaserScan.h>
00038 
00039 #include <cstdlib>
00040 #include <algorithm>
00041 #include <vector>
00042 
00043 // Define our own PointCloud type for easy use
00044 typedef struct
00045 {
00046   float x;  // x
00047   float y;  // y
00048   float z;  // z
00049   float i;  // intensity
00050   uint16_t r;  // ring
00051 }
00052 Point;
00053 
00054 typedef struct
00055 {
00056   std_msgs::Header header;
00057   std::vector<Point> points;
00058 }
00059 PointCloud;
00060 
00061 // Global variables
00062 ros::Publisher g_pub;
00063 ros::Subscriber g_sub;
00064 sensor_msgs::LaserScan g_scan;
00065 volatile bool g_scan_new = false;
00066 
00067 // Convert WallTime to Time
00068 static inline ros::Time rosTime(const ros::WallTime &stamp)
00069 {
00070   return ros::Time(stamp.sec, stamp.nsec);
00071 }
00072 
00073 // Subscriber receive callback
00074 void recv(const sensor_msgs::LaserScanConstPtr& msg)
00075 {
00076   g_scan = *msg;
00077   g_scan_new = true;
00078 }
00079 
00080 // Wait for incoming LaserScan message
00081 bool waitForScan(ros::WallDuration dur)
00082 {
00083   const ros::WallTime start = ros::WallTime::now();
00084 
00085   while (!g_scan_new)
00086   {
00087     if ((ros::WallTime::now() - start) > dur)
00088     {
00089       return false;
00090     }
00091 
00092     ros::WallDuration(0.001).sleep();
00093     ros::spinOnce();
00094   }
00095 
00096   return true;
00097 }
00098 
00099 // Build and publish PointCloud2 messages of various structures
00100 void publishXYZIR1(const PointCloud &cloud)
00101 {
00102   g_scan_new = false;
00103   const uint32_t POINT_STEP = 32;
00104   sensor_msgs::PointCloud2 msg;
00105   msg.header.frame_id = cloud.header.frame_id;
00106   msg.header.stamp = cloud.header.stamp;
00107   msg.fields.resize(5);
00108   msg.fields[0].name = "x";
00109   msg.fields[0].offset = 0;
00110   msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
00111   msg.fields[0].count = 1;
00112   msg.fields[1].name = "y";
00113   msg.fields[1].offset = 4;
00114   msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
00115   msg.fields[1].count = 1;
00116   msg.fields[2].name = "z";
00117   msg.fields[2].offset = 8;
00118   msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
00119   msg.fields[2].count = 1;
00120   msg.fields[3].name = "intensity";
00121   msg.fields[3].offset = 16;
00122   msg.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
00123   msg.fields[3].count = 1;
00124   msg.fields[4].name = "ring";
00125   msg.fields[4].offset = 20;
00126   msg.fields[4].datatype = sensor_msgs::PointField::UINT16;
00127   msg.fields[4].count = 1;
00128   msg.data.resize(std::max((size_t)1, cloud.points.size()) * POINT_STEP, 0x00);
00129   msg.point_step = POINT_STEP;
00130   msg.row_step = msg.data.size();
00131   msg.height = 1;
00132   msg.width = msg.row_step / POINT_STEP;
00133   msg.is_bigendian = false;
00134   msg.is_dense = true;
00135   uint8_t *ptr = msg.data.data();
00136 
00137   for (size_t i = 0; i < cloud.points.size(); i++)
00138   {
00139     *(reinterpret_cast<float*>(ptr +  0)) = cloud.points[i].x;
00140     *(reinterpret_cast<float*>(ptr +  4)) = cloud.points[i].y;
00141     *(reinterpret_cast<float*>(ptr +  8)) = cloud.points[i].z;
00142     *(reinterpret_cast<float*>(ptr + 16)) = cloud.points[i].i;
00143     *(reinterpret_cast<uint16_t*>(ptr + 20)) = cloud.points[i].r;
00144     ptr += POINT_STEP;
00145   }
00146 
00147   g_pub.publish(msg);
00148 }
00149 
00150 void publishXYZIR2(const PointCloud &cloud)
00151 {
00152   g_scan_new = false;
00153   const uint32_t POINT_STEP = 19;
00154   sensor_msgs::PointCloud2 msg;
00155   msg.header.frame_id = cloud.header.frame_id;
00156   msg.header.stamp = cloud.header.stamp;
00157   msg.fields.resize(5);
00158   msg.fields[0].name = "z";
00159   msg.fields[0].offset = 4;
00160   msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
00161   msg.fields[0].count = 1;
00162   msg.fields[1].name = "y";
00163   msg.fields[1].offset = 8;
00164   msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
00165   msg.fields[1].count = 1;
00166   msg.fields[2].name = "x";
00167   msg.fields[2].offset = 12;
00168   msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
00169   msg.fields[2].count = 1;
00170   msg.fields[3].name = "intensity";
00171   msg.fields[3].offset = 0;
00172   msg.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
00173   msg.fields[3].count = 1;
00174   msg.fields[4].name = "ring";
00175   msg.fields[4].offset = 16;
00176   msg.fields[4].datatype = sensor_msgs::PointField::UINT16;
00177   msg.fields[4].count = 1;
00178   msg.data.resize(std::max((size_t)1, cloud.points.size()) * POINT_STEP, 0x00);
00179   msg.point_step = POINT_STEP;
00180   msg.row_step = msg.data.size();
00181   msg.height = 1;
00182   msg.width = msg.row_step / POINT_STEP;
00183   msg.is_bigendian = false;
00184   msg.is_dense = true;
00185   uint8_t *ptr = msg.data.data();
00186 
00187   for (size_t i = 0; i < cloud.points.size(); i++)
00188   {
00189     *(reinterpret_cast<float*>(ptr +  0)) = cloud.points[i].i;
00190     *(reinterpret_cast<float*>(ptr +  4)) = cloud.points[i].z;
00191     *(reinterpret_cast<float*>(ptr +  8)) = cloud.points[i].y;
00192     *(reinterpret_cast<float*>(ptr + 12)) = cloud.points[i].x;
00193     *(reinterpret_cast<uint16_t*>(ptr + 16)) = cloud.points[i].r;
00194     ptr += POINT_STEP;
00195   }
00196 
00197   g_pub.publish(msg);
00198 }
00199 
00200 void publishXYZR(const PointCloud &cloud)
00201 {
00202   g_scan_new = false;
00203   const uint32_t POINT_STEP = 15;
00204   sensor_msgs::PointCloud2 msg;
00205   msg.header.frame_id = cloud.header.frame_id;
00206   msg.header.stamp = cloud.header.stamp;
00207   msg.fields.resize(4);
00208   msg.fields[0].name = "x";
00209   msg.fields[0].offset = 0;
00210   msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
00211   msg.fields[0].count = 1;
00212   msg.fields[1].name = "y";
00213   msg.fields[1].offset = 4;
00214   msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
00215   msg.fields[1].count = 1;
00216   msg.fields[2].name = "z";
00217   msg.fields[2].offset = 8;
00218   msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
00219   msg.fields[2].count = 1;
00220   msg.fields[3].name = "ring";
00221   msg.fields[3].offset = 12;
00222   msg.fields[3].datatype = sensor_msgs::PointField::UINT16;
00223   msg.fields[3].count = 1;
00224   msg.data.resize(std::max((size_t)1, cloud.points.size()) * POINT_STEP, 0x00);
00225   msg.point_step = POINT_STEP;
00226   msg.row_step = msg.data.size();
00227   msg.height = 1;
00228   msg.width = msg.row_step / POINT_STEP;
00229   msg.is_bigendian = false;
00230   msg.is_dense = true;
00231   uint8_t *ptr = msg.data.data();
00232 
00233   for (size_t i = 0; i < cloud.points.size(); i++)
00234   {
00235     *(reinterpret_cast<float*>(ptr + 0)) = cloud.points[i].x;
00236     *(reinterpret_cast<float*>(ptr + 4)) = cloud.points[i].y;
00237     *(reinterpret_cast<float*>(ptr + 8)) = cloud.points[i].z;
00238     *(reinterpret_cast<uint16_t*>(ptr + 12)) = cloud.points[i].r;
00239     ptr += POINT_STEP;
00240   }
00241 
00242   g_pub.publish(msg);
00243 }
00244 
00245 void publishR(const PointCloud &cloud)
00246 {
00247   g_scan_new = false;
00248   const uint32_t POINT_STEP = 2;
00249   sensor_msgs::PointCloud2 msg;
00250   msg.header.stamp = rosTime(ros::WallTime::now());
00251   msg.fields.resize(1);
00252   msg.fields[0].name = "ring";
00253   msg.fields[0].offset = 0;
00254   msg.fields[0].datatype = sensor_msgs::PointField::UINT16;
00255   msg.fields[0].count = 1;
00256   msg.data.resize(std::max((size_t)1, cloud.points.size()) * POINT_STEP, 0x00);
00257   msg.point_step = POINT_STEP;
00258   msg.row_step = msg.data.size();
00259   msg.height = 1;
00260   msg.width = msg.row_step / POINT_STEP;
00261   uint8_t *ptr = msg.data.data();
00262 
00263   for (size_t i = 0; i < cloud.points.size(); i++)
00264   {
00265     *(reinterpret_cast<uint16_t*>(ptr + 0)) = cloud.points[i].r;
00266     ptr += POINT_STEP;
00267   }
00268 
00269   g_pub.publish(msg);
00270 }
00271 
00272 void publishXYZR32(const PointCloud &cloud)
00273 {
00274   g_scan_new = false;
00275   const uint32_t POINT_STEP = 16;
00276   sensor_msgs::PointCloud2 msg;
00277   msg.header.frame_id = cloud.header.frame_id;
00278   msg.header.stamp = cloud.header.stamp;
00279   msg.fields.resize(4);
00280   msg.fields[0].name = "x";
00281   msg.fields[0].offset = 0;
00282   msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
00283   msg.fields[0].count = 1;
00284   msg.fields[1].name = "y";
00285   msg.fields[1].offset = 4;
00286   msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
00287   msg.fields[1].count = 1;
00288   msg.fields[2].name = "z";
00289   msg.fields[2].offset = 8;
00290   msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
00291   msg.fields[2].count = 1;
00292   msg.fields[3].name = "ring";
00293   msg.fields[3].offset = 12;
00294   msg.fields[3].datatype = sensor_msgs::PointField::UINT32;
00295   msg.fields[3].count = 1;
00296   msg.data.resize(std::max((size_t)1, cloud.points.size()) * POINT_STEP, 0x00);
00297   msg.point_step = POINT_STEP;
00298   msg.row_step = msg.data.size();
00299   msg.height = 1;
00300   msg.width = msg.row_step / POINT_STEP;
00301   msg.is_bigendian = false;
00302   msg.is_dense = true;
00303   uint8_t *ptr = msg.data.data();
00304 
00305   for (size_t i = 0; i < cloud.points.size(); i++)
00306   {
00307     *(reinterpret_cast<float*>(ptr + 0)) = cloud.points[i].x;
00308     *(reinterpret_cast<float*>(ptr + 4)) = cloud.points[i].y;
00309     *(reinterpret_cast<float*>(ptr + 8)) = cloud.points[i].z;
00310     *(reinterpret_cast<uint32_t*>(ptr + 12)) = cloud.points[i].r;
00311     ptr += POINT_STEP;
00312   }
00313 
00314   g_pub.publish(msg);
00315 }
00316 
00317 void publishXYZ(const PointCloud &cloud)
00318 {
00319   g_scan_new = false;
00320   const uint32_t POINT_STEP = 12;
00321   sensor_msgs::PointCloud2 msg;
00322   msg.header.stamp = rosTime(ros::WallTime::now());
00323   msg.fields.resize(3);
00324   msg.fields[0].name = "x";
00325   msg.fields[0].offset = 0;
00326   msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
00327   msg.fields[0].count = 1;
00328   msg.fields[1].name = "y";
00329   msg.fields[1].offset = 4;
00330   msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
00331   msg.fields[1].count = 1;
00332   msg.fields[2].name = "z";
00333   msg.fields[2].offset = 8;
00334   msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
00335   msg.fields[2].count = 1;
00336   msg.data.resize(std::max((size_t)1, cloud.points.size()) * POINT_STEP, 0x00);
00337   msg.point_step = POINT_STEP;
00338   msg.row_step = msg.data.size();
00339   msg.height = 1;
00340   msg.width = msg.row_step / POINT_STEP;
00341   uint8_t *ptr = msg.data.data();
00342 
00343   for (size_t i = 0; i < cloud.points.size(); i++)
00344   {
00345     *(reinterpret_cast<float*>(ptr + 0)) = cloud.points[i].x;
00346     *(reinterpret_cast<float*>(ptr + 4)) = cloud.points[i].y;
00347     *(reinterpret_cast<float*>(ptr + 8)) = cloud.points[i].z;
00348     ptr += POINT_STEP;
00349   }
00350 
00351   g_pub.publish(msg);
00352 }
00353 
00354 void publishNone()
00355 {
00356   g_scan_new = false;
00357   const uint32_t POINT_STEP = 16;
00358   sensor_msgs::PointCloud2 msg;
00359   msg.header.stamp = rosTime(ros::WallTime::now());
00360   msg.data.resize(1 * POINT_STEP, 0x00);
00361   msg.point_step = POINT_STEP;
00362   msg.row_step = msg.data.size();
00363   msg.height = 1;
00364   msg.width = msg.row_step / POINT_STEP;
00365   g_pub.publish(msg);
00366 }
00367 
00368 // Find the index of the point in the PointCloud with the shortest 2d distance to the point (x,y)
00369 static inline float SQUARE(float x)
00370 {
00371   return x * x;
00372 }
00373 
00374 size_t findClosestIndex(const PointCloud &cloud, uint16_t ring, float x, float y)
00375 {
00376   size_t index = SIZE_MAX;
00377   float delta = INFINITY;
00378 
00379   for (size_t i = 0; i < cloud.points.size(); i++)
00380   {
00381     if (cloud.points[i].r == ring)
00382     {
00383       float dist = SQUARE(x - cloud.points[i].x) + SQUARE(y - cloud.points[i].y);
00384 
00385       if (dist < delta)
00386       {
00387         delta = dist;
00388         index = i;
00389       }
00390     }
00391   }
00392 
00393   return index;
00394 }
00395 
00396 // Verify that all LaserScan header values are values are passed through, and other values are default
00397 void verifyScanEmpty(const PointCloud &cloud, bool intensity = true)
00398 {
00399   ASSERT_EQ(cloud.header.stamp, g_scan.header.stamp);
00400   EXPECT_EQ(cloud.header.frame_id, g_scan.header.frame_id);
00401 
00402   for (size_t i = 0; i < g_scan.ranges.size(); i++)
00403   {
00404     EXPECT_EQ(INFINITY, g_scan.ranges[i]);
00405   }
00406 
00407   if (!intensity)
00408   {
00409     EXPECT_EQ(0, g_scan.intensities.size());
00410   }
00411   else
00412   {
00413     EXPECT_EQ(g_scan.ranges.size(), g_scan.intensities.size());
00414 
00415     for (size_t i = 0; i < g_scan.intensities.size(); i++)
00416     {
00417       EXPECT_EQ(0.0, g_scan.intensities[i]);
00418     }
00419   }
00420 }
00421 
00422 // Verify that every PointCloud point made it to the LaserScan and other values are default
00423 void verifyScanSparse(const PointCloud &cloud, uint16_t ring, uint16_t ring_count, bool intensity = true)
00424 {
00425   ASSERT_EQ(cloud.header.stamp, g_scan.header.stamp);
00426   EXPECT_EQ(cloud.header.frame_id, g_scan.header.frame_id);
00427   EXPECT_EQ(intensity ? g_scan.ranges.size() : 0, g_scan.intensities.size());
00428   size_t count = 0;
00429 
00430   for (size_t i = 0; i < g_scan.ranges.size(); i++)
00431   {
00432     double r = g_scan.ranges[i];
00433 
00434     if (std::isfinite(r))
00435     {
00436       float a = g_scan.angle_min + i * g_scan.angle_increment;
00437       float x = g_scan.ranges[i] * cosf(a);
00438       float y = g_scan.ranges[i] * sinf(a);
00439       float e = g_scan.ranges[i] * g_scan.angle_increment + static_cast<float>(1e-3);  // allowable error
00440       size_t index = findClosestIndex(cloud, ring, x, y);
00441 
00442       if (index < cloud.points.size())
00443       {
00444         count++;
00445         EXPECT_NEAR(cloud.points[index].x, x, e);
00446         EXPECT_NEAR(cloud.points[index].y, y, e);
00447 
00448         if (i < g_scan.intensities.size())
00449         {
00450           EXPECT_EQ(cloud.points[index].i, g_scan.intensities[i]);
00451         }
00452       }
00453       else
00454       {
00455         EXPECT_TRUE(false);  // LaserScan point not found in PointCloud
00456       }
00457     }
00458     else
00459     {
00460       EXPECT_EQ(INFINITY, r);
00461     }
00462   }
00463 
00464   if (ring_count > 0)
00465   {
00466     EXPECT_EQ(cloud.points.size() / ring_count, count);  // Make sure that all points were converted to ranges
00467   }
00468 }
00469 
00470 // Verify that every LaserScan point is not default, and every point came from the PointCloud
00471 void verifyScanDense(const PointCloud &cloud, uint16_t ring, bool intensity = true)
00472 {
00473   ASSERT_EQ(cloud.header.stamp, g_scan.header.stamp);
00474   EXPECT_EQ(cloud.header.frame_id, g_scan.header.frame_id);
00475   EXPECT_EQ(intensity ? g_scan.ranges.size() : 0, g_scan.intensities.size());
00476 
00477   for (size_t i = 0; i < g_scan.ranges.size(); i++)
00478   {
00479     double r = g_scan.ranges[i];
00480 
00481     if (std::isfinite(r))
00482     {
00483       float a = g_scan.angle_min + i * g_scan.angle_increment;
00484       float x = g_scan.ranges[i] * cosf(a);
00485       float y = g_scan.ranges[i] * sinf(a);
00486       float e = g_scan.ranges[i] * g_scan.angle_increment + static_cast<float>(1e-3);  // allowable error
00487       size_t index = findClosestIndex(cloud, ring, x, y);
00488 
00489       if (index < cloud.points.size())
00490       {
00491         EXPECT_NEAR(cloud.points[index].x, x, e);
00492         EXPECT_NEAR(cloud.points[index].y, y, e);
00493         // @TODO: Test for matching intensity
00494       }
00495       else
00496       {
00497         EXPECT_TRUE(false);  // LaserScan point not found in PointCloud
00498       }
00499     }
00500     else
00501     {
00502       EXPECT_TRUE(false);  // Dense PointCloud should populate every range in LaserScan
00503     }
00504   }
00505 }
00506 
00507 // Verify that no LaserScan is generated when the PointCloud2 message is missing required fields
00508 TEST(System, missing_fields)
00509 {
00510   // Make sure system is connected
00511   ASSERT_EQ(1, g_sub.getNumPublishers());
00512   ASSERT_EQ(1, g_pub.getNumSubscribers());
00513 
00514   // Create PointCloud with 16 rings
00515   PointCloud cloud;
00516   cloud.points.resize(1);
00517   cloud.points[0].x = 0.0;
00518   cloud.points[0].y = 0.0;
00519   cloud.points[0].z = 0.0;
00520   cloud.points[0].i = 0.0;
00521   cloud.points[0].r = 15;
00522 
00523   // Verify no LaserScan when PointCloud2 fields are empty
00524   publishNone();
00525   EXPECT_FALSE(waitForScan(ros::WallDuration(0.5)));
00526 
00527   // Verify no LaserScan when PointCloud2 fields are missing 'ring'
00528   publishXYZ(cloud);
00529   EXPECT_FALSE(waitForScan(ros::WallDuration(0.5)));
00530 
00531   // Verify no LaserScan when PointCloud2 field 'ring' is the incorrect type
00532   publishXYZR32(cloud);
00533   EXPECT_FALSE(waitForScan(ros::WallDuration(0.5)));
00534 
00535 
00536   // Verify no LaserScan when PointCloud2 fields are missing 'x' and 'y'
00537   publishR(cloud);
00538   EXPECT_FALSE(waitForScan(ros::WallDuration(0.5)));
00539 
00540   // Verify that the node hasn't crashed by sending normal PointCloud2 fields
00541   cloud.header.stamp = rosTime(ros::WallTime::now());
00542   publishXYZIR1(cloud);
00543   ASSERT_TRUE(waitForScan(ros::WallDuration(1.0)));
00544   ASSERT_EQ(cloud.header.stamp, g_scan.header.stamp);
00545 }
00546 
00547 // Verify that non-point fields are passed through unmodified
00548 TEST(System, empty_data)
00549 {
00550   // Make sure system is connected
00551   ASSERT_EQ(1, g_sub.getNumPublishers());
00552   ASSERT_EQ(1, g_pub.getNumSubscribers());
00553 
00554   // Create PointCloud with 16 rings
00555   PointCloud cloud;
00556   cloud.header.frame_id = "abcdefghijklmnopqrstuvwxyz";
00557   cloud.points.resize(1);
00558   cloud.points[0].x = 0.0;
00559   cloud.points[0].y = 0.0;
00560   cloud.points[0].z = 0.0;
00561   cloud.points[0].i = 0.0;
00562   cloud.points[0].r = 15;
00563 
00564   // Verify that all three PointCloud2 types create proper default values
00565 
00566   // PointXYZIR (expected format)
00567   cloud.header.stamp = rosTime(ros::WallTime::now());
00568   publishXYZIR1(cloud);
00569   ASSERT_TRUE(waitForScan(ros::WallDuration(1.0)));
00570   verifyScanEmpty(cloud, true);
00571 
00572   // PointXYZIR (unexpected format with intensity)
00573   cloud.header.stamp = rosTime(ros::WallTime::now());
00574   publishXYZIR2(cloud);
00575   ASSERT_TRUE(waitForScan(ros::WallDuration(1.0)));
00576   verifyScanEmpty(cloud, true);
00577 
00578   // PointXYZR (unexpected format without intensity)
00579   cloud.header.stamp = rosTime(ros::WallTime::now());
00580   publishXYZR(cloud);
00581   ASSERT_TRUE(waitForScan(ros::WallDuration(1.0)));
00582   verifyScanEmpty(cloud, false);
00583 }
00584 
00585 // Verify that every piece of a small amount of random data is passed through
00586 TEST(System, random_data_sparse)
00587 {
00588   // Make sure system is connected
00589   ASSERT_EQ(1, g_sub.getNumPublishers());
00590   ASSERT_EQ(1, g_pub.getNumSubscribers());
00591 
00592   // Create PointCloud with sparse random data
00593   PointCloud cloud;
00594   cloud.header.frame_id = "velodyne";
00595   const size_t RANGE_COUNT = 100;
00596   const size_t RING_COUNT = 16;
00597   const double RANGE_MAX = 20.0;
00598   const double INTENSITY_MAX = 1.0;
00599 
00600   for (size_t i = 0; i < RANGE_COUNT; i++)
00601   {
00602     double angle_y = i * 1.99 * M_PI / RANGE_COUNT;  // yaw
00603 
00604     for (size_t j = 0; j < RING_COUNT; j++)
00605     {
00606       double angle_p = j * 0.2 * M_PI / RING_COUNT - 0.1 * M_PI;  // pitch
00607       double range = std::rand() * (RANGE_MAX / RAND_MAX);
00608       Point point;
00609       point.x = range * cos(angle_p) * cos(angle_y);
00610       point.y = range * cos(angle_p) * sin(angle_y);
00611       point.z = range * sin(angle_p);
00612       point.i = std::rand() * (INTENSITY_MAX / RAND_MAX);
00613       point.r = j;
00614       cloud.points.push_back(point);
00615     }
00616   }
00617 
00618   // Verify that all three PointCloud2 types are handled correctly
00619 
00620   // PointXYZIR (expected format)
00621   cloud.header.stamp = rosTime(ros::WallTime::now());
00622   publishXYZIR1(cloud);
00623   ASSERT_TRUE(waitForScan(ros::WallDuration(1.0)));
00624   verifyScanSparse(cloud, 8, RING_COUNT, true);
00625 
00626   // PointXYZIR (unexpected format with intensity)
00627   cloud.header.stamp = rosTime(ros::WallTime::now());
00628   publishXYZIR2(cloud);
00629   ASSERT_TRUE(waitForScan(ros::WallDuration(1.0)));
00630   verifyScanSparse(cloud, 8, RING_COUNT, true);
00631 
00632   // PointXYZR (unexpected format without intensity)
00633   cloud.header.stamp = rosTime(ros::WallTime::now());
00634   publishXYZR(cloud);
00635   ASSERT_TRUE(waitForScan(ros::WallDuration(1.0)));
00636   verifyScanSparse(cloud, 8, RING_COUNT, false);
00637 }
00638 
00639 // Verify that every LaserScan range is valid when given an extra large amount of random data
00640 TEST(System, random_data_dense)
00641 {
00642   // Make sure system is connected
00643   ASSERT_EQ(1, g_sub.getNumPublishers());
00644   ASSERT_EQ(1, g_pub.getNumSubscribers());
00645 
00646   // Create PointCloud with dense random data
00647   PointCloud cloud;
00648   cloud.header.frame_id = "velodyne";
00649   const size_t RANGE_COUNT = 2500;
00650   const size_t RING_COUNT = 16;
00651   const double RANGE_MAX = 20.0;
00652   const double INTENSITY_MAX = 1.0;
00653 
00654   for (size_t i = 0; i < RANGE_COUNT; i++)
00655   {
00656     double angle_y = i * 2.0 * M_PI / RANGE_COUNT;  // yaw
00657 
00658     for (size_t j = 0; j < RING_COUNT; j++)
00659     {
00660       double angle_p = j * 0.2 * M_PI / RING_COUNT - 0.1 * M_PI;  // pitch
00661       double range = std::rand() * (RANGE_MAX / RAND_MAX);
00662       Point point;
00663       point.x = range * cos(angle_p) * cos(angle_y);
00664       point.y = range * cos(angle_p) * sin(angle_y);
00665       point.z = range * sin(angle_p);
00666       point.i = std::rand() * (INTENSITY_MAX / RAND_MAX);
00667       point.r = j;
00668       cloud.points.push_back(point);
00669     }
00670   }
00671 
00672   // Verify that all three PointCloud2 types are handled correctly
00673 
00674   // PointXYZIR (expected format)
00675   cloud.header.stamp = rosTime(ros::WallTime::now());
00676   publishXYZIR1(cloud);
00677   ASSERT_TRUE(waitForScan(ros::WallDuration(1.0)));
00678   verifyScanDense(cloud, 8, true);
00679 
00680   // PointXYZIR (unexpected format with intensity)
00681   cloud.header.stamp = rosTime(ros::WallTime::now());
00682   publishXYZIR2(cloud);
00683   ASSERT_TRUE(waitForScan(ros::WallDuration(1.0)));
00684   verifyScanDense(cloud, 8, true);
00685 
00686   // PointXYZR (unexpected format without intensity)
00687   cloud.header.stamp = rosTime(ros::WallTime::now());
00688   publishXYZR(cloud);
00689   ASSERT_TRUE(waitForScan(ros::WallDuration(1.0)));
00690   verifyScanDense(cloud, 8, false);
00691 }
00692 
00693 int main(int argc, char **argv)
00694 {
00695   testing::InitGoogleTest(&argc, argv);
00696 
00697   // Initialize ROS
00698   ros::init(argc, argv, "test_lazy_subscriber");
00699   ros::NodeHandle nh;
00700 
00701   // Setup publisher and subscriber
00702   g_pub = nh.advertise<sensor_msgs::PointCloud2>("velodyne_points", 2);
00703   g_sub = nh.subscribe("scan", 2, recv);
00704 
00705   // Wait for other nodes to startup
00706   ros::WallDuration(1.0).sleep();
00707   ros::spinOnce();
00708 
00709   // Run all the tests that were declared with TEST()
00710   return RUN_ALL_TESTS();
00711 }


velodyne_laserscan
Author(s): Micho Radovnikovich, Kevin Hallenbeck
autogenerated on Wed Jul 3 2019 19:32:17