point_cloud_handlers.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, 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: point_cloud_handlers.hpp 6161 2012-07-05 17:37:29Z rusu $
00035  *
00036  */
00037 
00038 #include <pcl/console/time.h>
00039 #include <pcl/pcl_macros.h>
00040 
00042 template <typename PointT> void
00043 pcl::visualization::PointCloudColorHandlerCustom<PointT>::getColor (vtkSmartPointer<vtkDataArray> &scalars) const
00044 {
00045   if (!capable_)
00046     return;
00047 
00048   if (!scalars)
00049     scalars = vtkSmartPointer<vtkUnsignedCharArray>::New ();
00050   scalars->SetNumberOfComponents (3);
00051   
00052   vtkIdType nr_points = cloud_->points.size ();
00053   reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetNumberOfTuples (nr_points);
00054 
00055   // Get a random color
00056   unsigned char* colors = new unsigned char[nr_points * 3];
00057 
00058   // Color every point
00059   for (vtkIdType cp = 0; cp < nr_points; ++cp)
00060   {
00061     colors[cp * 3 + 0] = static_cast<unsigned char> (r_);
00062     colors[cp * 3 + 1] = static_cast<unsigned char> (g_);
00063     colors[cp * 3 + 2] = static_cast<unsigned char> (b_);
00064   }
00065   reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetArray (colors, 3 * nr_points, 0);
00066 }
00067 
00069 template <typename PointT> void
00070 pcl::visualization::PointCloudColorHandlerRandom<PointT>::getColor (vtkSmartPointer<vtkDataArray> &scalars) const
00071 {
00072   if (!capable_)
00073     return;
00074 
00075   if (!scalars)
00076     scalars = vtkSmartPointer<vtkUnsignedCharArray>::New ();
00077   scalars->SetNumberOfComponents (3);
00078   
00079   vtkIdType nr_points = cloud_->points.size ();
00080   reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetNumberOfTuples (nr_points);
00081 
00082   // Get a random color
00083   unsigned char* colors = new unsigned char[nr_points * 3];
00084   double r, g, b;
00085   pcl::visualization::getRandomColors (r, g, b);
00086 
00087   int r_ = static_cast<int> (pcl_lrint (r * 255.0)), 
00088       g_ = static_cast<int> (pcl_lrint (g * 255.0)), 
00089       b_ = static_cast<int> (pcl_lrint (b * 255.0));
00090 
00091   // Color every point
00092   for (vtkIdType cp = 0; cp < nr_points; ++cp)
00093   {
00094     colors[cp * 3 + 0] = static_cast<unsigned char> (r_);
00095     colors[cp * 3 + 1] = static_cast<unsigned char> (g_);
00096     colors[cp * 3 + 2] = static_cast<unsigned char> (b_);
00097   }
00098   reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetArray (colors, 3 * nr_points, 0);
00099 }
00100 
00102 template <typename PointT>
00103 pcl::visualization::PointCloudColorHandlerRGBField<PointT>::PointCloudColorHandlerRGBField (const PointCloudConstPtr &cloud) : 
00104   pcl::visualization::PointCloudColorHandler<PointT>::PointCloudColorHandler (cloud)
00105 {
00106   // Handle the 24-bit packed RGB values
00107   field_idx_ = pcl::getFieldIndex (*cloud, "rgb", fields_);
00108   if (field_idx_ != -1)
00109   {
00110     capable_ = true;
00111     return;
00112   }
00113   else
00114   {
00115     field_idx_ = pcl::getFieldIndex (*cloud, "rgba", fields_);
00116     if (field_idx_ != -1)
00117       capable_ = true;
00118     else
00119       capable_ = false;
00120   }
00121 }
00122 
00124 template <typename PointT> void 
00125 pcl::visualization::PointCloudColorHandlerRGBField<PointT>::getColor (vtkSmartPointer<vtkDataArray> &scalars) const
00126 {
00127   if (!capable_)
00128     return;
00129 
00130   if (!scalars)
00131     scalars = vtkSmartPointer<vtkUnsignedCharArray>::New ();
00132   scalars->SetNumberOfComponents (3);
00133 
00134   vtkIdType nr_points = cloud_->points.size ();
00135   reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetNumberOfTuples (nr_points);
00136   unsigned char* colors = reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->GetPointer (0);
00137 
00138   int j = 0;
00139   // If XYZ present, check if the points are invalid
00140   int x_idx = -1;
00141   for (size_t d = 0; d < fields_.size (); ++d)
00142     if (fields_[d].name == "x")
00143       x_idx = static_cast<int> (d);
00144 
00145   if (x_idx != -1)
00146   {
00147     // Color every point
00148     for (vtkIdType cp = 0; cp < nr_points; ++cp)
00149     {
00150       // Copy the value at the specified field
00151       if (!pcl_isfinite (cloud_->points[cp].x) ||
00152           !pcl_isfinite (cloud_->points[cp].y) || 
00153           !pcl_isfinite (cloud_->points[cp].z))
00154         continue;
00155 
00156       int idx = j * 3;
00157       colors[idx    ] = cloud_->points[cp].r;
00158       colors[idx + 1] = cloud_->points[cp].g;
00159       colors[idx + 2] = cloud_->points[cp].b;
00160       j++;
00161     }
00162   }
00163   else
00164   {
00165     // Color every point
00166     for (vtkIdType cp = 0; cp < nr_points; ++cp)
00167     {
00168       int idx = static_cast<int> (cp) * 3;
00169       colors[idx    ] = cloud_->points[cp].r;
00170       colors[idx + 1] = cloud_->points[cp].g;
00171       colors[idx + 2] = cloud_->points[cp].b;
00172     }
00173   }
00174 }
00175 
00177 template <typename PointT>
00178 pcl::visualization::PointCloudColorHandlerHSVField<PointT>::PointCloudColorHandlerHSVField (const PointCloudConstPtr &cloud) : 
00179   pcl::visualization::PointCloudColorHandler<PointT>::PointCloudColorHandler (cloud)
00180 {
00181   // Check for the presence of the "H" field
00182   field_idx_ = pcl::getFieldIndex (*cloud, "h", fields_);
00183   if (field_idx_ == -1)
00184   {
00185     capable_ = false;
00186     return;
00187   }
00188 
00189   // Check for the presence of the "S" field
00190   s_field_idx_ = pcl::getFieldIndex (*cloud, "s", fields_);
00191   if (s_field_idx_ == -1)
00192   {
00193     capable_ = false;
00194     return;
00195   }
00196 
00197   // Check for the presence of the "V" field
00198   v_field_idx_ = pcl::getFieldIndex (*cloud, "v", fields_);
00199   if (v_field_idx_ == -1)
00200   {
00201     capable_ = false;
00202     return;
00203   }
00204   capable_ = true;
00205 }
00206 
00208 template <typename PointT> void 
00209 pcl::visualization::PointCloudColorHandlerHSVField<PointT>::getColor (vtkSmartPointer<vtkDataArray> &scalars) const
00210 {
00211   if (!capable_)
00212     return;
00213 
00214   if (!scalars)
00215     scalars = vtkSmartPointer<vtkUnsignedCharArray>::New ();
00216   scalars->SetNumberOfComponents (3);
00217 
00218   vtkIdType nr_points = cloud_->points.size ();
00219   reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->SetNumberOfTuples (nr_points);
00220   unsigned char* colors = reinterpret_cast<vtkUnsignedCharArray*>(&(*scalars))->GetPointer (0);
00221 
00222   int j = 0;
00223   // If XYZ present, check if the points are invalid
00224   int x_idx = -1;
00225   
00226   for (size_t d = 0; d < fields_.size (); ++d)
00227     if (fields_[d].name == "x")
00228       x_idx = static_cast<int> (d);
00229 
00230   if (x_idx != -1)
00231   {
00232     // Color every point
00233     for (vtkIdType cp = 0; cp < nr_points; ++cp)
00234     {
00235       // Copy the value at the specified field
00236       if (!pcl_isfinite (cloud_->points[cp].x) ||
00237           !pcl_isfinite (cloud_->points[cp].y) || 
00238           !pcl_isfinite (cloud_->points[cp].z))
00239         continue;
00240 
00241       int idx = j * 3;
00242 
00244 
00245       // Fill color data with HSV here:
00246       if (cloud_->points[cp].s == 0)
00247       {
00248         colors[idx] = colors[idx+1] = colors[idx+2] = cloud_->points[cp].v;
00249         return;
00250       } 
00251       float a = cloud_->points[cp].h / 60;
00252       int   i = floor (a);
00253       float f = a - i;
00254       float p = cloud_->points[cp].v * (1 - cloud_->points[cp].s);
00255       float q = cloud_->points[cp].v * (1 - cloud_->points[cp].s * f);
00256       float t = cloud_->points[cp].v * (1 - cloud_->points[cp].s * (1 - f));
00257 
00258       switch (i) 
00259       {
00260         case 0:
00261           colors[idx] = cloud_->points[cp].v; colors[idx+1] = t; colors[idx+2] = p; break;
00262         case 1:
00263           colors[idx] = q; colors[idx+1] = cloud_->points[cp].v; colors[idx+2] = p; break;
00264         case 2:
00265           colors[idx] = p; colors[idx+1] = cloud_->points[cp].v; colors[idx+2] = t; break;
00266         case 3:
00267           colors[idx] = p; colors[idx+1] = q; colors[idx+2] = cloud_->points[cp].v; break;
00268         case 4:
00269           colors[idx] = t; colors[idx+1] = p; colors[idx+2] = cloud_->points[cp].v; break;
00270         default:
00271           colors[idx] = cloud_->points[cp].v; colors[idx+1] = p; colors[idx+2] = q; break;
00272       }
00273       j++;
00274     }
00275   }
00276   else
00277   {
00278     // Color every point
00279     for (vtkIdType cp = 0; cp < nr_points; ++cp)
00280     {
00281       int idx = cp * 3;
00282 
00283       // Fill color data with HSV here:
00284       if (cloud_->points[cp].s == 0)
00285       {
00286         colors[idx] = colors[idx+1] = colors[idx+2] = cloud_->points[cp].v;
00287         return;
00288       } 
00289       float a = cloud_->points[cp].h / 60;
00290       int   i = floor (a);
00291       float f = a - i;
00292       float p = cloud_->points[cp].v * (1 - cloud_->points[cp].s);
00293       float q = cloud_->points[cp].v * (1 - cloud_->points[cp].s * f);
00294       float t = cloud_->points[cp].v * (1 - cloud_->points[cp].s * (1 - f));
00295 
00296       switch (i) 
00297       {
00298         case 0:
00299           colors[idx] = cloud_->points[cp].v; colors[idx+1] = t; colors[idx+2] = p; break;
00300         case 1:
00301           colors[idx] = q; colors[idx+1] = cloud_->points[cp].v; colors[idx+2] = p; break;
00302         case 2:
00303           colors[idx] = p; colors[idx+1] = cloud_->points[cp].v; colors[idx+2] = t; break;
00304         case 3:
00305           colors[idx] = p; colors[idx+1] = q; colors[idx+2] = cloud_->points[cp].v; break;
00306         case 4:
00307           colors[idx] = t; colors[idx+1] = p; colors[idx+2] = cloud_->points[cp].v; break;
00308         default:
00309           colors[idx] = cloud_->points[cp].v; colors[idx+1] = p; colors[idx+2] = q; break;
00310       }
00311     }
00312   }
00313 }
00314 
00316 template <typename PointT>
00317 pcl::visualization::PointCloudColorHandlerGenericField<PointT>::PointCloudColorHandlerGenericField (
00318     const PointCloudConstPtr &cloud, const std::string &field_name) : 
00319   pcl::visualization::PointCloudColorHandler<PointT>::PointCloudColorHandler (cloud), 
00320   field_name_ (field_name)
00321 {
00322   field_idx_  = pcl::getFieldIndex (*cloud, field_name, fields_);
00323   if (field_idx_ != -1)
00324     capable_ = true;
00325   else
00326     capable_ = false;
00327 }
00328 
00330 template <typename PointT> void 
00331 pcl::visualization::PointCloudColorHandlerGenericField<PointT>::getColor (vtkSmartPointer<vtkDataArray> &scalars) const
00332 {
00333   if (!capable_)
00334     return;
00335 
00336   if (!scalars)
00337     scalars = vtkSmartPointer<vtkFloatArray>::New ();
00338   scalars->SetNumberOfComponents (1);
00339 
00340   vtkIdType nr_points = cloud_->points.size ();
00341   reinterpret_cast<vtkFloatArray*>(&(*scalars))->SetNumberOfTuples (nr_points);
00342 
00343   typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00344 
00345   float* colors = new float[nr_points];
00346   float field_data;
00347 
00348   int j = 0;
00349   // If XYZ present, check if the points are invalid
00350   int x_idx = -1;
00351   for (size_t d = 0; d < fields_.size (); ++d)
00352     if (fields_[d].name == "x")
00353       x_idx = static_cast<int> (d);
00354 
00355   if (x_idx != -1)
00356   {
00357     // Color every point
00358     for (vtkIdType cp = 0; cp < nr_points; ++cp)
00359     {
00360       // Copy the value at the specified field
00361       if (!pcl_isfinite (cloud_->points[cp].x) || !pcl_isfinite (cloud_->points[cp].y) || !pcl_isfinite (cloud_->points[cp].z))
00362         continue;
00363 
00364       const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&cloud_->points[cp]);
00365       memcpy (&field_data, pt_data + fields_[field_idx_].offset, pcl::getFieldSize (fields_[field_idx_].datatype));
00366 
00367       colors[j] = field_data;
00368       j++;
00369     }
00370   }
00371   else
00372   {
00373     // Color every point
00374     for (vtkIdType cp = 0; cp < nr_points; ++cp)
00375     {
00376       const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&cloud_->points[cp]);
00377       memcpy (&field_data, pt_data + fields_[field_idx_].offset, pcl::getFieldSize (fields_[field_idx_].datatype));
00378 
00379       if (!pcl_isfinite (field_data))
00380         continue;
00381 
00382       colors[j] = field_data;
00383       j++;
00384     }
00385   }
00386   reinterpret_cast<vtkFloatArray*>(&(*scalars))->SetArray (colors, j, 0);
00387 }
00388 
00390 template <typename PointT>
00391 pcl::visualization::PointCloudGeometryHandlerXYZ<PointT>::PointCloudGeometryHandlerXYZ (const PointCloudConstPtr &cloud) 
00392   : pcl::visualization::PointCloudGeometryHandler<PointT>::PointCloudGeometryHandler (cloud)
00393 {
00394   field_x_idx_ = pcl::getFieldIndex (*cloud, "x", fields_);
00395   if (field_x_idx_ == -1)
00396     return;
00397   field_y_idx_ = pcl::getFieldIndex (*cloud, "y", fields_);
00398   if (field_y_idx_ == -1)
00399     return;
00400   field_z_idx_ = pcl::getFieldIndex (*cloud, "z", fields_);
00401   if (field_z_idx_ == -1)
00402     return;
00403   capable_ = true;
00404 }
00405 
00407 template <typename PointT> void 
00408 pcl::visualization::PointCloudGeometryHandlerXYZ<PointT>::getGeometry (vtkSmartPointer<vtkPoints> &points) const
00409 {
00410   if (!capable_)
00411     return;
00412 
00413   if (!points)
00414     points = vtkSmartPointer<vtkPoints>::New ();
00415   points->SetDataTypeToFloat ();
00416 
00417   vtkSmartPointer<vtkFloatArray> data = vtkSmartPointer<vtkFloatArray>::New ();
00418   data->SetNumberOfComponents (3);
00419   vtkIdType nr_points = cloud_->points.size ();
00420 
00421   // Add all points
00422   vtkIdType j = 0;    // true point index
00423   float* pts = static_cast<float*> (malloc (nr_points * 3 * sizeof (float)));
00424 
00425   // If the dataset has no invalid values, just copy all of them
00426   if (cloud_->is_dense)
00427   {
00428     for (vtkIdType i = 0; i < nr_points; ++i)
00429     {
00430       pts[i * 3 + 0] = cloud_->points[i].x;
00431       pts[i * 3 + 1] = cloud_->points[i].y;
00432       pts[i * 3 + 2] = cloud_->points[i].z;
00433     }
00434     data->SetArray (&pts[0], nr_points * 3, 0);
00435     points->SetData (data);
00436   }
00437   // Need to check for NaNs, Infs, ec
00438   else
00439   {
00440     for (vtkIdType i = 0; i < nr_points; ++i)
00441     {
00442       // Check if the point is invalid
00443       if (!pcl_isfinite (cloud_->points[i].x) || !pcl_isfinite (cloud_->points[i].y) || !pcl_isfinite (cloud_->points[i].z))
00444         continue;
00445 
00446       pts[j * 3 + 0] = cloud_->points[i].x;
00447       pts[j * 3 + 1] = cloud_->points[i].y;
00448       pts[j * 3 + 2] = cloud_->points[i].z;
00449       // Set j and increment
00450       j++;
00451     }
00452     data->SetArray (&pts[0], j * 3, 0);
00453     points->SetData (data);
00454   }
00455 }
00456 
00458 template <typename PointT>
00459 pcl::visualization::PointCloudGeometryHandlerSurfaceNormal<PointT>::PointCloudGeometryHandlerSurfaceNormal (const PointCloudConstPtr &cloud) 
00460   : pcl::visualization::PointCloudGeometryHandler<PointT>::PointCloudGeometryHandler (cloud)
00461 {
00462   field_x_idx_ = pcl::getFieldIndex (*cloud, "normal_x", fields_);
00463   if (field_x_idx_ == -1)
00464     return;
00465   field_y_idx_ = pcl::getFieldIndex (*cloud, "normal_y", fields_);
00466   if (field_y_idx_ == -1)
00467     return;
00468   field_z_idx_ = pcl::getFieldIndex (*cloud, "normal_z", fields_);
00469   if (field_z_idx_ == -1)
00470     return;
00471   capable_ = true;
00472 }
00473 
00475 template <typename PointT> void 
00476 pcl::visualization::PointCloudGeometryHandlerSurfaceNormal<PointT>::getGeometry (vtkSmartPointer<vtkPoints> &points) const
00477 {
00478   if (!capable_)
00479     return;
00480 
00481   if (!points)
00482     points = vtkSmartPointer<vtkPoints>::New ();
00483   points->SetDataTypeToFloat ();
00484   points->SetNumberOfPoints (cloud_->points.size ());
00485 
00486   // Add all points
00487   double p[3];
00488   for (vtkIdType i = 0; i < static_cast<vtkIdType> (cloud_->points.size ()); ++i)
00489   {
00490     p[0] = cloud_->points[i].normal[0];
00491     p[1] = cloud_->points[i].normal[1];
00492     p[2] = cloud_->points[i].normal[2];
00493 
00494     points->SetPoint (i, p);
00495   }
00496 }
00497 
00499 template <typename PointT>
00500 pcl::visualization::PointCloudGeometryHandlerCustom<PointT>::PointCloudGeometryHandlerCustom (const PointCloudConstPtr &cloud,
00501     const std::string &x_field_name, const std::string &y_field_name, const std::string &z_field_name) : pcl::visualization::PointCloudGeometryHandler<PointT>::PointCloudGeometryHandler (cloud)
00502 {
00503   field_x_idx_ = pcl::getFieldIndex (*cloud, x_field_name, fields_);
00504   if (field_x_idx_ == -1)
00505     return;
00506   field_y_idx_ = pcl::getFieldIndex (*cloud, y_field_name, fields_);
00507   if (field_y_idx_ == -1)
00508     return;
00509   field_z_idx_ = pcl::getFieldIndex (*cloud, z_field_name, fields_);
00510   if (field_z_idx_ == -1)
00511     return;
00512   field_name_ = x_field_name + y_field_name + z_field_name;
00513   capable_ = true;
00514 }
00515 
00517 template <typename PointT> void 
00518 pcl::visualization::PointCloudGeometryHandlerCustom<PointT>::getGeometry (vtkSmartPointer<vtkPoints> &points) const
00519 {
00520   if (!capable_)
00521     return;
00522 
00523   if (!points)
00524     points = vtkSmartPointer<vtkPoints>::New ();
00525   points->SetDataTypeToFloat ();
00526   points->SetNumberOfPoints (cloud_->points.size ());
00527 
00528   float data;
00529   // Add all points
00530   double p[3];
00531   for (vtkIdType i = 0; i < static_cast<vtkIdType> (cloud_->points.size ()); ++i)
00532   {
00533     // Copy the value at the specified field
00534     const uint8_t* pt_data = reinterpret_cast<const uint8_t*> (&cloud_->points[i]);
00535     memcpy (&data, pt_data + fields_[field_x_idx_].offset, sizeof (float));
00536     p[0] = data;
00537 
00538     memcpy (&data, pt_data + fields_[field_y_idx_].offset, sizeof (float));
00539     p[1] = data;
00540 
00541     memcpy (&data, pt_data + fields_[field_z_idx_].offset, sizeof (float));
00542     p[2] = data;
00543 
00544     points->SetPoint (i, p);
00545   }
00546 }
00547 


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