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 #include <sensor_msgs/PointCloud2.h>
00039 #include <pcl/point_types.h>
00040 #include <pcl/io/pcd_io.h>
00041 #include <pcl/segmentation/extract_clusters.h>
00042 #include <pcl/filters/extract_indices.h>
00043 #include <pcl/console/print.h>
00044 #include <pcl/console/parse.h>
00045 #include <pcl/console/time.h>
00046 #include <vector>
00047 #include <boost/lexical_cast.hpp>
00048 #include <boost/make_shared.hpp>
00049
00050 using namespace pcl;
00051 using namespace pcl::io;
00052 using namespace pcl::console;
00053
00054 int default_min = 100;
00055 int default_max = 25000;
00056 double default_tolerance = 0.02;
00057
00058 Eigen::Vector4f translation;
00059 Eigen::Quaternionf orientation;
00060
00061 void
00062 printHelp (int, char **argv)
00063 {
00064 print_error ("Syntax is: %s input.pcd output.pcd <options>\n", argv[0]);
00065 print_info (" where options are:\n");
00066 print_info (" -min X = use a minimum of X points peer cluster (default: ");
00067 print_value ("%d", default_min); print_info (")\n");
00068 print_info (" -max X = use a maximum of X points peer cluster (default: ");
00069 print_value ("%d", default_max); print_info (")\n");
00070 print_info (" -tolerance X = the spacial distance between clusters (default: ");
00071 print_value ("%lf", default_tolerance); print_info (")\n");
00072 }
00073
00074 bool
00075 loadCloud (const std::string &filename, sensor_msgs::PointCloud2 &cloud)
00076 {
00077 TicToc tt;
00078 print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00079
00080 tt.tic ();
00081 if (loadPCDFile (filename, cloud, translation, orientation) < 0)
00082 return (false);
00083 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00084 print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00085
00086 return (true);
00087 }
00088
00089 void
00090 compute (const sensor_msgs::PointCloud2::ConstPtr &input, std::vector<sensor_msgs::PointCloud2::Ptr> &output,
00091 int min, int max, double tolerance)
00092 {
00093
00094 PointCloud<pcl::PointXYZ>::Ptr xyz (new PointCloud<pcl::PointXYZ>);
00095 fromROSMsg (*input, *xyz);
00096
00097
00098 TicToc tt;
00099 tt.tic ();
00100
00101 print_highlight (stderr, "Computing ");
00102
00103
00104 pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
00105 tree->setInputCloud (xyz);
00106
00107 std::vector<pcl::PointIndices> cluster_indices;
00108 pcl::EuclideanClusterExtraction<pcl::PointXYZ> ec;
00109 ec.setClusterTolerance (tolerance);
00110 ec.setMinClusterSize (min);
00111 ec.setMaxClusterSize (max);
00112 ec.setSearchMethod (tree);
00113 ec.setInputCloud (xyz);
00114 ec.extract (cluster_indices);
00115
00116 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cluster_indices.size ()); print_info (" clusters]\n");
00117
00118 output.reserve (cluster_indices.size ());
00119 for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it)
00120 {
00121 pcl::ExtractIndices<sensor_msgs::PointCloud2> extract;
00122 extract.setInputCloud (input);
00123 extract.setIndices (boost::make_shared<const pcl::PointIndices> (*it));
00124 sensor_msgs::PointCloud2::Ptr out (new sensor_msgs::PointCloud2);
00125 extract.filter (*out);
00126 output.push_back (out);
00127 }
00128 }
00129
00130 void
00131 saveCloud (const std::string &filename, const std::vector<sensor_msgs::PointCloud2::Ptr> &output)
00132 {
00133 TicToc tt;
00134 tt.tic ();
00135
00136 std::string basename = filename.substr (0, filename.length () - 4);
00137
00138 for (size_t i = 0; i < output.size (); i++)
00139 {
00140 std::string clustername = basename + boost::lexical_cast<std::string>(i) + ".pcd";
00141 print_highlight ("Saving "); print_value ("%s ", clustername.c_str ());
00142
00143 pcl::io::savePCDFile (clustername, *(output[i]), translation, orientation, false);
00144
00145 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output[i]->width * output[i]->height); print_info (" points]\n");
00146 }
00147
00148 }
00149
00150
00151 int
00152 main (int argc, char** argv)
00153 {
00154 print_info ("Extract point clusters using pcl::EuclideanClusterExtraction. For more information, use: %s -h\n", argv[0]);
00155 bool help = false;
00156 parse_argument (argc, argv, "-h", help);
00157 if (argc < 3 || help)
00158 {
00159 printHelp (argc, argv);
00160 return (-1);
00161 }
00162
00163
00164 std::vector<int> p_file_indices;
00165 p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00166 if (p_file_indices.size () != 2)
00167 {
00168 print_error ("Need one input PCD file and one output PCD file to continue.\n");
00169 return (-1);
00170 }
00171
00172
00173 int min = default_min;
00174 int max = default_max;
00175 double tolerance = default_tolerance;
00176 parse_argument (argc, argv, "-min", min);
00177 parse_argument (argc, argv, "-max", max);
00178 parse_argument (argc, argv, "-tolerance", tolerance);
00179
00180
00181 sensor_msgs::PointCloud2::Ptr cloud (new sensor_msgs::PointCloud2);
00182 if (!loadCloud (argv[p_file_indices[0]], *cloud))
00183 return (-1);
00184
00185
00186 std::vector<sensor_msgs::PointCloud2::Ptr> output;
00187 compute (cloud, output, min, max, tolerance);
00188
00189
00190 saveCloud (argv[p_file_indices[1]], output);
00191 }