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/point_types.h>
00040 #include <pcl/io/pcd_io.h>
00041 #include <pcl/console/print.h>
00042 #include <pcl/console/parse.h>
00043 #include <pcl/console/time.h>
00044 #include <pcl/surface/mls.h>
00045 #include <pcl/filters/voxel_grid.h>
00046
00047 using namespace pcl;
00048 using namespace pcl::io;
00049 using namespace pcl::console;
00050
00051 int default_polynomial_order = 2;
00052 bool default_use_polynomial_fit = false;
00053 double default_search_radius = 0.0,
00054 default_sqr_gauss_param = 0.0;
00055
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 = sphere radius to be used for finding the k-nearest neighbors used for fitting (default: ");
00063 print_value ("%f", default_search_radius); print_info (")\n");
00064 print_info (" -sqr_gauss_param X = parameter used for the distance based weighting of neighbors (recommended = search_radius^2) (default: ");
00065 print_value ("%f", default_sqr_gauss_param); print_info (")\n");
00066 print_info (" -use_polynomial_fit X = decides whether the surface and normal are approximated using a polynomial or only via tangent estimation (default: ");
00067 print_value ("%d", default_use_polynomial_fit); print_info (")\n");
00068 print_info (" -polynomial_order X = order of the polynomial to be fit (implicitly, use_polynomial_fit = 1) (default: ");
00069 print_value ("%d", default_polynomial_order); print_info (")\n");
00070 }
00071
00072 bool
00073 loadCloud (const std::string &filename, pcl::PCLPointCloud2 &cloud)
00074 {
00075 TicToc tt;
00076 print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00077
00078 tt.tic ();
00079 if (loadPCDFile (filename, cloud) < 0)
00080 return (false);
00081 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00082 print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00083
00084 return (true);
00085 }
00086
00087 void
00088 compute (const pcl::PCLPointCloud2::ConstPtr &input, pcl::PCLPointCloud2 &output,
00089 double search_radius, bool sqr_gauss_param_set, double sqr_gauss_param,
00090 bool use_polynomial_fit, int polynomial_order)
00091 {
00092
00093 PointCloud<PointXYZ>::Ptr xyz_cloud_pre (new pcl::PointCloud<PointXYZ> ()),
00094 xyz_cloud (new pcl::PointCloud<PointXYZ> ());
00095 fromPCLPointCloud2 (*input, *xyz_cloud_pre);
00096
00097
00098 for (size_t i = 0; i < xyz_cloud_pre->size (); ++i)
00099 if (pcl_isfinite (xyz_cloud_pre->points[i].x))
00100 xyz_cloud->push_back (xyz_cloud_pre->points[i]);
00101 xyz_cloud->header = xyz_cloud_pre->header;
00102 xyz_cloud->height = 1;
00103 xyz_cloud->width = static_cast<uint32_t> (xyz_cloud->size ());
00104 xyz_cloud->is_dense = false;
00105
00106
00107
00108 PointCloud<PointNormal>::Ptr xyz_cloud_smoothed (new PointCloud<PointNormal> ());
00109
00110 MovingLeastSquares<PointXYZ, PointNormal> mls;
00111 mls.setInputCloud (xyz_cloud);
00112 mls.setSearchRadius (search_radius);
00113 if (sqr_gauss_param_set) mls.setSqrGaussParam (sqr_gauss_param);
00114 mls.setPolynomialFit (use_polynomial_fit);
00115 mls.setPolynomialOrder (polynomial_order);
00116
00117
00118
00119
00120 mls.setUpsamplingMethod (MovingLeastSquares<PointXYZ, PointNormal>::NONE);
00121 mls.setPointDensity (60000 * int (search_radius));
00122 mls.setUpsamplingRadius (0.025);
00123 mls.setUpsamplingStepSize (0.015);
00124 mls.setDilationIterations (2);
00125 mls.setDilationVoxelSize (0.01f);
00126
00127 search::KdTree<PointXYZ>::Ptr tree (new search::KdTree<PointXYZ> ());
00128 mls.setSearchMethod (tree);
00129 mls.setComputeNormals (true);
00130
00131 PCL_INFO ("Computing smoothed surface and normals with search_radius %f , sqr_gaussian_param %f, polynomial fitting %d, polynomial order %d\n",
00132 mls.getSearchRadius(), mls.getSqrGaussParam(), mls.getPolynomialFit(), mls.getPolynomialOrder());
00133 TicToc tt;
00134 tt.tic ();
00135 mls.process (*xyz_cloud_smoothed);
00136 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", xyz_cloud_smoothed->width * xyz_cloud_smoothed->height); print_info (" points]\n");
00137
00138 toPCLPointCloud2 (*xyz_cloud_smoothed, output);
00139 }
00140
00141 void
00142 saveCloud (const std::string &filename, const pcl::PCLPointCloud2 &output)
00143 {
00144 TicToc tt;
00145 tt.tic ();
00146
00147 print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00148
00149 pcl::io::savePCDFile (filename, output, Eigen::Vector4f::Zero (),
00150 Eigen::Quaternionf::Identity (), true);
00151
00152 print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00153 }
00154
00155
00156 int
00157 main (int argc, char** argv)
00158 {
00159 print_info ("Moving Least Squares smoothing of a point cloud. For more information, use: %s -h\n", argv[0]);
00160
00161 if (argc < 3)
00162 {
00163 printHelp (argc, argv);
00164 return (-1);
00165 }
00166
00167
00168 std::vector<int> p_file_indices;
00169 p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00170 if (p_file_indices.size () != 2)
00171 {
00172 print_error ("Need one input PCD file and one output PCD file to continue.\n");
00173 return (-1);
00174 }
00175
00176
00177 double search_radius = default_search_radius;
00178 double sqr_gauss_param = default_sqr_gauss_param;
00179 bool sqr_gauss_param_set = true;
00180 int polynomial_order = default_polynomial_order;
00181 bool use_polynomial_fit = default_use_polynomial_fit;
00182
00183 parse_argument (argc, argv, "-radius", search_radius);
00184 if (parse_argument (argc, argv, "-sqr_gauss_param", sqr_gauss_param) == -1)
00185 sqr_gauss_param_set = false;
00186 if (parse_argument (argc, argv, "-polynomial_order", polynomial_order) != -1 )
00187 use_polynomial_fit = true;
00188 parse_argument (argc, argv, "-use_polynomial_fit", use_polynomial_fit);
00189
00190
00191 pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2);
00192 if (!loadCloud (argv[p_file_indices[0]], *cloud))
00193 return (-1);
00194
00195
00196 pcl::PCLPointCloud2 output;
00197 compute (cloud, output, search_radius, sqr_gauss_param_set, sqr_gauss_param,
00198 use_polynomial_fit, polynomial_order);
00199
00200
00201 saveCloud (argv[p_file_indices[1]], output);
00202 }