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/normal_3d.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
00054 Eigen::Vector4f translation;
00055 Eigen::Quaternionf orientation;
00056
00057 void
00058 printHelp (int, char **argv)
00059 {
00060 print_error ("Syntax is: %s input.pcd output.pcd <options>\n", argv[0]);
00061 print_info (" where options are:\n");
00062 print_info (" -radius X = use a radius of Xm around each point to determine the neighborhood (default: ");
00063 print_value ("%f", default_radius); print_info (")\n");
00064 print_info (" -k X = use a fixed number of X-nearest neighbors around each point (default: ");
00065 print_value ("%f", default_k); print_info (")\n");
00066 }
00067
00068 bool
00069 loadCloud (const std::string &filename, sensor_msgs::PointCloud2 &cloud)
00070 {
00071 TicToc tt;
00072 print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00073
00074 tt.tic ();
00075 if (loadPCDFile (filename, cloud, translation, orientation) < 0)
00076 return (false);
00077 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00078 print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00079
00080 return (true);
00081 }
00082
00083 void
00084 compute (const sensor_msgs::PointCloud2::ConstPtr &input, sensor_msgs::PointCloud2 &output,
00085 int k, double radius)
00086 {
00087
00088 PointCloud<PointXYZ>::Ptr xyz (new PointCloud<PointXYZ>);
00089 fromROSMsg (*input, *xyz);
00090
00091
00092 TicToc tt;
00093 tt.tic ();
00094
00095 print_highlight (stderr, "Computing ");
00096
00097 NormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
00098 ne.setInputCloud (xyz);
00099
00100 ne.setKSearch (k);
00101 ne.setRadiusSearch (radius);
00102
00103 PointCloud<Normal> normals;
00104 ne.compute (normals);
00105
00106 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", normals.width * normals.height); print_info (" points]\n");
00107
00108
00109 sensor_msgs::PointCloud2 output_normals;
00110 toROSMsg (normals, output_normals);
00111 concatenateFields (*input, output_normals, output);
00112 }
00113
00114 void
00115 saveCloud (const std::string &filename, const sensor_msgs::PointCloud2 &output)
00116 {
00117 TicToc tt;
00118 tt.tic ();
00119
00120 print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00121
00122 pcl::io::savePCDFile (filename, output, translation, orientation, false);
00123
00124 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00125 }
00126
00127
00128 int
00129 main (int argc, char** argv)
00130 {
00131 print_info ("Estimate surface normals using pcl::NormalEstimation. For more information, use: %s -h\n", argv[0]);
00132
00133 if (argc < 3)
00134 {
00135 printHelp (argc, argv);
00136 return (-1);
00137 }
00138
00139
00140 std::vector<int> p_file_indices;
00141 p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00142 if (p_file_indices.size () != 2)
00143 {
00144 print_error ("Need one input PCD file and one output PCD file to continue.\n");
00145 return (-1);
00146 }
00147
00148
00149 int k = default_k;
00150 double radius = default_radius;
00151 parse_argument (argc, argv, "-k", k);
00152 parse_argument (argc, argv, "-radius", radius);
00153
00154
00155 sensor_msgs::PointCloud2::Ptr cloud (new sensor_msgs::PointCloud2);
00156 if (!loadCloud (argv[p_file_indices[0]], *cloud))
00157 return (-1);
00158
00159
00160 sensor_msgs::PointCloud2 output;
00161 compute (cloud, output, k, radius);
00162
00163
00164 saveCloud (argv[p_file_indices[1]], output);
00165 }
00166