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 #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
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
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
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
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
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
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
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
00117 std::string::size_type position;
00118 if ((position = file_name.find (".pcd")) == std::string::npos)
00119 continue;
00120
00121
00122 file_name = file_name.substr (0, position) + ".pcd";
00123
00124 pcl::console::print_debug (" Load: %s ... ", file_name.c_str ());
00125
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
00138 std::vector<int> indices;
00139 getCorrespondingPointCloud (cleaner->GetOutput (), cloud_xyz, indices);
00140
00141
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 }