Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include <vtkPolyData.h>
00040 #include <vtkCleanPolyData.h>
00041 #include <vtkSmartPointer.h>
00042
00043 #include <pcl/visualization/common/io.h>
00044 #include <pcl/io/pcd_io.h>
00045 #include <pcl/visualization/eigen.h>
00046
00048 void
00049 pcl::visualization::getCorrespondingPointCloud (vtkPolyData *src,
00050 const pcl::PointCloud<pcl::PointXYZ> &tgt,
00051 std::vector<int> &indices)
00052 {
00053
00054 pcl::PointCloud<pcl::PointXYZ> cloud;
00055 cloud.height = 1; cloud.width = static_cast<uint32_t> (src->GetNumberOfPoints ());
00056 cloud.is_dense = false;
00057 cloud.points.resize (cloud.width * cloud.height);
00058 for (int i = 0; i < src->GetNumberOfPoints (); i++)
00059 {
00060 double p[3];
00061 src->GetPoint (i, p);
00062 cloud.points[i].x = static_cast<float> (p[0]);
00063 cloud.points[i].y = static_cast<float> (p[1]);
00064 cloud.points[i].z = static_cast<float> (p[2]);
00065 }
00066
00067
00068 pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
00069 boost::shared_ptr<pcl::PointCloud<pcl::PointXYZ> > tgt_ptr (new pcl::PointCloud<pcl::PointXYZ> (tgt));
00070 kdtree.setInputCloud (tgt_ptr);
00071
00072 std::vector<int> nn_indices (1);
00073 std::vector<float> nn_dists (1);
00074
00075 for (size_t i = 0; i < cloud.points.size (); ++i)
00076 {
00077 kdtree.nearestKSearch (cloud.points[i], 1, nn_indices, nn_dists);
00078 indices.push_back (nn_indices[0]);
00079 }
00080
00081 std::sort (indices.begin (), indices.end ());
00082 indices.erase (std::unique (indices.begin (), indices.end ()), indices.end ());
00083 }
00084
00086 bool
00087 pcl::visualization::savePointData (vtkPolyData* data, const std::string &out_file, const boost::shared_ptr<CloudActorMap> &actors)
00088 {
00089
00090 vtkSmartPointer<vtkCleanPolyData> cleaner = vtkSmartPointer<vtkCleanPolyData>::New ();
00091 cleaner->SetTolerance (0.0);
00092 cleaner->SetInput (data);
00093 cleaner->ConvertLinesToPointsOff ();
00094 cleaner->ConvertPolysToLinesOff ();
00095 cleaner->ConvertStripsToPolysOff ();
00096 cleaner->PointMergingOn ();
00097 cleaner->Update ();
00098
00099
00100 if (cleaner->GetOutput ()->GetNumberOfPoints () != data->GetNumberOfPoints ())
00101 {
00102 int nr_pts_pruned = static_cast<int> (data->GetNumberOfPoints () - cleaner->GetOutput ()->GetNumberOfPoints ());
00103 pcl::console::print_highlight ("Number of points pruned: "); pcl::console::print_value ("%d\n", nr_pts_pruned);
00104 }
00105
00106
00107 CloudActorMap::iterator it;
00108 int i = 1;
00109 for (it = actors->begin (); it != actors->end (); ++it)
00110 {
00111 std::string file_name = (*it).first;
00112
00113
00114 std::string::size_type position;
00115 if ((position = file_name.find (".pcd")) == std::string::npos)
00116 continue;
00117
00118
00119 file_name = file_name.substr (0, position) + ".pcd";
00120
00121 pcl::console::print_debug (" Load: %s ... ", file_name.c_str ());
00122
00123 pcl::PCLPointCloud2 cloud;
00124 if (pcl::io::loadPCDFile (file_name, cloud) == -1)
00125 {
00126 pcl::console::print_error (stdout, "[failed]\n");
00127 return (false);
00128 }
00129 else
00130 pcl::console::print_debug ("[success]\n");
00131
00132 pcl::PointCloud<pcl::PointXYZ> cloud_xyz;
00133 pcl::fromPCLPointCloud2 (cloud, cloud_xyz);
00134
00135 std::vector<int> indices;
00136 getCorrespondingPointCloud (cleaner->GetOutput (), cloud_xyz, indices);
00137
00138
00139 pcl::PCLPointCloud2 cloud_out;
00140 pcl::copyPointCloud (cloud, indices, cloud_out);
00141 std::stringstream ss;
00142 ss << out_file << i++ << ".pcd";
00143 pcl::console::print_debug (" Save: %s ... ", ss.str ().c_str ());
00144 if (pcl::io::savePCDFile (ss.str (), cloud_out, Eigen::Vector4f::Zero (),
00145 Eigen::Quaternionf::Identity (), true) == -1)
00146 {
00147 pcl::console::print_error (stdout, "[failed]\n");
00148 return (false);
00149 }
00150 else
00151 pcl::console::print_debug ("[success]\n");
00152 }
00153
00154 return (true);
00155 }