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
00040 #include <sensor_msgs/PointCloud2.h>
00041 #include <pcl/io/pcd_io.h>
00042 #include <pcl/features/boundary.h>
00043 #include <pcl/console/print.h>
00044 #include <pcl/console/parse.h>
00045 #include <pcl/console/time.h>
00046
00047 using namespace pcl;
00048 using namespace pcl::io;
00049 using namespace pcl::console;
00050
00051 int default_k = 0;
00052 double default_radius = 0.0;
00053 double default_angle = M_PI/2.0;
00054
00055 Eigen::Vector4f translation;
00056 Eigen::Quaternionf orientation;
00057
00058 void
00059 printHelp (int, char **argv)
00060 {
00061 print_error ("Syntax is: %s input.pcd output.pcd <options>\n", argv[0]);
00062 print_info (" where options are:\n");
00063 print_info (" -radius X = use a radius of Xm around each point to determine the neighborhood (default: ");
00064 print_value ("%f", default_radius); print_info (")\n");
00065 print_info (" -k X = use a fixed number of X-nearest neighbors around each point (default: ");
00066 print_value ("%d", default_k); print_info (")\n");
00067 print_info (" -thresh X = the decision boundary (angle threshold) that marks points as boundary or regular (default: ");
00068 print_value ("%f", default_angle); print_info (")\n");
00069 }
00070
00071 bool
00072 loadCloud (const std::string &filename, sensor_msgs::PointCloud2 &cloud)
00073 {
00074 TicToc tt;
00075 print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00076
00077 tt.tic ();
00078 if (loadPCDFile (filename, cloud, translation, orientation) < 0)
00079 return (false);
00080 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00081 print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00082
00083
00084 if (pcl::getFieldIndex (cloud, "normal_x") == -1)
00085 {
00086 print_error ("The input dataset does not contain normal information!\n");
00087 return (false);
00088 }
00089 return (true);
00090 }
00091
00092 void
00093 compute (const sensor_msgs::PointCloud2::ConstPtr &input, sensor_msgs::PointCloud2 &output,
00094 int k, double radius, double angle)
00095 {
00096
00097 PointCloud<PointNormal>::Ptr xyznormals (new PointCloud<PointNormal>);
00098 fromROSMsg (*input, *xyznormals);
00099
00100
00101 TicToc tt;
00102 tt.tic ();
00103
00104 print_highlight (stderr, "Computing ");
00105
00106 BoundaryEstimation<pcl::PointNormal, pcl::PointNormal, pcl::Boundary> ne;
00107 ne.setInputCloud (xyznormals);
00108 ne.setInputNormals (xyznormals);
00109
00110 ne.setKSearch (k);
00111 ne.setAngleThreshold (static_cast<float> (angle));
00112 ne.setRadiusSearch (radius);
00113
00114 PointCloud<Boundary> boundaries;
00115 ne.compute (boundaries);
00116
00117 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", boundaries.width * boundaries.height); print_info (" points]\n");
00118
00119
00120 sensor_msgs::PointCloud2 output_boundaries;
00121 toROSMsg (boundaries, output_boundaries);
00122 concatenateFields (*input, output_boundaries, output);
00123 }
00124
00125 void
00126 saveCloud (const std::string &filename, const sensor_msgs::PointCloud2 &output)
00127 {
00128 TicToc tt;
00129 tt.tic ();
00130
00131 print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00132
00133 pcl::io::savePCDFile (filename, output, translation, orientation, false);
00134
00135 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00136 }
00137
00138
00139 int
00140 main (int argc, char** argv)
00141 {
00142 print_info ("Estimate boundary points using pcl::BoundaryEstimation. For more information, use: %s -h\n", argv[0]);
00143 bool help = false;
00144 parse_argument (argc, argv, "-h", help);
00145 if (argc < 3 || help)
00146 {
00147 printHelp (argc, argv);
00148 return (-1);
00149 }
00150
00151
00152 std::vector<int> p_file_indices;
00153 p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00154 if (p_file_indices.size () != 2)
00155 {
00156 print_error ("Need one input PCD file and one output PCD file to continue.\n");
00157 return (-1);
00158 }
00159
00160
00161 int k = default_k;
00162 double radius = default_radius;
00163 double angle = default_angle;
00164 parse_argument (argc, argv, "-k", k);
00165 parse_argument (argc, argv, "-radius", radius);
00166 parse_argument (argc, argv, "-thresh", angle);
00167
00168
00169 sensor_msgs::PointCloud2::Ptr cloud (new sensor_msgs::PointCloud2);
00170 if (!loadCloud (argv[p_file_indices[0]], *cloud))
00171 return (-1);
00172
00173
00174 sensor_msgs::PointCloud2 output;
00175 compute (cloud, output, k, radius, angle);
00176
00177
00178 saveCloud (argv[p_file_indices[1]], output);
00179 }
00180