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
00041
00047 void
00048 pcl_visualization::getCorrespondingPointCloud (vtkPolyData *src, const pcl::PointCloud<pcl::PointXYZ> &tgt,
00049 std::vector<int> &indices)
00050 {
00051
00052 pcl::PointCloud<pcl::PointXYZ> cloud;
00053 cloud.height = 1; cloud.width = src->GetNumberOfPoints ();
00054 cloud.is_dense = false;
00055 cloud.points.resize (cloud.width * cloud.height);
00056 for (int i = 0; i < src->GetNumberOfPoints (); i++)
00057 {
00058 double p[3];
00059 src->GetPoint (i, p);
00060 cloud.points[i].x = p[0]; cloud.points[i].y = p[1]; cloud.points[i].z = p[2];
00061 }
00062
00063
00064 pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
00065 kdtree.setInputCloud (boost::make_shared<pcl::PointCloud<pcl::PointXYZ> > (tgt));
00066
00067 std::vector<int> nn_indices (1);
00068 std::vector<float> nn_dists (1);
00069
00070 for (size_t i = 0; i < cloud.points.size (); ++i)
00071 {
00072 kdtree.nearestKSearch (cloud.points[i], 1, nn_indices, nn_dists);
00073 indices.push_back (nn_indices[0]);
00074 }
00075
00076 sort (indices.begin (), indices.end ());
00077 indices.erase (unique (indices.begin (), indices.end ()), indices.end ());
00078 }
00079
00081
00088 bool
00089 pcl_visualization::savePointData (vtkPolyData* data, const std::string &out_file, const boost::shared_ptr<CloudActorMap> &actors)
00090 {
00091
00092 vtkSmartPointer<vtkCleanPolyData> cleaner = vtkSmartPointer<vtkCleanPolyData>::New ();
00093 cleaner->SetTolerance (0.0);
00094 cleaner->SetInput (data);
00095 cleaner->ConvertLinesToPointsOff ();
00096 cleaner->ConvertPolysToLinesOff ();
00097 cleaner->ConvertStripsToPolysOff ();
00098 cleaner->PointMergingOn ();
00099 cleaner->Update ();
00100
00101
00102 if (cleaner->GetOutput ()->GetNumberOfPoints () != data->GetNumberOfPoints ())
00103 {
00104 int nr_pts_pruned = data->GetNumberOfPoints () - cleaner->GetOutput ()->GetNumberOfPoints ();
00105 terminal_tools::print_highlight ("Number of points pruned: "); terminal_tools::print_value ("%d\n", nr_pts_pruned);
00106 }
00107
00108
00109 CloudActorMap::iterator it;
00110 int i = 1;
00111 for (it = actors->begin (); it != actors->end (); ++it)
00112 {
00113 std::string file_name = (*it).first;
00114
00115
00116 std::string::size_type position;
00117 if ((position = file_name.find (".pcd")) == std::string::npos)
00118 continue;
00119
00120
00121 file_name = file_name.substr (0, position) + ".pcd";
00122
00123 terminal_tools::print_debug (" Load: %s ... ", file_name.c_str ());
00124
00125 sensor_msgs::PointCloud2 cloud;
00126 if (pcl::io::loadPCDFile (file_name, cloud) == -1)
00127 {
00128 terminal_tools::print_error (stdout, "[failed]\n");
00129 return (false);
00130 }
00131 else
00132 terminal_tools::print_debug ("[success]\n");
00133
00134 pcl::PointCloud<pcl::PointXYZ> cloud_xyz;
00135 pcl::fromROSMsg (cloud, cloud_xyz);
00136
00137 std::vector<int> indices;
00138 getCorrespondingPointCloud (cleaner->GetOutput (), cloud_xyz, indices);
00139
00140
00141 sensor_msgs::PointCloud2 cloud_out;
00142 pcl::copyPointCloud (cloud, indices, cloud_out);
00143 std::stringstream ss;
00144 ss << out_file << i++ << ".pcd";
00145 terminal_tools::print_debug (" Save: %s ... ", ss.str ().c_str ());
00146 if (pcl::io::savePCDFile (ss.str (), cloud_out, Eigen::Vector4f::Zero (),
00147 Eigen::Quaternionf::Identity (), true) == -1)
00148 {
00149 terminal_tools::print_error (stdout, "[failed]\n");
00150 return (false);
00151 }
00152 else
00153 terminal_tools::print_debug ("[success]\n");
00154 }
00155
00156 return (true);
00157 }