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
00039 #include <sensor_msgs/PointCloud2.h>
00040 #include <pcl/io/pcd_io.h>
00041 #include <pcl/filters/voxel_grid.h>
00042 #include <pcl/console/print.h>
00043 #include <pcl/console/parse.h>
00044 #include <pcl/console/time.h>
00045
00046 using namespace pcl;
00047 using namespace pcl::io;
00048 using namespace pcl::console;
00049
00050 float default_leaf_size = 0.01f;
00051 std::string default_field ("z");
00052 double default_filter_min = -std::numeric_limits<double>::max ();
00053 double default_filter_max = std::numeric_limits<double>::max ();
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 (" -leaf x,y,z = the VoxelGrid leaf size (default: ");
00061 print_value ("%f, %f, %f", default_leaf_size, default_leaf_size, default_leaf_size); print_info (")\n");
00062 print_info (" -field X = filter data along this field name (default: ");
00063 print_value ("%s", default_field.c_str ()); print_info (")\n");
00064 print_info (" -fmin X = filter all data with values along the specified field smaller than this value (default: ");
00065 print_value ("-inf"); print_info (")\n");
00066 print_info (" -fmax X = filter all data with values along the specified field larger than this value (default: ");
00067 print_value ("inf"); print_info (")\n");
00068 }
00069
00070 bool
00071 loadCloud (const std::string &filename, sensor_msgs::PointCloud2 &cloud)
00072 {
00073 TicToc tt;
00074 print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00075
00076 tt.tic ();
00077 if (loadPCDFile (filename, cloud) < 0)
00078 return (false);
00079 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00080 print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00081
00082 return (true);
00083 }
00084
00085 void
00086 compute (const sensor_msgs::PointCloud2::ConstPtr &input, sensor_msgs::PointCloud2 &output,
00087 float leaf_x, float leaf_y, float leaf_z, const std::string &field, double fmin, double fmax)
00088 {
00089 TicToc tt;
00090 tt.tic ();
00091
00092 print_highlight ("Computing ");
00093
00094 VoxelGrid<sensor_msgs::PointCloud2> grid;
00095 grid.setInputCloud (input);
00096 grid.setFilterFieldName (field);
00097 grid.setFilterLimits (fmin, fmax);
00098 grid.setLeafSize (leaf_x, leaf_y, leaf_z);
00099 grid.filter (output);
00100
00101 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00102 }
00103
00104 void
00105 saveCloud (const std::string &filename, const sensor_msgs::PointCloud2 &output)
00106 {
00107 TicToc tt;
00108 tt.tic ();
00109
00110 print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00111
00112 pcl::io::savePCDFile (filename, output);
00113
00114 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00115 }
00116
00117
00118 int
00119 main (int argc, char** argv)
00120 {
00121 print_info ("Downsample a cloud using pcl::VoxelGrid. For more information, use: %s -h\n", argv[0]);
00122
00123 if (argc < 3)
00124 {
00125 printHelp (argc, argv);
00126 return (-1);
00127 }
00128
00129
00130 std::vector<int> p_file_indices;
00131 p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00132 if (p_file_indices.size () != 2)
00133 {
00134 print_error ("Need one input PCD file and one output PCD file to continue.\n");
00135 return (-1);
00136 }
00137
00138
00139 float leaf_x = default_leaf_size,
00140 leaf_y = default_leaf_size,
00141 leaf_z = default_leaf_size;
00142
00143 std::vector<double> values;
00144 parse_x_arguments (argc, argv, "-leaf", values);
00145 if (values.size () == 1)
00146 {
00147 leaf_x = static_cast<float> (values[0]);
00148 leaf_y = static_cast<float> (values[0]);
00149 leaf_z = static_cast<float> (values[0]);
00150 }
00151 else if (values.size () == 3)
00152 {
00153 leaf_x = static_cast<float> (values[0]);
00154 leaf_y = static_cast<float> (values[1]);
00155 leaf_z = static_cast<float> (values[2]);
00156 }
00157 else
00158 {
00159 print_error ("Leaf size must be specified with either 1 or 3 numbers (%zu given). ", values.size ());
00160 }
00161 print_info ("Using a leaf size of: "); print_value ("%f, %f, %f\n", leaf_x, leaf_y, leaf_z);
00162
00163 std::string field (default_field);
00164 parse_argument (argc, argv, "-field", field);
00165 double fmin = default_filter_min,
00166 fmax = default_filter_max;
00167 parse_argument (argc, argv, "-fmin", fmin);
00168 parse_argument (argc, argv, "-fmax", fmax);
00169 print_info ("Filtering data on field: "); print_value ("%s", field.c_str ()); print_info (" between: ");
00170 if (fmin == -std::numeric_limits<double>::max ())
00171 print_value ("-inf ->");
00172 else
00173 print_value ("%f ->", fmin);
00174 if (fmax == std::numeric_limits<double>::max ())
00175 print_value ("inf\n");
00176 else
00177 print_value ("%f\n", fmax);
00178
00179
00180 sensor_msgs::PointCloud2::Ptr cloud (new sensor_msgs::PointCloud2);
00181 if (!loadCloud (argv[p_file_indices[0]], *cloud))
00182 return (-1);
00183
00184
00185 sensor_msgs::PointCloud2 output;
00186 compute (cloud, output, leaf_x, leaf_y, leaf_z, field, fmin, fmax);
00187
00188
00189 saveCloud (argv[p_file_indices[1]], output);
00190 }
00191