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