$search
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: io.cpp 36905 2011-05-27 00:34:09Z michael.s.dixon $ 00035 * 00036 */ 00037 #include "pcl_visualization/common/io.h" 00038 #include <Eigen/Geometry> 00039 #include <boost/make_shared.hpp> 00040 00042 00048 void 00049 pcl_visualization::getCorrespondingPointCloud (vtkPolyData *src, const pcl::PointCloud<pcl::PointXYZ> &tgt, 00050 std::vector<int> &indices) 00051 { 00052 // Iterate through the points and copy the data in a pcl::PointCloud 00053 pcl::PointCloud<pcl::PointXYZ> cloud; 00054 cloud.height = 1; cloud.width = src->GetNumberOfPoints (); 00055 cloud.is_dense = false; 00056 cloud.points.resize (cloud.width * cloud.height); 00057 for (int i = 0; i < src->GetNumberOfPoints (); i++) 00058 { 00059 double p[3]; 00060 src->GetPoint (i, p); 00061 cloud.points[i].x = p[0]; cloud.points[i].y = p[1]; cloud.points[i].z = p[2]; 00062 } 00063 00064 // Compute a kd-tree for tgt 00065 pcl::KdTreeFLANN<pcl::PointXYZ> kdtree; 00066 kdtree.setInputCloud (boost::make_shared<pcl::PointCloud<pcl::PointXYZ> > (tgt)); 00067 00068 std::vector<int> nn_indices (1); 00069 std::vector<float> nn_dists (1); 00070 // For each point on screen, find its correspondent in the target 00071 for (size_t i = 0; i < cloud.points.size (); ++i) 00072 { 00073 kdtree.nearestKSearch (cloud.points[i], 1, nn_indices, nn_dists); 00074 indices.push_back (nn_indices[0]); 00075 } 00076 // Sort and remove duplicate indices 00077 sort (indices.begin (), indices.end ()); 00078 indices.erase (unique (indices.begin (), indices.end ()), indices.end ()); 00079 } 00080 00082 00089 bool 00090 pcl_visualization::savePointData (vtkPolyData* data, const std::string &out_file, const boost::shared_ptr<CloudActorMap> &actors) 00091 { 00092 // Clean the data (no duplicates!) 00093 vtkSmartPointer<vtkCleanPolyData> cleaner = vtkSmartPointer<vtkCleanPolyData>::New (); 00094 cleaner->SetTolerance (0.0); 00095 cleaner->SetInput (data); 00096 cleaner->ConvertLinesToPointsOff (); 00097 cleaner->ConvertPolysToLinesOff (); 00098 cleaner->ConvertStripsToPolysOff (); 00099 cleaner->PointMergingOn (); 00100 cleaner->Update (); 00101 00102 // If we pruned any points, print the number of points pruned to screen 00103 if (cleaner->GetOutput ()->GetNumberOfPoints () != data->GetNumberOfPoints ()) 00104 { 00105 int nr_pts_pruned = data->GetNumberOfPoints () - cleaner->GetOutput ()->GetNumberOfPoints (); 00106 pcl::console::print_highlight ("Number of points pruned: "); pcl::console::print_value ("%d\n", nr_pts_pruned); 00107 } 00108 00109 // Attempting to load all Point Cloud data input files (using the actor name)... 00110 CloudActorMap::iterator it; 00111 int i = 1; 00112 for (it = actors->begin (); it != actors->end (); ++it) 00113 { 00114 std::string file_name = (*it).first; 00115 00116 // Is there a ".pcd" in the name? If no, then do not attempt to load this actor 00117 std::string::size_type position; 00118 if ((position = file_name.find (".pcd")) == std::string::npos) 00119 continue; 00120 00121 // Strip the ".pcd-X" 00122 file_name = file_name.substr (0, position) + ".pcd"; 00123 00124 pcl::console::print_debug (" Load: %s ... ", file_name.c_str ()); 00125 // Assume the name of the actor is the name of the file 00126 sensor_msgs::PointCloud2 cloud; 00127 if (pcl::io::loadPCDFile (file_name, cloud) == -1) 00128 { 00129 pcl::console::print_error (stdout, "[failed]\n"); 00130 return (false); 00131 } 00132 else 00133 pcl::console::print_debug ("[success]\n"); 00134 00135 pcl::PointCloud<pcl::PointXYZ> cloud_xyz; 00136 pcl::fromROSMsg (cloud, cloud_xyz); 00137 // Get the corresponding indices that we need to save from this point cloud 00138 std::vector<int> indices; 00139 getCorrespondingPointCloud (cleaner->GetOutput (), cloud_xyz, indices); 00140 00141 // Copy the indices and save the file 00142 sensor_msgs::PointCloud2 cloud_out; 00143 pcl::copyPointCloud (cloud, indices, cloud_out); 00144 std::stringstream ss; 00145 ss << out_file << i++ << ".pcd"; 00146 pcl::console::print_debug (" Save: %s ... ", ss.str ().c_str ()); 00147 if (pcl::io::savePCDFile (ss.str (), cloud_out, Eigen::Vector4f::Zero (), 00148 Eigen::Quaternionf::Identity (), true) == -1) 00149 { 00150 pcl::console::print_error (stdout, "[failed]\n"); 00151 return (false); 00152 } 00153 else 00154 pcl::console::print_debug ("[success]\n"); 00155 } 00156 00157 return (true); 00158 }