cloud_mesh.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) 2012, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of Willow Garage, Inc. nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  */
00036 
00037 #include <pcl/apps/modeler/cloud_mesh.h>
00038 
00039 #include <pcl/visualization/point_cloud_handlers.h>
00040 #include <pcl/filters/filter_indices.h>
00041 #include <pcl/common/transforms.h>
00042 #include <pcl/PolygonMesh.h>
00043 #include <pcl/io/pcd_io.h>
00044 #include <pcl/io/obj_io.h>
00045 #include <vtkDataArray.h>
00046 #include <vtkCellArray.h>
00047 
00049 pcl::modeler::CloudMesh::CloudMesh()
00050   :vtk_points_(vtkSmartPointer<vtkPoints>::New()),
00051   vtk_polygons_(vtkSmartPointer<vtkCellArray>::New())
00052 {
00053   cloud_.reset(new pcl::PointCloud<pcl::PointSurfel>());
00054   vtk_points_->SetDataTypeToFloat ();
00055 }
00056 
00058 pcl::modeler::CloudMesh::CloudMesh(PointCloudPtr cloud)
00059   :cloud_(cloud),
00060   vtk_points_(vtkSmartPointer<vtkPoints>::New()),
00061   vtk_polygons_(vtkSmartPointer<vtkCellArray>::New())
00062 {
00063   vtk_points_->SetDataTypeToFloat ();
00064   updateVtkPoints();
00065 }
00066 
00068 pcl::modeler::CloudMesh::~CloudMesh ()
00069 {
00070 }
00071 
00073 std::vector<std::string>
00074 pcl::modeler::CloudMesh::getAvaiableFieldNames() const
00075 {
00076   // TODO:
00077   return (std::vector<std::string>());
00078 }
00079 
00081 bool
00082 pcl::modeler::CloudMesh::open(const std::string& filename)
00083 {
00084   if (pcl::io::loadPCDFile(filename, *cloud_) != 0)
00085     return (false);
00086 
00087   updateVtkPoints();
00088 
00089   return (true);
00090 }
00091 
00093 bool
00094 pcl::modeler::CloudMesh::save(const std::string& filename) const
00095 {
00096   if (filename.rfind(".obj") == (filename.length()-4))
00097   {
00098     pcl::PolygonMesh polygon_mesh;
00099     pcl::toPCLPointCloud2(*cloud_, polygon_mesh.cloud);
00100     polygon_mesh.polygons = polygons_;
00101     return (pcl::io::saveOBJFile(filename, polygon_mesh, true) == 0);
00102   }
00103 
00104   return (pcl::io::savePCDFile(filename, *cloud_, true) == 0);
00105 }
00106 
00108 bool
00109 pcl::modeler::CloudMesh::save(const std::vector<const CloudMesh*>& cloud_meshes, const std::string& filename)
00110 {
00111   if (cloud_meshes.empty())
00112     return false;
00113 
00114   if (cloud_meshes.size() == 1)
00115     return (cloud_meshes[0]->save(filename));
00116 
00117   CloudMesh cloud_mesh;
00118   for (size_t i = 0, i_end = cloud_meshes.size(); i < i_end; ++ i)
00119   {
00120     if (filename.rfind(".obj") == (filename.length()-4))
00121     {
00122       size_t delta = cloud_mesh.cloud_->size();
00123       const std::vector<pcl::Vertices>& polygons = cloud_meshes[i]->polygons_;
00124       for (size_t j = 0, j_end = polygons.size(); j < j_end; ++ j)
00125       {
00126         pcl::Vertices polygon = polygons[j];
00127         for (size_t k = 0, k_end = polygon.vertices.size(); k < k_end; ++ k)
00128           polygon.vertices[k] += static_cast<unsigned int> (delta);
00129         cloud_mesh.polygons_.push_back(polygon);
00130       }
00131     }
00132 
00133     *cloud_mesh.cloud_ += *(cloud_meshes[i]->cloud_);
00134   }
00135 
00136   return (cloud_mesh.save(filename));
00137 }
00138 
00140 void
00141 pcl::modeler::CloudMesh::getColorScalarsFromField(vtkSmartPointer<vtkDataArray> &scalars, const std::string& field) const
00142 {
00143   if (field == "rgb" || field == "rgba")
00144   {
00145     pcl::visualization::PointCloudColorHandlerRGBField<PointT> color_handler(cloud_);
00146     color_handler.getColor(scalars);
00147     return;
00148   }
00149 
00150   if (field == "random")
00151   {
00152     pcl::visualization::PointCloudColorHandlerRandom<PointT> color_handler(cloud_);
00153     color_handler.getColor(scalars);
00154     return;
00155   }
00156 
00157   pcl::visualization::PointCloudColorHandlerGenericField<PointT> color_handler(cloud_, field);
00158   color_handler.getColor(scalars);
00159 
00160   return;
00161 }
00162 
00164 void
00165 pcl::modeler::CloudMesh::updateVtkPoints()
00166 {
00167   if (vtk_points_->GetData() == NULL)
00168     vtk_points_->SetData(vtkSmartPointer<vtkFloatArray>::New ());
00169 
00170   vtkFloatArray* data = dynamic_cast<vtkFloatArray*>(vtk_points_->GetData());
00171   data->SetNumberOfComponents (3);
00172 
00173   // If the dataset has no invalid values, just copy all of them
00174   if (cloud_->is_dense)
00175   {
00176     vtkIdType nr_points = cloud_->points.size ();
00177     data->SetNumberOfValues(3*nr_points);
00178 
00179     for (vtkIdType i = 0; i < nr_points; ++i)
00180     {
00181       data->SetValue(i*3+0, cloud_->points[i].x);
00182       data->SetValue(i*3+1, cloud_->points[i].y);
00183       data->SetValue(i*3+2, cloud_->points[i].z);
00184     }
00185   }
00186   // Need to check for NaNs, Infs, ec
00187   else
00188   {
00189     pcl::IndicesPtr indices(new std::vector<int>());
00190     pcl::removeNaNFromPointCloud(*cloud_, *indices);
00191 
00192     data->SetNumberOfValues(3*indices->size());
00193 
00194     for (vtkIdType i = 0, i_end = indices->size(); i < i_end; ++i)
00195     {
00196       vtkIdType idx = (*indices)[i];
00197       data->SetValue(i*3+0, cloud_->points[idx].x);
00198       data->SetValue(i*3+1, cloud_->points[idx].y);
00199       data->SetValue(i*3+2, cloud_->points[idx].z);
00200     }
00201   }
00202   data->Squeeze();
00203 
00204   return;
00205 }
00206 
00208 void
00209 pcl::modeler::CloudMesh::updateVtkPolygons()
00210 {
00211   vtk_polygons_->Reset();
00212 
00213   if (cloud_->is_dense)
00214   {
00215     for (size_t i = 0, i_end = polygons_.size (); i < i_end; ++i)
00216     {
00217       size_t n_points = polygons_[i].vertices.size ();
00218       vtk_polygons_->InsertNextCell (static_cast<unsigned int> (n_points));
00219       for (size_t j = 0; j < n_points; j++)
00220         vtk_polygons_->InsertCellPoint (polygons_[i].vertices[j]);
00221     }
00222   }
00223   else
00224   {
00225     pcl::IndicesPtr indices(new std::vector<int>());
00226     pcl::removeNaNFromPointCloud(*cloud_, *indices);
00227 
00228     for (size_t i = 0, i_end = polygons_.size(); i < i_end; ++i)
00229     {
00230       size_t n_points = polygons_[i].vertices.size ();
00231       vtk_polygons_->InsertNextCell (static_cast<unsigned int> (n_points));
00232       for (size_t j = 0; j < n_points; j++)
00233         vtk_polygons_->InsertCellPoint ((*indices)[polygons_[i].vertices[j]]);
00234     }
00235   }
00236 
00237   return;
00238 }
00239 
00241 void
00242 pcl::modeler::CloudMesh::transform(double tx, double ty, double tz, double rx, double ry, double rz)
00243 {
00244   Eigen::Vector4f centroid;
00245   pcl::compute3DCentroid(*cloud_, centroid);
00246 
00247   CloudMesh::PointCloud mean_cloud = *cloud_;
00248   pcl::demeanPointCloud(*cloud_, centroid, mean_cloud);
00249 
00250   rx *= M_PI/180;
00251   ry *= M_PI/180;
00252   rz *= M_PI/180;
00253   Eigen::Affine3f affine_transform = pcl::getTransformation (float (tx), float (ty), float (tz), float (rx), float (ry), float (rz));
00254   CloudMesh::PointCloud transform_cloud = mean_cloud;
00255   pcl::transformPointCloudWithNormals(mean_cloud, transform_cloud, affine_transform.matrix());
00256 
00257   centroid = -centroid;
00258   pcl::demeanPointCloud(transform_cloud, centroid, *cloud_);
00259 
00260   return;
00261 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:22:43