Go to the documentation of this file.00001 #include <pcl/point_cloud.h>
00002 #include <pcl/point_types.h>
00003 #include <pcl/common/io.h>
00004
00005 #include <pcl/visualization/pcl_visualizer.h>
00006 #include <pcl/surface/on_nurbs/fitting_surface_tdm.h>
00007 #include <pcl/surface/on_nurbs/triangulation.h>
00008
00009 typedef pcl::PointXYZ Point;
00010
00011 void
00012 CreateCylinderPoints (pcl::PointCloud<Point>::Ptr cloud, pcl::on_nurbs::vector_vec3d &data, unsigned npoints,
00013 double alpha, double h, double r)
00014 {
00015 for (unsigned i = 0; i < npoints; i++)
00016 {
00017 double da = alpha * double (rand ()) / RAND_MAX;
00018 double dh = h * (double (rand ()) / RAND_MAX - 0.5);
00019
00020 Point p;
00021 p.x = float (r * cos (da));
00022 p.y = float (r * sin (da));
00023 p.z = float (dh);
00024
00025 data.push_back (Eigen::Vector3d (p.x, p.y, p.z));
00026 cloud->push_back (p);
00027 }
00028 }
00029
00030 int
00031 main ()
00032 {
00033 unsigned npoints (200);
00034 unsigned refinement (2);
00035 unsigned iterations (10);
00036
00037 pcl::visualization::PCLVisualizer viewer ("Test: NURBS surface fitting");
00038 viewer.setSize (800, 600);
00039
00040
00041 pcl::PointCloud<Point>::Ptr cloud (new pcl::PointCloud<Point>);
00042 pcl::on_nurbs::NurbsDataSurface data;
00043 CreateCylinderPoints (cloud, data.interior, npoints, M_PI, 1.0, 0.5);
00044 viewer.addPointCloud<Point> (cloud, "cloud_cylinder");
00045
00046
00047 ON_NurbsSurface nurbs = pcl::on_nurbs::FittingSurface::initNurbsPCABoundingBox (3, &data);
00048 pcl::on_nurbs::FittingSurface fit (&data, nurbs);
00049
00050
00051 pcl::on_nurbs::FittingSurface::Parameter params;
00052 params.interior_smoothness = 0.1;
00053 params.interior_weight = 1.0;
00054 params.boundary_smoothness = 0.1;
00055 params.boundary_weight = 0.0;
00056
00057
00058 for (unsigned i = 0; i < refinement; i++)
00059 {
00060 fit.refine (0);
00061 fit.refine (1);
00062 }
00063
00064
00065 for (unsigned i = 0; i < iterations; i++)
00066 {
00067 fit.assemble (params);
00068 fit.solve ();
00069 }
00070
00071
00072 nurbs = fit.m_nurbs;
00073 pcl::PolygonMesh mesh;
00074 std::string mesh_id = "mesh_nurbs";
00075 pcl::on_nurbs::Triangulation::convertSurface2PolygonMesh (nurbs, mesh, 128);
00076 viewer.addPolygonMesh (mesh, mesh_id);
00077
00078 viewer.spin ();
00079 return 0;
00080 }