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/filters/crop_hull.h>
00039 #include <pcl/io/pcd_io.h>
00040 #include <pcl/console/print.h>
00041 #include <pcl/console/parse.h>
00042 #include <pcl/console/time.h>
00043 #include <pcl/surface/concave_hull.h>
00044
00045
00046
00047 using namespace pcl;
00048 using namespace pcl::io;
00049 using namespace pcl::console;
00050
00051 typedef PointXYZ PointT;
00052 typedef PointCloud<PointT> CloudT;
00053
00054 const static double default_alpha = 1e3f;
00055
00056 static void
00057 printHelp (int, char **argv)
00058 {
00059 print_error ("Syntax is: %s hull_cloud.pcd input.pcd output.pcd <options>\n", argv[0]);
00060 print_info (" where options are:\n");
00061 print_info (" -alpha X = the hull alpha value (0+) (default: ");
00062 print_value ("%f", default_alpha);
00063 print_info (")\n");
00064 }
00065
00066 static bool
00067 loadCloud (std::string const& filename, CloudT &cloud)
00068 {
00069 TicToc tt;
00070 print_highlight ("Loading ");
00071 print_value ("%s ", filename.c_str ());
00072
00073 tt.tic ();
00074 if (loadPCDFile (filename, cloud) < 0)
00075 return (false);
00076
00077 print_info ("[done, ");
00078 print_value ("%g", tt.toc ());
00079 print_info (" ms : ");
00080 print_value ("%d", cloud.width * cloud.height);
00081 print_info (" points]\n");
00082 print_info ("Available dimensions: ");
00083 print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00084
00085 return (true);
00086 }
00087
00088 static void
00089 saveCloud (std::string const& filename, CloudT const& cloud)
00090 {
00091 TicToc tt;
00092 tt.tic ();
00093
00094 print_highlight ("Saving ");
00095 print_value ("%s ", filename.c_str ());
00096
00097 pcl::io::savePCDFile (filename, cloud);
00098
00099 print_info ("[done, ");
00100 print_value ("%g", tt.toc ());
00101 print_info (" ms : ");
00102 print_value ("%d", cloud.width * cloud.height);
00103 print_info (" points]\n");
00104 }
00105
00106 static void
00107 cropToHull (CloudT::Ptr output, CloudT::Ptr input, CloudT::Ptr hull_cloud, std::vector<pcl::Vertices> const& polygons, int dim)
00108 {
00109 TicToc tt;
00110 tt.tic ();
00111
00112 print_highlight ("Cropping ");
00113
00114 CropHull<PointT> crop_filter;
00115 crop_filter.setInputCloud (input);
00116 crop_filter.setHullCloud (hull_cloud);
00117 crop_filter.setHullIndices (polygons);
00118 crop_filter.setDim (dim);
00119
00120 crop_filter.filter (*output);
00121
00122 print_info ("[done, ");
00123 print_value ("%g", tt.toc ());
00124 print_info (" ms : ");
00125 print_value ("%d", output->size());
00126 print_info (" points passed crop]\n");
00127 }
00128
00129 static CloudT::Ptr
00130 calculateHull (std::vector<pcl::Vertices>& polygons, int& dim, CloudT::Ptr cloud, double alpha)
00131 {
00132 pcl::ConcaveHull<PointT> hull_calculator;
00133 CloudT::Ptr hull (new CloudT);
00134 hull_calculator.setInputCloud (cloud);
00135 hull_calculator.setAlpha (alpha);
00136 hull_calculator.reconstruct (*hull, polygons);
00137
00138 dim = hull_calculator.getDim();
00139 return hull;
00140 }
00141
00142 int
00143 main (int argc, char** argv)
00144 {
00145 print_info ("Filter a point cloud using the convex hull of another point "
00146 "cloud. For more information, use: %s -h\n", argv[0]);
00147
00148 if (argc < 4)
00149 {
00150 printHelp (argc, argv);
00151 return (-1);
00152 }
00153
00154
00155 std::vector<int> p_file_indices;
00156 p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00157 if (p_file_indices.size () != 3)
00158 {
00159 print_error ("Need at least three pcd files to continue.\n");
00160 return (-1);
00161 }
00162
00163
00164 double alpha = default_alpha;
00165 parse_argument (argc, argv, "-alpha", alpha);
00166
00167 CloudT::Ptr hull_cloud (new CloudT);
00168 CloudT::Ptr hull_points (new CloudT);
00169 CloudT::Ptr input_cloud (new CloudT);
00170 CloudT::Ptr output_cloud (new CloudT);
00171 std::vector<pcl::Vertices> hull_polygons;
00172 int dim = 0;
00173
00174 if (!loadCloud (argv[p_file_indices[0]], *hull_cloud))
00175 return (-1);
00176
00177 if (!loadCloud (argv[p_file_indices[1]], *input_cloud))
00178 return (-1);
00179
00180 hull_points = calculateHull (hull_polygons, dim, hull_cloud, alpha);
00181
00182 cropToHull (output_cloud, input_cloud, hull_points, hull_polygons, dim);
00183
00184
00185
00186
00187
00188
00189
00190
00191
00192
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202 if (output_cloud->size ())
00203 saveCloud (argv[p_file_indices[2]], *output_cloud);
00204 else
00205 print_error ("No points passed crop.\n");
00206 }
00207
00208