voxel_grid.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: voxel_grid.cpp 6144 2012-07-04 22:06:28Z rusu $
00035  *
00036  */
00037 
00038 #include <iostream>
00039 #include <pcl/impl/instantiate.hpp>
00040 #include <pcl/point_types.h>
00041 #include <pcl/common/io.h>
00042 #include <pcl/filters/voxel_grid.h>
00043 #include <pcl/filters/impl/voxel_grid.hpp>
00044 
00046 void
00047 pcl::getMinMax3D (const sensor_msgs::PointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
00048                   Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt)
00049 {
00050   // @todo fix this
00051   if (cloud->fields[x_idx].datatype != sensor_msgs::PointField::FLOAT32 || 
00052       cloud->fields[y_idx].datatype != sensor_msgs::PointField::FLOAT32 ||
00053       cloud->fields[z_idx].datatype != sensor_msgs::PointField::FLOAT32)
00054   {
00055     PCL_ERROR ("[pcl::getMinMax3D] XYZ dimensions are not float type!\n");
00056     return;
00057   }
00058 
00059   Eigen::Array4f min_p, max_p;
00060   min_p.setConstant (FLT_MAX);
00061   max_p.setConstant (-FLT_MAX);
00062 
00063   int nr_points = cloud->width * cloud->height;
00064 
00065   Eigen::Array4f pt = Eigen::Array4f::Zero ();
00066   Eigen::Array4i xyz_offset (cloud->fields[x_idx].offset, cloud->fields[y_idx].offset, cloud->fields[z_idx].offset, 0);
00067 
00068   for (int cp = 0; cp < nr_points; ++cp)
00069   {
00070     // Unoptimized memcpys: assume fields x, y, z are in random order
00071     memcpy (&pt[0], &cloud->data[xyz_offset[0]], sizeof (float));
00072     memcpy (&pt[1], &cloud->data[xyz_offset[1]], sizeof (float));
00073     memcpy (&pt[2], &cloud->data[xyz_offset[2]], sizeof (float));
00074     // Check if the point is invalid
00075     if (!pcl_isfinite (pt[0]) || 
00076         !pcl_isfinite (pt[1]) || 
00077         !pcl_isfinite (pt[2]))
00078     {
00079       xyz_offset += cloud->point_step;
00080       continue;
00081     }
00082     xyz_offset += cloud->point_step;
00083     min_p = (min_p.min) (pt);
00084     max_p = (max_p.max) (pt);
00085   }
00086   min_pt = min_p;
00087   max_pt = max_p;
00088 }
00089 
00091 void
00092 pcl::getMinMax3D (const sensor_msgs::PointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx,
00093                   const std::string &distance_field_name, float min_distance, float max_distance,
00094                   Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative)
00095 {
00096   // @todo fix this
00097   if (cloud->fields[x_idx].datatype != sensor_msgs::PointField::FLOAT32 || 
00098       cloud->fields[y_idx].datatype != sensor_msgs::PointField::FLOAT32 ||
00099       cloud->fields[z_idx].datatype != sensor_msgs::PointField::FLOAT32)
00100   {
00101     PCL_ERROR ("[pcl::getMinMax3D] XYZ dimensions are not float type!\n");
00102     return;
00103   }
00104 
00105   Eigen::Array4f min_p, max_p;
00106   min_p.setConstant (FLT_MAX);
00107   max_p.setConstant (-FLT_MAX);
00108 
00109   // Get the distance field index
00110   int distance_idx = pcl::getFieldIndex (*cloud, distance_field_name);
00111 
00112   // @todo fix this
00113   if (cloud->fields[distance_idx].datatype != sensor_msgs::PointField::FLOAT32)
00114   {
00115     PCL_ERROR ("[pcl::getMinMax3D] Filtering dimensions is not float type!\n");
00116     return;
00117   }
00118 
00119   int nr_points = cloud->width * cloud->height;
00120 
00121   Eigen::Array4f pt = Eigen::Array4f::Zero ();
00122   Eigen::Array4i xyz_offset (cloud->fields[x_idx].offset,
00123                              cloud->fields[y_idx].offset,
00124                              cloud->fields[z_idx].offset,
00125                              0);
00126   float distance_value = 0;
00127   for (int cp = 0; cp < nr_points; ++cp)
00128   {
00129     int point_offset = cp * cloud->point_step;
00130 
00131     // Get the distance value
00132     memcpy (&distance_value, &cloud->data[point_offset + cloud->fields[distance_idx].offset], sizeof (float));
00133 
00134     if (limit_negative)
00135     {
00136       // Use a threshold for cutting out points which inside the interval
00137       if ((distance_value < max_distance) && (distance_value > min_distance))
00138       {
00139         xyz_offset += cloud->point_step;
00140         continue;
00141       }
00142     }
00143     else
00144     {
00145       // Use a threshold for cutting out points which are too close/far away
00146       if ((distance_value > max_distance) || (distance_value < min_distance))
00147       {
00148         xyz_offset += cloud->point_step;
00149         continue;
00150       }
00151     }
00152 
00153     // Unoptimized memcpys: assume fields x, y, z are in random order
00154     memcpy (&pt[0], &cloud->data[xyz_offset[0]], sizeof (float));
00155     memcpy (&pt[1], &cloud->data[xyz_offset[1]], sizeof (float));
00156     memcpy (&pt[2], &cloud->data[xyz_offset[2]], sizeof (float));
00157     // Check if the point is invalid
00158     if (!pcl_isfinite (pt[0]) || 
00159         !pcl_isfinite (pt[1]) || 
00160         !pcl_isfinite (pt[2]))
00161     {
00162       xyz_offset += cloud->point_step;
00163       continue;
00164     }
00165     xyz_offset += cloud->point_step;
00166     min_p = (min_p.min) (pt);
00167     max_p = (max_p.max) (pt);
00168   }
00169   min_pt = min_p;
00170   max_pt = max_p;
00171 }
00172 
00174 void
00175 pcl::VoxelGrid<sensor_msgs::PointCloud2>::applyFilter (PointCloud2 &output)
00176 {
00177   // If fields x/y/z are not present, we cannot downsample
00178   if (x_idx_ == -1 || y_idx_ == -1 || z_idx_ == -1)
00179   {
00180     PCL_ERROR ("[pcl::%s::applyFilter] Input dataset doesn't have x-y-z coordinates!\n", getClassName ().c_str ());
00181     output.width = output.height = 0;
00182     output.data.clear ();
00183     return;
00184   }
00185   int nr_points  = input_->width * input_->height;
00186 
00187   // Copy the header (and thus the frame_id) + allocate enough space for points
00188   output.height         = 1;                    // downsampling breaks the organized structure
00189   if (downsample_all_data_)
00190   {
00191     output.fields       = input_->fields;
00192     output.point_step   = input_->point_step;
00193   }
00194   else
00195   {
00196     output.fields.resize (4);
00197 
00198     output.fields[0] = input_->fields[x_idx_];
00199     output.fields[0].offset = 0;
00200 
00201     output.fields[1] = input_->fields[y_idx_];
00202     output.fields[1].offset = 4;
00203 
00204     output.fields[2] = input_->fields[z_idx_];
00205     output.fields[2].offset = 8;
00206 
00207     output.fields[3].name = "rgba";
00208     output.fields[3].offset = 12;
00209     output.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
00210 
00211     output.point_step = 16;
00212   }
00213   output.is_bigendian = input_->is_bigendian;
00214   output.row_step     = input_->row_step;
00215   output.is_dense     = true;                 // we filter out invalid points
00216 
00217   Eigen::Vector4f min_p, max_p;
00218   // Get the minimum and maximum dimensions
00219   if (!filter_field_name_.empty ()) // If we don't want to process the entire cloud...
00220     getMinMax3D (input_, x_idx_, y_idx_, z_idx_, filter_field_name_, 
00221                  static_cast<float> (filter_limit_min_), 
00222                  static_cast<float> (filter_limit_max_), min_p, max_p, filter_limit_negative_);
00223   else
00224     getMinMax3D (input_, x_idx_, y_idx_, z_idx_, min_p, max_p);
00225 
00226   // Compute the minimum and maximum bounding box values
00227   min_b_[0] = static_cast<int> (floor (min_p[0] * inverse_leaf_size_[0]));
00228   max_b_[0] = static_cast<int> (floor (max_p[0] * inverse_leaf_size_[0]));
00229   min_b_[1] = static_cast<int> (floor (min_p[1] * inverse_leaf_size_[1]));
00230   max_b_[1] = static_cast<int> (floor (max_p[1] * inverse_leaf_size_[1]));
00231   min_b_[2] = static_cast<int> (floor (min_p[2] * inverse_leaf_size_[2]));
00232   max_b_[2] = static_cast<int> (floor (max_p[2] * inverse_leaf_size_[2]));
00233 
00234   // Compute the number of divisions needed along all axis
00235   div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones ();
00236   div_b_[3] = 0;
00237 
00238   std::vector<cloud_point_index_idx> index_vector;
00239   index_vector.reserve (nr_points);
00240 
00241   // Create the first xyz_offset, and set up the division multiplier
00242   Eigen::Array4i xyz_offset (input_->fields[x_idx_].offset,
00243                              input_->fields[y_idx_].offset,
00244                              input_->fields[z_idx_].offset,
00245                              0);
00246   divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0);
00247   Eigen::Vector4f pt  = Eigen::Vector4f::Zero ();
00248 
00249   int centroid_size = 4;
00250   if (downsample_all_data_)
00251     centroid_size = static_cast<int> (input_->fields.size ());
00252 
00253   int rgba_index = -1;
00254 
00255   // ---[ RGB special case
00256   // if the data contains "rgba" or "rgb", add an extra field for r/g/b in centroid
00257   for (int d = 0; d < centroid_size; ++d)
00258   {
00259     if (input_->fields[d].name == std::string ("rgba") || input_->fields[d].name == std::string ("rgb"))
00260     {
00261       rgba_index = d;
00262       centroid_size += 3;
00263       break;
00264     }
00265   }
00266 
00267   // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first...
00268   if (!filter_field_name_.empty ())
00269   {
00270     // Get the distance field index
00271     int distance_idx = pcl::getFieldIndex (*input_, filter_field_name_);
00272 
00273     // @todo fixme
00274     if (input_->fields[distance_idx].datatype != sensor_msgs::PointField::FLOAT32)
00275     {
00276       PCL_ERROR ("[pcl::%s::applyFilter] Distance filtering requested, but distances are not float/double in the dataset! Only FLOAT32/FLOAT64 distances are supported right now.\n", getClassName ().c_str ());
00277       output.width = output.height = 0;
00278       output.data.clear ();
00279       return;
00280     }
00281 
00282     // First pass: go over all points and insert them into the index_vector vector
00283     // with calculated idx. Points with the same idx value will contribute to the
00284     // same point of resulting CloudPoint
00285     float distance_value = 0;
00286     for (int cp = 0; cp < nr_points; ++cp)
00287     {
00288       int point_offset = cp * input_->point_step;
00289       // Get the distance value
00290       memcpy (&distance_value, &input_->data[point_offset + input_->fields[distance_idx].offset], sizeof (float));
00291 
00292       if (filter_limit_negative_)
00293       {
00294         // Use a threshold for cutting out points which inside the interval
00295         if (distance_value < filter_limit_max_ && distance_value > filter_limit_min_)
00296         {
00297           xyz_offset += input_->point_step;
00298           continue;
00299         }
00300       }
00301       else
00302       {
00303         // Use a threshold for cutting out points which are too close/far away
00304         if (distance_value > filter_limit_max_ || distance_value < filter_limit_min_)
00305         {
00306           xyz_offset += input_->point_step;
00307           continue;
00308         }
00309       }
00310 
00311       // Unoptimized memcpys: assume fields x, y, z are in random order
00312       memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof (float));
00313       memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof (float));
00314       memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof (float));
00315 
00316       // Check if the point is invalid
00317       if (!pcl_isfinite (pt[0]) || 
00318           !pcl_isfinite (pt[1]) || 
00319           !pcl_isfinite (pt[2]))
00320       {
00321         xyz_offset += input_->point_step;
00322         continue;
00323       }
00324 
00325       int ijk0 = static_cast<int> (floor (pt[0] * inverse_leaf_size_[0]) - min_b_[0]);
00326       int ijk1 = static_cast<int> (floor (pt[1] * inverse_leaf_size_[1]) - min_b_[1]);
00327       int ijk2 = static_cast<int> (floor (pt[2] * inverse_leaf_size_[2]) - min_b_[2]);
00328       // Compute the centroid leaf index
00329       int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
00330       index_vector.push_back (cloud_point_index_idx (idx, cp));
00331 
00332       xyz_offset += input_->point_step;
00333     }
00334   }
00335   // No distance filtering, process all data
00336   else
00337   {
00338     // First pass: go over all points and insert them into the right leaf
00339     for (int cp = 0; cp < nr_points; ++cp)
00340     {
00341       // Unoptimized memcpys: assume fields x, y, z are in random order
00342       memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof (float));
00343       memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof (float));
00344       memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof (float));
00345 
00346       // Check if the point is invalid
00347       if (!pcl_isfinite (pt[0]) || 
00348           !pcl_isfinite (pt[1]) || 
00349           !pcl_isfinite (pt[2]))
00350       {
00351         xyz_offset += input_->point_step;
00352         continue;
00353       }
00354 
00355       int ijk0 = static_cast<int> (floor (pt[0] * inverse_leaf_size_[0]) - min_b_[0]);
00356       int ijk1 = static_cast<int> (floor (pt[1] * inverse_leaf_size_[1]) - min_b_[1]);
00357       int ijk2 = static_cast<int> (floor (pt[2] * inverse_leaf_size_[2]) - min_b_[2]);
00358       // Compute the centroid leaf index
00359       int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2];
00360       index_vector.push_back (cloud_point_index_idx (idx, cp));
00361       xyz_offset += input_->point_step;
00362     }
00363   }
00364 
00365   // Second pass: sort the index_vector vector using value representing target cell as index
00366   // in effect all points belonging to the same output cell will be next to each other
00367   std::sort (index_vector.begin (), index_vector.end (), std::less<cloud_point_index_idx> ());
00368 
00369   // Third pass: count output cells
00370   // we need to skip all the same, adjacenent idx values
00371   unsigned int total=0;
00372   unsigned int index=0;
00373   while (index < index_vector.size ()) 
00374   {
00375     unsigned int i = index + 1;
00376     while (i < index_vector.size () && index_vector[i].idx == index_vector[index].idx) 
00377       ++i;
00378     ++total;
00379     index = i;
00380   }
00381 
00382   // Fourth pass: compute centroids, insert them into their final position
00383   output.width = total;
00384   output.row_step = output.point_step * output.width;
00385   output.data.resize (output.width * output.point_step);
00386 
00387   if (save_leaf_layout_) 
00388   {
00389     try
00390     {
00391       // Resizing won't reset old elements to -1.  If leaf_layout_ has been used previously, it needs to be re-initialized to -1
00392       uint32_t new_layout_size = div_b_[0]*div_b_[1]*div_b_[2];
00393       //This is the number of elements that need to be re-initialized to -1
00394       uint32_t reinit_size = std::min (static_cast<unsigned int> (new_layout_size), static_cast<unsigned int> (leaf_layout_.size()));
00395       for (uint32_t i = 0; i < reinit_size; i++)
00396       {
00397         leaf_layout_[i] = -1;
00398       }        
00399       leaf_layout_.resize (new_layout_size, -1);           
00400     }
00401     catch (std::bad_alloc&)
00402     {
00403       throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout", 
00404         "voxel_grid.cpp", "applyFilter");       
00405     }
00406     catch (std::length_error&)
00407     {
00408       throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout", 
00409         "voxel_grid.cpp", "applyFilter");       
00410     }
00411   }
00412   
00413   // If we downsample each field, the {x,y,z}_idx_ offsets should correspond in input_ and output
00414   if (downsample_all_data_)
00415     xyz_offset = Eigen::Array4i (output.fields[x_idx_].offset,
00416                                  output.fields[y_idx_].offset,
00417                                  output.fields[z_idx_].offset,
00418                                  0);
00419   else
00420     // If not, we must have created a new xyzw cloud
00421     xyz_offset = Eigen::Array4i (0, 4, 8, 12);
00422 
00423   index=0;
00424   Eigen::VectorXf centroid = Eigen::VectorXf::Zero (centroid_size);
00425   Eigen::VectorXf temporary = Eigen::VectorXf::Zero (centroid_size);
00426 
00427   for (unsigned int cp = 0; cp < index_vector.size ();)
00428   {
00429     int point_offset = index_vector[cp].cloud_point_index * input_->point_step;
00430     // Do we need to process all the fields?
00431     if (!downsample_all_data_) 
00432     {
00433       memcpy (&pt[0], &input_->data[point_offset+input_->fields[x_idx_].offset], sizeof (float));
00434       memcpy (&pt[1], &input_->data[point_offset+input_->fields[y_idx_].offset], sizeof (float));
00435       memcpy (&pt[2], &input_->data[point_offset+input_->fields[z_idx_].offset], sizeof (float));
00436       centroid[0] = pt[0];
00437       centroid[1] = pt[1];
00438       centroid[2] = pt[2];
00439       centroid[3] = 0;
00440     }
00441     else
00442     {
00443       // ---[ RGB special case
00444       // fill extra r/g/b centroid field
00445       if (rgba_index >= 0)
00446       {
00447         pcl::RGB rgb;
00448         memcpy (&rgb, &input_->data[point_offset + input_->fields[rgba_index].offset], sizeof (RGB));
00449         centroid[centroid_size-3] = rgb.r;
00450         centroid[centroid_size-2] = rgb.g;
00451         centroid[centroid_size-1] = rgb.b;
00452       }
00453       // Copy all the fields
00454       for (unsigned int d = 0; d < input_->fields.size (); ++d)
00455         memcpy (&centroid[d], &input_->data[point_offset + input_->fields[d].offset], field_sizes_[d]);
00456     }
00457 
00458     unsigned int i = cp + 1;
00459     while (i < index_vector.size () && index_vector[i].idx == index_vector[cp].idx) 
00460     {
00461       int point_offset = index_vector[i].cloud_point_index * input_->point_step;
00462       if (!downsample_all_data_) 
00463       {
00464         memcpy (&pt[0], &input_->data[point_offset+input_->fields[x_idx_].offset], sizeof (float));
00465         memcpy (&pt[1], &input_->data[point_offset+input_->fields[y_idx_].offset], sizeof (float));
00466         memcpy (&pt[2], &input_->data[point_offset+input_->fields[z_idx_].offset], sizeof (float));
00467         centroid[0] += pt[0];
00468         centroid[1] += pt[1];
00469         centroid[2] += pt[2];
00470       }
00471       else
00472       {
00473         // ---[ RGB special case
00474         // fill extra r/g/b centroid field
00475         if (rgba_index >= 0)
00476         {
00477           pcl::RGB rgb;
00478           memcpy (&rgb, &input_->data[point_offset + input_->fields[rgba_index].offset], sizeof (RGB));
00479           temporary[centroid_size-3] = rgb.r;
00480           temporary[centroid_size-2] = rgb.g;
00481           temporary[centroid_size-1] = rgb.b;
00482         }
00483         // Copy all the fields
00484         for (unsigned int d = 0; d < input_->fields.size (); ++d)
00485           memcpy (&temporary[d], &input_->data[point_offset + input_->fields[d].offset], field_sizes_[d]);
00486         centroid+=temporary;
00487       }
00488       ++i;
00489     }
00490 
00491           // Save leaf layout information for fast access to cells relative to current position
00492     if (save_leaf_layout_)
00493       leaf_layout_[index_vector[cp].idx] = index;
00494 
00495     // Normalize the centroid
00496     centroid /= static_cast<float> (i - cp);
00497 
00498     // Do we need to process all the fields?
00499     if (!downsample_all_data_)
00500     {
00501       // Copy the data
00502       memcpy (&output.data[xyz_offset[0]], &centroid[0], sizeof (float));
00503       memcpy (&output.data[xyz_offset[1]], &centroid[1], sizeof (float));
00504       memcpy (&output.data[xyz_offset[2]], &centroid[2], sizeof (float));
00505       xyz_offset += output.point_step;
00506     }
00507     else
00508     {
00509       int point_offset = index * output.point_step;
00510       // Copy all the fields
00511       for (size_t d = 0; d < output.fields.size (); ++d)
00512         memcpy (&output.data[point_offset + output.fields[d].offset], &centroid[d], field_sizes_[d]);
00513 
00514       // ---[ RGB special case
00515       // full extra r/g/b centroid field
00516       if (rgba_index >= 0) 
00517       {
00518         float r = centroid[centroid_size-3], g = centroid[centroid_size-2], b = centroid[centroid_size-1];
00519         int rgb = (static_cast<int> (r) << 16) | (static_cast<int> (g) << 8) | static_cast<int> (b);
00520         memcpy (&output.data[point_offset + output.fields[rgba_index].offset], &rgb, sizeof (float));
00521       }
00522     }
00523     cp = i;
00524     ++index;
00525   }
00526 }
00527 
00528 // Instantiations of specific point types
00529 PCL_INSTANTIATE(getMinMax3D, PCL_XYZ_POINT_TYPES)
00530 PCL_INSTANTIATE(VoxelGrid, PCL_XYZ_POINT_TYPES)
00531 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:03