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 #ifndef CLOSING_BOUNDARY_H
00039 #define CLOSING_BOUNDARY_H
00040
00041 #include <pcl/surface/on_nurbs/nurbs_data.h>
00042 #include <pcl/surface/on_nurbs/nurbs_tools.h>
00043 #include <pcl/surface/on_nurbs/fitting_surface_pdm.h>
00044
00045 namespace pcl
00046 {
00047 namespace on_nurbs
00048 {
00049
00053 class ClosingBoundary
00054 {
00055 public:
00056 enum Type
00057 {
00058 COMMON_BOUNDARY_POINT_MEAN, COMMON_BOUNDARY_POINT_TANGENTS, COMMON_BOUNDARY_POINT_PLANES,
00059 CLOSEST_POINTS_BOUNDARY, CLOSEST_POINTS_INTERIOR,
00060 };
00061
00062 struct Parameter
00063 {
00064 double max_dist;
00065 double max_error;
00066 unsigned samples;
00067 unsigned com_iter;
00068 unsigned fit_iter;
00069 double accuracy;
00070 double smoothness;
00071 double boundary_weight;
00072 double interior_weight;
00073 Type type;
00074
00075 Parameter (double _max_dist = 0.02, double _max_error = 0.02, unsigned _samples = 10, unsigned _iter = 10,
00076 unsigned _fit_iter = 10, double _accuracy = 1e-3, double _smooth = 0.00001,
00077 double _bnd_weight = 1.0, double _int_weight = 1.0, Type _type = COMMON_BOUNDARY_POINT_MEAN) :
00078 max_dist (_max_dist), max_error (_max_error), samples (_samples), com_iter (_iter), fit_iter (_fit_iter),
00079 accuracy (_accuracy), smoothness (_smooth), boundary_weight (_bnd_weight),
00080 interior_weight (_int_weight), type (_type)
00081 {
00082 }
00083
00084 };
00085
00088 static double
00089 getLineDistance (const Eigen::Vector3d &P0, const Eigen::Vector3d &u, const Eigen::Vector3d &Q0,
00090 const Eigen::Vector3d &v, Eigen::Vector3d &P, Eigen::Vector3d &Q);
00091
00093 static Eigen::Vector3d
00094 intersectPlanes (const Eigen::Vector3d &N1, double d1, const Eigen::Vector3d &N2, double d2,
00095 const Eigen::Vector3d &N3, double d3);
00096
00099 static Eigen::Vector3d
00100 commonBoundaryPoint1 (ON_NurbsSurface &n1, ON_NurbsSurface &n2, Eigen::Vector2d ¶ms1,
00101 Eigen::Vector2d ¶ms2, const Eigen::Vector3d &start, unsigned nsteps, double &error,
00102 double accuracy);
00103
00106 static Eigen::Vector3d
00107 commonBoundaryPoint2 (ON_NurbsSurface &n1, ON_NurbsSurface &n2, Eigen::Vector2d ¶ms1,
00108 Eigen::Vector2d ¶ms2, const Eigen::Vector3d &start, unsigned nsteps, double &error,
00109 double accuracy);
00110
00113 static Eigen::Vector3d
00114 commonBoundaryPoint3 (ON_NurbsSurface &n1, ON_NurbsSurface &n2, Eigen::Vector2d ¶ms1,
00115 Eigen::Vector2d ¶ms2, const Eigen::Vector3d &start, unsigned nsteps, double &error,
00116 double accuracy);
00117
00119 static void
00120 sampleUniform (ON_NurbsSurface *nurbs, vector_vec3d &point_list, unsigned samples);
00121
00123 static void
00124 sampleRandom (ON_NurbsSurface *nurbs, vector_vec3d &point_list, unsigned samples);
00125
00127 static void
00128 sampleFromBoundary (ON_NurbsSurface *nurbs, vector_vec3d &point_list, vector_vec2d ¶m_list, unsigned samples);
00129
00132 static void
00133 optimizeBoundary (std::vector<ON_NurbsSurface> &nurbs_list, std::vector<NurbsDataSurface> &data_list,
00134 Parameter param);
00135
00136
00137
00138
00139
00140 };
00141
00142 }
00143 }
00144
00145 #endif