point_cloud_handlers.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, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  */
00038 
00039 #include <pcl/visualization/point_cloud_handlers.h>
00040 #include <pcl/visualization/impl/point_cloud_geometry_handlers.hpp>
00041 #include <pcl/pcl_macros.h>
00042 #include <pcl/common/io.h>
00043 #include <pcl/impl/instantiate.hpp>
00044 #include <pcl/point_types.h>
00045 
00047 bool
00048 pcl::visualization::PointCloudColorHandlerCustom<pcl::PCLPointCloud2>::getColor (vtkSmartPointer<vtkDataArray> &scalars) const
00049 {
00050   if (!capable_ || !cloud_)
00051     return (false);
00052   
00053   if (!scalars)
00054     scalars = vtkSmartPointer<vtkUnsignedCharArray>::New ();
00055   scalars->SetNumberOfComponents (3);
00056   
00057   vtkIdType nr_points = cloud_->width * cloud_->height;
00058   reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetNumberOfTuples (nr_points);
00059   
00060   // Get a random color
00061   unsigned char* colors = new unsigned char[nr_points * 3];
00062   
00063   // Color every point
00064   for (vtkIdType cp = 0; cp < nr_points; ++cp)
00065   {
00066     colors[cp * 3 + 0] = static_cast<unsigned char> (r_);
00067     colors[cp * 3 + 1] = static_cast<unsigned char> (g_);
00068     colors[cp * 3 + 2] = static_cast<unsigned char> (b_);
00069   }
00070   reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetArray (colors, 3 * nr_points, 0);
00071   return (true);
00072 }
00073 
00075 bool
00076 pcl::visualization::PointCloudColorHandlerRandom<pcl::PCLPointCloud2>::getColor (vtkSmartPointer<vtkDataArray> &scalars) const
00077 {
00078   if (!capable_ || !cloud_)
00079     return (false);
00080   
00081   if (!scalars)
00082     scalars = vtkSmartPointer<vtkUnsignedCharArray>::New ();
00083   scalars->SetNumberOfComponents (3);
00084   
00085   vtkIdType nr_points = cloud_->width * cloud_->height;
00086   reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetNumberOfTuples (nr_points);
00087   
00088   // Get a random color
00089   unsigned char* colors = new unsigned char[nr_points * 3];
00090   double r, g, b;
00091   pcl::visualization::getRandomColors (r, g, b);
00092   
00093   long r_ = pcl_lrint (r * 255.0), g_ = pcl_lrint (g * 255.0), b_ = pcl_lrint (b * 255.0);
00094 
00095   // Color every point
00096   for (vtkIdType cp = 0; cp < nr_points; ++cp)
00097   {
00098     colors[cp * 3 + 0] = static_cast<unsigned char> (r_);
00099     colors[cp * 3 + 1] = static_cast<unsigned char> (g_);
00100     colors[cp * 3 + 2] = static_cast<unsigned char> (b_);
00101   }
00102   reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetArray (colors, 3 * nr_points, 0);
00103   return (true);
00104 }
00105 
00107 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PCLPointCloud2>::PointCloudColorHandlerRGBField (
00108     const pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>::PointCloudConstPtr &cloud) :
00109   pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>::PointCloudColorHandler (cloud)
00110 {
00111   // Handle the 24-bit packed RGB values
00112   field_idx_ = pcl::getFieldIndex (*cloud, "rgb");
00113   if (field_idx_ != -1)
00114   {
00115     capable_ = true;
00116     return;
00117   }
00118   else
00119   {
00120     field_idx_ = pcl::getFieldIndex (*cloud, "rgba");
00121     if (field_idx_ != -1)
00122       capable_ = true;
00123     else
00124       capable_ = false;
00125   }
00126 }
00127 
00129 bool
00130 pcl::visualization::PointCloudColorHandlerRGBField<pcl::PCLPointCloud2>::getColor (vtkSmartPointer<vtkDataArray> &scalars) const
00131 {
00132   if (!capable_ || !cloud_)
00133     return (false);
00134 
00135   if (!scalars)
00136     scalars = vtkSmartPointer<vtkUnsignedCharArray>::New ();
00137   scalars->SetNumberOfComponents (3);
00138 
00139   vtkIdType nr_points = cloud_->width * cloud_->height;
00140   reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetNumberOfTuples (nr_points);
00141   // Allocate enough memory to hold all colors
00142   unsigned char* colors = new unsigned char[nr_points * 3];
00143 
00144   pcl::RGB rgb_data;
00145   int point_offset = cloud_->fields[field_idx_].offset;
00146   int j = 0;
00147   
00148   // If XYZ present, check if the points are invalid
00149   int x_idx = pcl::getFieldIndex (*cloud_, "x");
00150   if (x_idx != -1)
00151   {
00152     float x_data, y_data, z_data;
00153     int x_point_offset = cloud_->fields[x_idx].offset;
00154     
00155     // Color every point
00156     for (vtkIdType cp = 0; cp < nr_points; ++cp, 
00157                                            point_offset += cloud_->point_step, 
00158                                            x_point_offset += cloud_->point_step)
00159     {
00160       // Copy the value at the specified field
00161       memcpy (&rgb_data, &cloud_->data[point_offset], sizeof (float));
00162 
00163       memcpy (&x_data, &cloud_->data[x_point_offset], sizeof (float));
00164       memcpy (&y_data, &cloud_->data[x_point_offset + sizeof (float)], sizeof (float));
00165       memcpy (&z_data, &cloud_->data[x_point_offset + 2 * sizeof (float)], sizeof (float));
00166 
00167       if (!pcl_isfinite (x_data) || !pcl_isfinite (y_data) || !pcl_isfinite (z_data))
00168         continue;
00169 
00170       colors[j + 0] = rgb_data.r;
00171       colors[j + 1] = rgb_data.g;
00172       colors[j + 2] = rgb_data.b;
00173       j += 3;
00174     }
00175   }
00176   // No XYZ data checks
00177   else
00178   {
00179     // Color every point
00180     for (vtkIdType cp = 0; cp < nr_points; ++cp, point_offset += cloud_->point_step)
00181     {
00182       // Copy the value at the specified field
00183       memcpy (&rgb_data, &cloud_->data[point_offset], sizeof (float));
00184 
00185       colors[j + 0] = rgb_data.r;
00186       colors[j + 1] = rgb_data.g;
00187       colors[j + 2] = rgb_data.b;
00188       j += 3;
00189     }
00190   }
00191   if (j != 0)
00192     reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetArray (colors, j, 0);
00193   else
00194     reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetNumberOfTuples (0);
00195   //delete [] colors;
00196   return (true);
00197 }
00198 
00200 pcl::visualization::PointCloudColorHandlerHSVField<pcl::PCLPointCloud2>::PointCloudColorHandlerHSVField (
00201     const pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>::PointCloudConstPtr &cloud) :
00202   pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>::PointCloudColorHandler (cloud),
00203   s_field_idx_ (-1), v_field_idx_ (-1)
00204 {
00205   // Check for the presence of the "H" field
00206   field_idx_ = pcl::getFieldIndex (*cloud, "h");
00207   if (field_idx_ == -1)
00208   {
00209     capable_ = false;
00210     return;
00211   }
00212 
00213   // Check for the presence of the "S" field
00214   s_field_idx_ = pcl::getFieldIndex (*cloud, "s");
00215   if (s_field_idx_ == -1)
00216   {
00217     capable_ = false;
00218     return;
00219   }
00220 
00221   // Check for the presence of the "V" field
00222   v_field_idx_ = pcl::getFieldIndex (*cloud, "v");
00223   if (v_field_idx_ == -1)
00224   {
00225     capable_ = false;
00226     return;
00227   }
00228   capable_ = true;
00229 }
00230 
00232 bool
00233 pcl::visualization::PointCloudColorHandlerHSVField<pcl::PCLPointCloud2>::getColor (vtkSmartPointer<vtkDataArray> &scalars) const
00234 {
00235   if (!capable_ || !cloud_)
00236     return (false);
00237 
00238   if (!scalars)
00239     scalars = vtkSmartPointer<vtkUnsignedCharArray>::New ();
00240   scalars->SetNumberOfComponents (3);
00241 
00242   vtkIdType nr_points = cloud_->width * cloud_->height;
00243   reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetNumberOfTuples (nr_points);
00244 
00245   // Allocate enough memory to hold all colors
00246   // colors is taken over by SetArray (line 419)
00247   unsigned char* colors = new unsigned char[nr_points * 3];
00248 
00249   float h_data, v_data, s_data;
00250   int point_offset = cloud_->fields[field_idx_].offset;
00251   int j = 0;
00252 
00253   // If XYZ present, check if the points are invalid
00254   int x_idx = pcl::getFieldIndex (*cloud_, "x");
00255   if (x_idx != -1)
00256   {
00257     float x_data, y_data, z_data;
00258     int x_point_offset = cloud_->fields[x_idx].offset;
00259 
00260     // Color every point
00261     for (vtkIdType cp = 0; cp < nr_points; ++cp, 
00262                                            point_offset += cloud_->point_step, 
00263                                            x_point_offset += cloud_->point_step)
00264     {
00265       // Copy the value at the specified field
00266       memcpy (&h_data, &cloud_->data[point_offset], sizeof (float));
00267       memcpy (&s_data, &cloud_->data[point_offset + sizeof (float)], sizeof (float));
00268       memcpy (&v_data, &cloud_->data[point_offset + 2 * sizeof (float)], sizeof (float));
00269 
00270       if (!pcl_isfinite (h_data) || !pcl_isfinite (s_data) || !pcl_isfinite (v_data))
00271         continue;   //skip to next point
00272 
00273       memcpy (&x_data, &cloud_->data[x_point_offset], sizeof (float));
00274       memcpy (&y_data, &cloud_->data[x_point_offset + sizeof (float)], sizeof (float));
00275       memcpy (&z_data, &cloud_->data[x_point_offset + 2 * sizeof (float)], sizeof (float));
00276 
00277       if (!pcl_isfinite (x_data) || !pcl_isfinite (y_data) || !pcl_isfinite (z_data))
00278         continue;   //skip to next point
00279 
00280       int idx = j * 3;
00281       // Fill color data with HSV here:
00282       if (s_data == 0)
00283       {
00284         colors[idx] = colors[idx+1] = colors[idx+2] = static_cast<unsigned char> (v_data);
00285         continue;   //skip to next point
00286       } 
00287       float a = h_data / 60;
00288       int   i = static_cast<int> (floor (a));
00289       float f = a - static_cast<float> (i);
00290       float p = v_data * (1 - s_data);
00291       float q = v_data * (1 - s_data * f);
00292       float t = v_data * (1 - s_data * (1 - f));
00293 
00294       switch (i) 
00295       {
00296         case 0:
00297         {
00298           colors[idx]   = static_cast<unsigned char> (v_data);
00299           colors[idx+1] = static_cast<unsigned char> (t);
00300           colors[idx+2] = static_cast<unsigned char> (p);
00301           break;
00302         }
00303         case 1:
00304         {
00305           colors[idx]   = static_cast<unsigned char> (q);
00306           colors[idx+1] = static_cast<unsigned char> (v_data);
00307           colors[idx+2] = static_cast<unsigned char> (p);
00308           break;
00309         }
00310         case 2:
00311         {
00312           colors[idx]   = static_cast<unsigned char> (p);
00313           colors[idx+1] = static_cast<unsigned char> (v_data);
00314           colors[idx+2] = static_cast<unsigned char> (t);
00315           break;
00316         }
00317         case 3:
00318         {
00319           colors[idx]   = static_cast<unsigned char> (p);
00320           colors[idx+1] = static_cast<unsigned char> (q);
00321           colors[idx+2] = static_cast<unsigned char> (v_data);
00322           break;
00323         }
00324         case 4:
00325         {
00326           colors[idx]   = static_cast<unsigned char> (t);
00327           colors[idx+1] = static_cast<unsigned char> (p);
00328           colors[idx+2] = static_cast<unsigned char> (v_data);
00329           break;
00330         }
00331         default:
00332         {
00333           colors[idx]   = static_cast<unsigned char> (v_data);
00334           colors[idx+1] = static_cast<unsigned char> (p);
00335           colors[idx+2] = static_cast<unsigned char> (q);
00336           break;
00337         }
00338       }
00339       j++;
00340     }
00341   }
00342   // No XYZ data checks
00343   else
00344   {
00345     // Color every point
00346     for (vtkIdType cp = 0; cp < nr_points; ++cp, point_offset += cloud_->point_step)
00347     {
00348       // Copy the value at the specified field
00349       memcpy (&h_data, &cloud_->data[point_offset], sizeof (float));
00350       memcpy (&s_data, &cloud_->data[point_offset + sizeof (float)], sizeof (float));
00351       memcpy (&v_data, &cloud_->data[point_offset + 2 * sizeof (float)], sizeof (float));
00352 
00353       if (!pcl_isfinite (h_data) || !pcl_isfinite (s_data) || !pcl_isfinite (v_data))
00354         continue;   //skip to next point
00355 
00356       int idx = j * 3;
00357       // Fill color data with HSV here:
00358       if (s_data == 0)
00359       {
00360         colors[idx] = colors[idx+1] = colors[idx+2] = static_cast<unsigned char> (v_data);
00361         continue;   //skip to next point
00362       } 
00363       float a = h_data / 60;
00364       int   i = static_cast<int> (floor (a));
00365       float f = a - static_cast<float> (i);
00366       float p = v_data * (1 - s_data);
00367       float q = v_data * (1 - s_data * f);
00368       float t = v_data * (1 - s_data * (1 - f));
00369 
00370       switch (i) 
00371       {
00372         case 0:
00373         {
00374           colors[idx]   = static_cast<unsigned char> (v_data);
00375           colors[idx+1] = static_cast<unsigned char> (t);
00376           colors[idx+2] = static_cast<unsigned char> (p);
00377           break;
00378         }
00379         case 1:
00380         {
00381           colors[idx]   = static_cast<unsigned char> (q);
00382           colors[idx+1] = static_cast<unsigned char> (v_data);
00383           colors[idx+2] = static_cast<unsigned char> (p);
00384           break;
00385         }
00386         case 2:
00387         {
00388           colors[idx]   = static_cast<unsigned char> (p);
00389           colors[idx+1] = static_cast<unsigned char> (v_data);
00390           colors[idx+2] = static_cast<unsigned char> (t);
00391           break;
00392         }
00393         case 3:
00394         {
00395           colors[idx]   = static_cast<unsigned char> (p);
00396           colors[idx+1] = static_cast<unsigned char> (q);
00397           colors[idx+2] = static_cast<unsigned char> (v_data);
00398           break;
00399         }
00400         case 4:
00401         {
00402           colors[idx]   = static_cast<unsigned char> (t);
00403           colors[idx+1] = static_cast<unsigned char> (p);
00404           colors[idx+2] = static_cast<unsigned char> (v_data);
00405           break;
00406         }
00407         default:
00408         {
00409           colors[idx]   = static_cast<unsigned char> (v_data);
00410           colors[idx+1] = static_cast<unsigned char> (p);
00411           colors[idx+2] = static_cast<unsigned char> (q);
00412           break;
00413         }
00414       }
00415       j++;
00416     }
00417   }
00418   // Set array takes over allocation (Set save to 1 to keep the class from deleting the array when it cleans up or reallocates memory.)
00419   reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetArray (colors, 3 * j, 0);
00420   return (true);
00421 }
00422 
00424 pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2>::PointCloudColorHandlerGenericField (
00425     const pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>::PointCloudConstPtr &cloud,
00426     const std::string &field_name) : 
00427   pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>::PointCloudColorHandler (cloud),
00428   field_name_ (field_name)
00429 {
00430   field_idx_  = pcl::getFieldIndex (*cloud, field_name);
00431   if (field_idx_ != -1)
00432     capable_ = true;
00433   else
00434     capable_ = false;
00435 }
00436 
00438 bool
00439 pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2>::getColor (vtkSmartPointer<vtkDataArray> &scalars) const
00440 {
00441   if (!capable_ || !cloud_)
00442     return (false);
00443 
00444   if (!scalars)
00445     scalars = vtkSmartPointer<vtkFloatArray>::New ();
00446   scalars->SetNumberOfComponents (1);
00447 
00448   vtkIdType nr_points = cloud_->width * cloud_->height;
00449   reinterpret_cast<vtkFloatArray*>(&(*scalars))->SetNumberOfTuples (nr_points);
00450 
00451   float* colors = new float[nr_points];
00452   float field_data;
00453   int j = 0;
00454   int point_offset = cloud_->fields[field_idx_].offset;
00455 
00456   // If XYZ present, check if the points are invalid
00457   int x_idx = pcl::getFieldIndex (*cloud_, "x");
00458   if (x_idx != -1)
00459   {
00460     float x_data, y_data, z_data;
00461     int x_point_offset = cloud_->fields[x_idx].offset;
00462     
00463     // Color every point
00464     for (vtkIdType cp = 0; cp < nr_points; ++cp,
00465                                            point_offset += cloud_->point_step, 
00466                                            x_point_offset += cloud_->point_step)
00467     {
00468       memcpy (&x_data, &cloud_->data[x_point_offset], sizeof (float));
00469       memcpy (&y_data, &cloud_->data[x_point_offset + sizeof (float)], sizeof (float));
00470       memcpy (&z_data, &cloud_->data[x_point_offset + 2 * sizeof (float)], sizeof (float));
00471       if (!pcl_isfinite (x_data) || !pcl_isfinite (y_data) || !pcl_isfinite (z_data))
00472         continue;
00473 
00474       // Copy the value at the specified field
00475       memcpy (&field_data, &cloud_->data[point_offset], pcl::getFieldSize (cloud_->fields[field_idx_].datatype));
00476       colors[j] = field_data;
00477       j++;
00478     }
00479   }
00480   // No XYZ data checks
00481   else
00482   {
00483     // Color every point
00484     for (vtkIdType cp = 0; cp < nr_points; ++cp, point_offset += cloud_->point_step)
00485     {
00486       // Copy the value at the specified field
00487       //memcpy (&field_data, &cloud_->data[point_offset], sizeof (float));
00488       memcpy (&field_data, &cloud_->data[point_offset], pcl::getFieldSize (cloud_->fields[field_idx_].datatype));
00489 
00490       if (!pcl_isfinite (field_data))
00491         continue;
00492       colors[j] = field_data;
00493       j++;
00494     }
00495   }
00496   reinterpret_cast<vtkFloatArray*>(&(*scalars))->SetArray (colors, j, 0);
00497   return (true);
00498 }
00499 
00501 void 
00502 pcl::visualization::PointCloudGeometryHandler<pcl::PCLPointCloud2>::getGeometry (vtkSmartPointer<vtkPoints> &points) const
00503 {
00504   if (!capable_)
00505     return;
00506 
00507   if (!points)
00508     points = vtkSmartPointer<vtkPoints>::New ();
00509   points->SetDataTypeToFloat ();
00510 
00511   vtkSmartPointer<vtkFloatArray> data = vtkSmartPointer<vtkFloatArray>::New ();
00512   data->SetNumberOfComponents (3);
00513   vtkIdType nr_points = cloud_->width * cloud_->height;
00514 
00515   // Add all points
00516   float dim;
00517   vtkIdType j = 0;    // true point index
00518   float* pts = static_cast<float*> (malloc (nr_points * 3 * sizeof (float)));
00519   int point_offset = 0;
00520 
00521   // If the dataset has no invalid values, just copy all of them
00522   if (cloud_->is_dense)
00523   {
00524     for (vtkIdType i = 0; i < nr_points; ++i, point_offset+=cloud_->point_step)
00525     {
00526       // Copy the value at the specified field
00527       memcpy (&dim, &cloud_->data[point_offset + cloud_->fields[field_x_idx_].offset], sizeof (float));
00528       pts[i * 3 + 0] = dim;
00529 
00530       memcpy (&dim, &cloud_->data[point_offset + cloud_->fields[field_y_idx_].offset], sizeof (float));
00531       pts[i * 3 + 1] = dim;
00532 
00533       memcpy (&dim, &cloud_->data[point_offset + cloud_->fields[field_z_idx_].offset], sizeof (float));
00534       pts[i * 3 + 2] = dim;
00535     }
00536     data->SetArray (&pts[0], nr_points * 3, 0);
00537     points->SetData (data);
00538   }
00539   else
00540   {
00541     for (vtkIdType i = 0; i < nr_points; ++i, point_offset+=cloud_->point_step)
00542     {
00543       // Copy the value at the specified field
00544       memcpy (&dim, &cloud_->data[point_offset + cloud_->fields[field_x_idx_].offset], sizeof (float));
00545       if (!pcl_isfinite (dim))
00546         continue;
00547       pts[j * 3 + 0] = dim;
00548 
00549       memcpy (&dim, &cloud_->data[point_offset + cloud_->fields[field_y_idx_].offset], sizeof (float));
00550       if (!pcl_isfinite (dim))
00551         continue;
00552       pts[j * 3 + 1] = dim;
00553 
00554       memcpy (&dim, &cloud_->data[point_offset + cloud_->fields[field_z_idx_].offset], sizeof (float));
00555       if (!pcl_isfinite (dim))
00556         continue;
00557       pts[j * 3 + 2] = dim;
00558 
00559       // Set j and increment
00560       j++;
00561     }
00562     data->SetArray (&pts[0], j * 3, 0);
00563     points->SetData (data);
00564   }
00565 }
00566 
00568 pcl::visualization::PointCloudGeometryHandlerXYZ<pcl::PCLPointCloud2>::PointCloudGeometryHandlerXYZ (const PointCloudConstPtr &cloud)
00569 : pcl::visualization::PointCloudGeometryHandler<pcl::PCLPointCloud2>::PointCloudGeometryHandler (cloud)
00570 {
00571   field_x_idx_ = pcl::getFieldIndex (*cloud, "x");
00572   if (field_x_idx_ == -1)
00573     return;
00574   field_y_idx_ = pcl::getFieldIndex (*cloud, "y");
00575   if (field_y_idx_ == -1)
00576     return;
00577   field_z_idx_ = pcl::getFieldIndex (*cloud, "z");
00578   if (field_z_idx_ == -1)
00579     return;
00580   capable_ = true;
00581 }
00582 
00584 pcl::visualization::PointCloudGeometryHandlerSurfaceNormal<pcl::PCLPointCloud2>::PointCloudGeometryHandlerSurfaceNormal (const PointCloudConstPtr &cloud)
00585 : pcl::visualization::PointCloudGeometryHandler<pcl::PCLPointCloud2>::PointCloudGeometryHandler (cloud)
00586 {
00587   field_x_idx_ = pcl::getFieldIndex (*cloud, "normal_x");
00588   if (field_x_idx_ == -1)
00589     return;
00590   field_y_idx_ = pcl::getFieldIndex (*cloud, "normal_y");
00591   if (field_y_idx_ == -1)
00592     return;
00593   field_z_idx_ = pcl::getFieldIndex (*cloud, "normal_z");
00594   if (field_z_idx_ == -1)
00595     return;
00596   capable_ = true;
00597 }
00598 
00600 pcl::visualization::PointCloudGeometryHandlerCustom<pcl::PCLPointCloud2>::PointCloudGeometryHandlerCustom (
00601     const PointCloudConstPtr &cloud, const std::string &x_field_name, const std::string &y_field_name, const std::string &z_field_name) 
00602 : pcl::visualization::PointCloudGeometryHandler<pcl::PCLPointCloud2>::PointCloudGeometryHandler (cloud), field_name_ ()
00603 {
00604   field_x_idx_ = pcl::getFieldIndex (*cloud, x_field_name);
00605   if (field_x_idx_ == -1)
00606     return;
00607   field_y_idx_ = pcl::getFieldIndex (*cloud, y_field_name);
00608   if (field_y_idx_ == -1)
00609     return;
00610   field_z_idx_ = pcl::getFieldIndex (*cloud, z_field_name);
00611   if (field_z_idx_ == -1)
00612     return;
00613   field_name_ = x_field_name + y_field_name + z_field_name;
00614   capable_ = true;
00615 }
00616 
00617 // Instantiations of specific point types
00618 #ifdef PCL_ONLY_CORE_POINT_TYPES
00619   PCL_INSTANTIATE(PointCloudGeometryHandlerXYZ, (pcl::PointSurfel)(pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::PointNormal)(pcl::PointXYZRGBNormal))
00620   PCL_INSTANTIATE(PointCloudGeometryHandlerSurfaceNormal, (pcl::Normal)(pcl::PointNormal)(pcl::PointXYZRGBNormal))
00621 #else
00622   PCL_INSTANTIATE(PointCloudGeometryHandlerXYZ, PCL_XYZ_POINT_TYPES)
00623   PCL_INSTANTIATE(PointCloudGeometryHandlerSurfaceNormal, PCL_NORMAL_POINT_TYPES)
00624 #endif
00625 


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