vtk_lib_io.hpp
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-2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: vtk_io.hpp 4968 2012-05-03 06:39:52Z doria $
00037  *
00038  */
00039 
00040 #ifndef PCL_IO_VTK_IO_IMPL_H_
00041 #define PCL_IO_VTK_IO_IMPL_H_
00042 
00043 // PCL
00044 #include <pcl/io/pcd_io.h>
00045 #include <pcl/point_types.h>
00046 
00047 // VTK
00048 // Ignore warnings in the above headers
00049 #ifdef __GNUC__
00050 #pragma GCC system_header 
00051 #endif
00052 #include <vtkFloatArray.h>
00053 #include <vtkPointData.h>
00054 #include <vtkPoints.h>
00055 #include <vtkPolyData.h>
00056 #include <vtkUnsignedCharArray.h>
00057 #include <vtkSmartPointer.h>
00058 #include <vtkStructuredGrid.h>
00059 #include <vtkVertexGlyphFilter.h>
00060 
00062 template <typename PointT> void
00063 pcl::io::vtkPolyDataToPointCloud (vtkPolyData* const polydata, pcl::PointCloud<PointT>& cloud)
00064 {
00065   // This generic template will convert any VTK PolyData
00066   // to a coordinate-only PointXYZ PCL format.
00067   typedef pcl::PointCloud<PointT> CloudT;
00068 
00069   typedef typename pcl::traits::fieldList<typename CloudT::PointType>::type FieldList;
00070 
00071   cloud.width = polydata->GetNumberOfPoints ();
00072   cloud.height = 1; // This indicates that the point cloud is unorganized
00073   cloud.is_dense = false;
00074   cloud.points.resize (cloud.width);
00075 
00076   typename CloudT::PointType test_point = cloud.points[0];
00077 
00078   bool has_x = false; bool has_y = false; bool has_z = false;
00079   float x_val = 0.0f; float y_val = 0.0f; float z_val = 0.0f;
00080   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point, "x", has_x, x_val));
00081   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point, "y", has_y, y_val));
00082   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point, "z", has_z, z_val));
00083 
00084   // Set the coordinates of the pcl::PointCloud (if the pcl::PointCloud supports coordinates)
00085   if (has_x && has_y && has_z)
00086   {
00087     for (size_t i = 0; i < cloud.points.size (); ++i)
00088     {
00089       double coordinate[3];
00090       polydata->GetPoint (i, coordinate);
00091       typename CloudT::PointType p = cloud.points[i];
00092       pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, float> (p, "x", coordinate[0]));
00093       pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, float> (p, "y", coordinate[1]));
00094       pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, float> (p, "z", coordinate[2]));
00095       cloud.points[i] = p;
00096     }
00097   }
00098 
00099   // Set the normals of the pcl::PointCloud (if the pcl::PointCloud supports normals and the input vtkPolyData has normals)
00100   bool has_normal_x = false; bool has_normal_y = false; bool has_normal_z = false;
00101   float normal_x_val = 0.0f; float normal_y_val = 0.0f; float normal_z_val = 0.0f;
00102   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point,
00103                                                                                             "normal_x", has_normal_x, normal_x_val));
00104   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point,
00105                                                                                             "y_normal", has_normal_y, normal_y_val));
00106   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point,
00107                                                                                             "z_normal", has_normal_z, normal_z_val));
00108 
00109   vtkFloatArray* normals = vtkFloatArray::SafeDownCast (polydata->GetPointData ()->GetNormals ());
00110   if (has_normal_x && has_normal_y && has_normal_z && normals)
00111   {
00112     for (size_t i = 0; i < cloud.points.size (); ++i)
00113     {
00114       float normal[3];
00115       normals->GetTupleValue (i, normal);
00116       typename CloudT::PointType p = cloud.points[i];
00117       pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, float> (p, "normal_x", normal[0]));
00118       pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, float> (p, "normal_y", normal[1]));
00119       pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, float> (p, "normal_z", normal[2]));
00120       cloud.points[i] = p;
00121     }
00122   }
00123 
00124   // Set the colors of the pcl::PointCloud (if the pcl::PointCloud supports colors and the input vtkPolyData has colors)
00125   bool has_r = false; bool has_g = false; bool has_b = false;
00126   unsigned char r_val = 0.0f; unsigned char g_val = 0.0f; unsigned char b_val = 0.0f;
00127   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (test_point,
00128                                                                                             "r", has_r, r_val));
00129   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (test_point,
00130                                                                                             "g", has_g, g_val));
00131   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (test_point,
00132                                                                                             "b", has_b, b_val));
00133 
00134   vtkUnsignedCharArray* colors = vtkUnsignedCharArray::SafeDownCast (polydata->GetPointData ()->GetScalars ());
00135   if (has_r && has_g && has_b && colors)
00136   {
00137     for (size_t i = 0; i < cloud.points.size (); ++i)
00138     {
00139       unsigned char color[3];
00140       colors->GetTupleValue (i, color);
00141       typename CloudT::PointType p = cloud.points[i];
00142       pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, unsigned char> (p, "r", color[0]));
00143       pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, unsigned char> (p, "g", color[1]));
00144       pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, unsigned char> (p, "b", color[2]));
00145       cloud.points[i] = p;
00146     }
00147   }
00148 }
00149 
00151 template <typename PointT> void
00152 pcl::io::vtkStructuredGridToPointCloud (vtkStructuredGrid* const structured_grid, pcl::PointCloud<PointT>& cloud)
00153 {
00154   typedef pcl::PointCloud<PointT> CloudT;
00155 
00156   int dimensions[3];
00157   structured_grid->GetDimensions (dimensions);
00158   cloud.width = dimensions[0];
00159   cloud.height = dimensions[1]; // This indicates that the point cloud is organized
00160   cloud.is_dense = true;
00161   cloud.points.resize (cloud.width * cloud.height);
00162 
00163   typename CloudT::PointType test_point = cloud.points[0];
00164 
00165   typedef typename pcl::traits::fieldList<typename CloudT::PointType>::type FieldList;
00166   
00167   bool has_x = false; bool has_y = false; bool has_z = false;
00168   float x_val = 0.0f; float y_val = 0.0f; float z_val = 0.0f;
00169   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point, "x", has_x, x_val));
00170   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point, "y", has_y, y_val));
00171   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point, "z", has_z, z_val));
00172 
00173   if (has_x && has_y && has_z)
00174   {
00175     for (size_t i = 0; i < cloud.width; ++i)
00176     {
00177       for (size_t j = 0; j < cloud.height; ++j)
00178       {
00179         int queryPoint[3] = {i, j, 0};
00180         vtkIdType pointId = vtkStructuredData::ComputePointId (dimensions, queryPoint);
00181         double coordinate[3];
00182         if (structured_grid->IsPointVisible (pointId))
00183         {
00184           structured_grid->GetPoint (pointId, coordinate);
00185           typename CloudT::PointType p = cloud (i, j);
00186           pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, float> (p, "x", coordinate[0]));
00187           pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, float> (p, "y", coordinate[1]));
00188           pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, float> (p, "z", coordinate[2]));
00189           cloud (i, j) = p;
00190         }
00191         else
00192         {
00193           // Fill the point with an "empty" point?
00194         }
00195       }
00196     }
00197   }
00198 
00199   // Set the normals of the pcl::PointCloud (if the pcl::PointCloud supports normals and the input vtkStructuredGrid has normals)
00200   bool has_normal_x = false; bool has_normal_y = false; bool has_normal_z = false;
00201   float normal_x_val = 0.0f; float normal_y_val = 0.0f; float normal_z_val = 0.0f;
00202   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point,
00203                                                                                             "x_normal", has_normal_x, normal_x_val));
00204   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point,
00205                                                                                             "y_normal", has_normal_y, normal_y_val));
00206   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point,
00207                                                                                             "z_normal", has_normal_z, normal_z_val));
00208 
00209   vtkFloatArray* normals = vtkFloatArray::SafeDownCast (structured_grid->GetPointData ()->GetNormals ());
00210 
00211   if (has_x && has_y && has_z)
00212   {
00213     for (size_t i = 0; i < cloud.width; ++i)
00214     {
00215       for (size_t j = 0; j < cloud.height; ++j)
00216       {
00217         int queryPoint[3] = {i, j, 0};
00218         vtkIdType pointId = vtkStructuredData::ComputePointId (dimensions, queryPoint);
00219         float normal[3];
00220         if(structured_grid->IsPointVisible (pointId))
00221         {
00222           normals->GetTupleValue (i, normal);
00223           typename CloudT::PointType p = cloud (i, j);
00224           pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, float> (p, "normal_x", normal[0]));
00225           pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, float> (p, "normal_y", normal[1]));
00226           pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, float> (p, "normal_z", normal[2]));
00227           cloud (i, j) = p;
00228         }
00229         else
00230         {
00231           // Fill the point with an "empty" point?
00232         }
00233       }
00234     }
00235   }
00236 
00237   // Set the colors of the pcl::PointCloud (if the pcl::PointCloud supports colors and the input vtkStructuredGrid has colors)
00238   bool has_r = false; bool has_g = false; bool has_b = false;
00239   unsigned char r_val = 0.0f; unsigned char g_val = 0.0f; unsigned char b_val = 0.0f;
00240   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (test_point,
00241                                                                                             "r", has_r, r_val));
00242   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (test_point,
00243                                                                                             "g", has_g, g_val));
00244   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (test_point,
00245                                                                                             "b", has_b, b_val));
00246   vtkUnsignedCharArray* colors = vtkUnsignedCharArray::SafeDownCast(structured_grid->GetPointData()->GetArray("Colors"));
00247 
00248   if (has_r && has_g && has_b && colors)
00249   {
00250     for (size_t i = 0; i < cloud.width; ++i)
00251     {
00252       for (size_t j = 0; j < cloud.height; ++j)
00253       {
00254         int queryPoint[3] = {i, j, 0};
00255         vtkIdType pointId = vtkStructuredData::ComputePointId(dimensions, queryPoint);
00256         unsigned char color[3];
00257         if (structured_grid->IsPointVisible (pointId))
00258         {
00259           colors->GetTupleValue (i, color);
00260           typename CloudT::PointType p = cloud (i, j);
00261           pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, float> (p, "r", color[0]));
00262           pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, float> (p, "g", color[1]));
00263           pcl::for_each_type<FieldList> (pcl::SetIfFieldExists<typename CloudT::PointType, float> (p, "b", color[2]));
00264           cloud (i, j) = p;
00265         }
00266         else
00267         {
00268           // Fill the point with an "empty" point?
00269         }
00270       }
00271     }
00272   }
00273 }
00274 
00276 template <typename PointT> void
00277 pcl::io::pointCloudTovtkPolyData (const pcl::PointCloud<PointT>& cloud, vtkPolyData* const pdata)
00278 {
00279   typedef pcl::PointCloud<PointT> CloudT;
00280 
00281   typename CloudT::PointType test_point = cloud.points[0];
00282 
00283   typedef typename pcl::traits::fieldList<typename CloudT::PointType>::type FieldList;
00284 
00285   // Coordiantes (always must have coordinates)
00286   vtkSmartPointer<vtkPoints> points = vtkSmartPointer<vtkPoints>::New ();
00287   for (size_t i = 0; i < cloud.points.size (); ++i)
00288   {
00289     double p[3];
00290     p[0] = cloud.points[i].x;
00291     p[1] = cloud.points[i].y;
00292     p[2] = cloud.points[i].z;
00293     points->InsertNextPoint (p);
00294   }
00295 
00296   // Create a temporary PolyData and add the points to it
00297   vtkSmartPointer<vtkPolyData> temp_polydata = vtkSmartPointer<vtkPolyData>::New ();
00298   temp_polydata->SetPoints (points);
00299 
00300   // Normals (optional)
00301   bool has_normal_x = false; bool has_normal_y = false; bool has_normal_z = false;
00302   float normal_x_val = 0.0f; float normal_y_val = 0.0f; float normal_z_val = 0.0f;
00303   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point, "normal_x", has_normal_x, normal_x_val));
00304   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point, "normal_y", has_normal_y, normal_y_val));
00305   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point, "normal_z", has_normal_z, normal_z_val));
00306   if (has_normal_x && has_normal_y && has_normal_z)
00307   {
00308     vtkSmartPointer<vtkFloatArray> normals = vtkSmartPointer<vtkFloatArray>::New ();
00309     normals->SetNumberOfComponents (3); //3d normals (ie x,y,z)
00310     normals->SetNumberOfTuples (cloud.points.size ());
00311     normals->SetName ("Normals");
00312 
00313     for (size_t i = 0; i < cloud.points.size (); ++i)
00314     {
00315       typename CloudT::PointType p = cloud.points[i];
00316       pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (p, "x_normal", has_normal_x, normal_x_val));
00317       pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (p, "y_normal", has_normal_y, normal_y_val));
00318       pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (p, "z_normal", has_normal_z, normal_z_val));
00319       float normal[3] = {normal_x_val, normal_y_val, normal_z_val};
00320       normals->SetTupleValue (i, normal);
00321     }
00322     temp_polydata->GetPointData ()->SetNormals (normals);
00323   }
00324 
00325   // Colors (optional)
00326   bool has_r = false; bool has_g = false; bool has_b = false;
00327   unsigned char r_val = 0; unsigned char g_val = 0; unsigned char b_val = 0;
00328   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (test_point, "r", has_r, r_val));
00329   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (test_point, "g", has_g, g_val));
00330   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (test_point, "b", has_b, b_val));
00331   if (has_r && has_g && has_b)
00332   {
00333     vtkSmartPointer<vtkUnsignedCharArray> colors = vtkSmartPointer<vtkUnsignedCharArray>::New ();
00334     colors->SetNumberOfComponents (3);
00335     colors->SetNumberOfTuples (cloud.points.size ());
00336     colors->SetName ("RGB");
00337 
00338     for (size_t i = 0; i < cloud.points.size (); ++i)
00339     {
00340       typename CloudT::PointType p = cloud[i];
00341       pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (p, "r", has_r, r_val));
00342       pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (p, "g", has_g, g_val));
00343       pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (p, "b", has_b, b_val));
00344       unsigned char color[3] = {r_val, g_val, b_val};
00345       colors->SetTupleValue (i, color);
00346     }
00347     temp_polydata->GetPointData ()->SetScalars (colors);
00348   }
00349 
00350   // Add 0D topology to every point
00351   vtkSmartPointer<vtkVertexGlyphFilter> vertex_glyph_filter = vtkSmartPointer<vtkVertexGlyphFilter>::New ();
00352   #if VTK_MAJOR_VERSION <= 5
00353     vertex_glyph_filter->AddInputConnection (temp_polydata->GetProducerPort ());
00354   #else
00355     vertex_glyph_filter->SetInputData (temp_polydata);
00356   #endif
00357   vertex_glyph_filter->Update ();
00358 
00359   pdata->DeepCopy (vertex_glyph_filter->GetOutput ());
00360 }
00361 
00363 template <typename PointT> void
00364 pcl::io::pointCloudTovtkStructuredGrid (const pcl::PointCloud<PointT>& cloud, vtkStructuredGrid* const structured_grid)
00365 {
00366   typedef pcl::PointCloud<PointT> CloudT;
00367 
00368   typename CloudT::PointType test_point = cloud.points[0];
00369 
00370   typedef typename pcl::traits::fieldList<typename CloudT::PointType>::type FieldList;
00371   
00372   int dimensions[3] = {cloud.width, cloud.height, 1};
00373   structured_grid->SetDimensions (dimensions);
00374 
00375   vtkSmartPointer<vtkPoints> points = vtkSmartPointer<vtkPoints>::New ();
00376   points->SetNumberOfPoints (cloud.width * cloud.height);
00377 
00378   unsigned int numberOfInvalidPoints = 0;
00379 
00380   for (size_t i = 0; i < cloud.width; ++i)
00381   {
00382     for (size_t j = 0; j < cloud.height; ++j)
00383     {
00384       int queryPoint[3] = {i, j, 0};
00385       vtkIdType pointId = vtkStructuredData::ComputePointId (dimensions, queryPoint);
00386       typename CloudT::PointType point = cloud (i, j);
00387 
00388       if (pcl::isFinite (point))
00389       {
00390         float p[3] = {point.x, point.y, point.z};
00391         points->SetPoint (pointId, p);
00392       }
00393       else
00394       {
00395       }
00396     }
00397   }
00398 
00399   structured_grid->SetPoints (points);
00400 
00401   // Normals (optional)
00402   bool has_normal_x = false; bool has_normal_y = false; bool has_normal_z = false;
00403   float normal_x_val = 0.0f; float normal_y_val = 0.0f; float normal_z_val = 0.0f;
00404   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point, "normal_x", has_normal_x, normal_x_val));
00405   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point, "normal_y", has_normal_y, normal_y_val));
00406   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (test_point, "normal_z", has_normal_z, normal_z_val));
00407   if (has_normal_x && has_normal_y && has_normal_z)
00408   {
00409     vtkSmartPointer<vtkFloatArray> normals = vtkSmartPointer<vtkFloatArray>::New ();
00410     normals->SetNumberOfComponents (3); // Note this must come before the SetNumberOfTuples calls
00411     normals->SetNumberOfTuples (cloud.width * cloud.height);
00412     normals->SetName ("Normals");
00413     for (size_t i = 0; i < cloud.width; ++i)
00414     {
00415       for (size_t j = 0; j < cloud.height; ++j)
00416       {
00417         int queryPoint[3] = {i, j, 0};
00418         vtkIdType pointId = vtkStructuredData::ComputePointId (dimensions, queryPoint);
00419         typename CloudT::PointType point = cloud (i, j);
00420 
00421         if (pcl::isFinite (point))
00422         {
00423           typename CloudT::PointType p = cloud.points[i];
00424           pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (p, "x_normal", has_normal_x, normal_x_val));
00425           pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (p, "y_normal", has_normal_y, normal_y_val));
00426           pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, float> (p, "z_normal", has_normal_z, normal_z_val));
00427           float normal[3] = {normal_x_val, normal_y_val, normal_z_val};
00428           normals->SetTupleValue (pointId, normal);
00429         }
00430         else
00431         {
00432         }
00433       }
00434     }
00435 
00436     structured_grid->GetPointData ()->SetNormals (normals);
00437   }
00438 
00439   // Colors (optional)
00440   bool has_r = false; bool has_g = false; bool has_b = false;
00441   unsigned char r_val = 0; unsigned char g_val = 0; unsigned char b_val = 0;
00442   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (test_point, "r", has_r, r_val));
00443   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (test_point, "g", has_g, g_val));
00444   pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (test_point, "b", has_b, b_val));
00445   if (has_r && has_g && has_b)
00446   {
00447     vtkSmartPointer<vtkUnsignedCharArray> colors = vtkSmartPointer<vtkUnsignedCharArray>::New();
00448     colors->SetNumberOfComponents (3); // Note this must come before the SetNumberOfTuples calls
00449     colors->SetNumberOfTuples (cloud.width * cloud.height);
00450     colors->SetName ("Colors");
00451     for (size_t i = 0; i < cloud.width; ++i)
00452     {
00453       for (size_t j = 0; j < cloud.height; ++j)
00454       {
00455         int queryPoint[3] = {i, j, 0};
00456         vtkIdType pointId = vtkStructuredData::ComputePointId (dimensions, queryPoint);
00457         typename CloudT::PointType point = cloud (i, j);
00458 
00459         if (pcl::isFinite (point))
00460         {
00461           typename CloudT::PointType p = cloud[i];
00462           pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (p, "r", has_r, r_val));
00463           pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (p, "g", has_g, g_val));
00464           pcl::for_each_type<FieldList> (pcl::CopyIfFieldExists<typename CloudT::PointType, unsigned char> (p, "b", has_b, b_val));
00465           unsigned char color[3] = {r_val, g_val, b_val};
00466           colors->SetTupleValue (i, color);
00467         }
00468         else
00469         {
00470         }
00471       }
00472     }
00473     structured_grid->GetPointData ()->AddArray (colors);
00474   }
00475 }
00476 
00477 #endif  //#ifndef PCL_IO_VTK_IO_H_
00478 


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