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/io/pcd_io.h>
00040 #include <pcl/keypoints/uniform_sampling.h>
00041 #include <pcl/console/print.h>
00042 #include <pcl/console/parse.h>
00043 #include <pcl/console/time.h>
00044
00045 using namespace std;
00046 using namespace pcl;
00047 using namespace pcl::io;
00048 using namespace pcl::console;
00049
00050 double default_radius = 0.01;
00051
00052 Eigen::Vector4f translation;
00053 Eigen::Quaternionf orientation;
00054
00055 void
00056 printHelp (int, char **argv)
00057 {
00058 print_error ("Syntax is: %s input.pcd output.pcd <options>\n", argv[0]);
00059 print_info (" where options are:\n");
00060 print_info (" -radius X = use a leaf size of X,X,X to uniformly select 1 point per leaf (default: ");
00061 print_value ("%f", default_radius); print_info (")\n");
00062 }
00063
00064 bool
00065 loadCloud (const string &filename, pcl::PCLPointCloud2 &cloud)
00066 {
00067 TicToc tt;
00068 print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00069
00070 tt.tic ();
00071 if (loadPCDFile (filename, cloud, translation, orientation) < 0)
00072 return (false);
00073 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00074 print_info ("Available dimensions: "); print_value ("%s\n", getFieldsList (cloud).c_str ());
00075
00076 return (true);
00077 }
00078
00079 void
00080 compute (const pcl::PCLPointCloud2::ConstPtr &input, pcl::PCLPointCloud2 &output,
00081 double radius)
00082 {
00083
00084 PointCloud<PointXYZ>::Ptr xyz (new PointCloud<PointXYZ>);
00085 fromPCLPointCloud2 (*input, *xyz);
00086
00087
00088 TicToc tt;
00089 tt.tic ();
00090
00091 print_highlight (stderr, "Computing ");
00092
00093 UniformSampling<PointXYZ> us;
00094 us.setInputCloud (xyz);
00095 us.setRadiusSearch (radius);
00096 PointCloud<int> subsampled_indices;
00097 us.compute (subsampled_indices);
00098 std::sort (subsampled_indices.points.begin (), subsampled_indices.points.end ());
00099
00100 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", subsampled_indices.width * subsampled_indices.height); print_info (" points]\n");
00101
00102
00103 copyPointCloud (*input, subsampled_indices.points, output);
00104 }
00105
00106 void
00107 saveCloud (const string &filename, const pcl::PCLPointCloud2 &output)
00108 {
00109 TicToc tt;
00110 tt.tic ();
00111
00112 print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00113
00114 PCDWriter w;
00115 w.writeBinaryCompressed (filename, output, translation, orientation);
00116
00117 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00118 }
00119
00120
00121 int
00122 main (int argc, char** argv)
00123 {
00124 print_info ("Uniform subsampling using UniformSampling. For more information, use: %s -h\n", argv[0]);
00125
00126 if (argc < 3)
00127 {
00128 printHelp (argc, argv);
00129 return (-1);
00130 }
00131
00132
00133 vector<int> p_file_indices;
00134 p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00135 if (p_file_indices.size () != 2)
00136 {
00137 print_error ("Need one input PCD file and one output PCD file to continue.\n");
00138 return (-1);
00139 }
00140
00141
00142 double radius = default_radius;
00143 parse_argument (argc, argv, "-radius", radius);
00144 print_info ("Extracting uniform points with a leaf size of: ");
00145 print_value ("%f\n", radius);
00146
00147
00148 pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2);
00149 if (!loadCloud (argv[p_file_indices[0]], *cloud))
00150 return (-1);
00151
00152
00153 pcl::PCLPointCloud2 output;
00154 compute (cloud, output, radius);
00155
00156
00157 saveCloud (argv[p_file_indices[1]], output);
00158 }
00159