Go to the documentation of this file.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 NURBS_FITTING_SPHERE_H
00039 #define NURBS_FITTING_SPHERE_H
00040
00041 #include <pcl/surface/on_nurbs/nurbs_tools.h>
00042 #include <pcl/surface/on_nurbs/nurbs_data.h>
00043 #include <pcl/surface/on_nurbs/nurbs_solve.h>
00044
00045 namespace pcl
00046 {
00047 namespace on_nurbs
00048 {
00049
00055 class FittingSphere
00056 {
00057 public:
00058
00059 ON_TextLog m_out;
00060 ON_NurbsSurface m_nurbs;
00061 NurbsDataSurface *m_data;
00062
00067 FittingSphere (int order, NurbsDataSurface *data);
00068
00072 FittingSphere (NurbsDataSurface *data, const ON_NurbsSurface &ns);
00073
00077 void
00078 assemble (double smoothness = 0.000001f);
00079
00082 void
00083 solve (double damp = 1.0);
00084
00087 void
00088 updateSurf (double damp);
00089
00093 void
00094 setInvMapParams (int in_max_steps, double invMapInt_accuracy);
00095
00096 inline void
00097 setQuiet (bool val)
00098 {
00099 m_quiet = val;
00100 m_solver.setQuiet (val);
00101 }
00102
00104 static ON_NurbsSurface
00105 initNurbsSphere (int order, NurbsDataSurface *data, Eigen::Vector3d pole_axis = Eigen::Vector3d (0.0, 0.0, 1.0));
00106
00108 static std::vector<double>
00109 getElementVector (const ON_NurbsSurface &nurbs, int dim);
00110
00124 static Eigen::Vector2d
00125 inverseMapping (const ON_NurbsSurface &nurbs, const Eigen::Vector3d &pt, const Eigen::Vector2d &hint,
00126 double &error, Eigen::Vector3d &p, Eigen::Vector3d &tu, Eigen::Vector3d &tv, int maxSteps = 100,
00127 double accuracy = 1e-6, bool quiet = true);
00128
00133 static Eigen::Vector2d
00134 findClosestElementMidPoint (const ON_NurbsSurface &nurbs, const Eigen::Vector3d &pt);
00135
00136 protected:
00137
00139 void
00140 init ();
00141
00143 void
00144 assembleInterior (double wInt, unsigned &row);
00145
00147 void
00148 addPointConstraint (const Eigen::Vector2d ¶ms, const Eigen::Vector3d &point, double weight, unsigned &row);
00149
00151 void
00152 addCageInteriorRegularisation (double weight, unsigned &row);
00153
00155 void
00156 addCageBoundaryRegularisation (double weight, int side, unsigned &row);
00157
00158 private:
00159 NurbsSolve m_solver;
00160 bool m_quiet;
00161
00162 int in_max_steps;
00163 double in_accuracy;
00164
00165
00166 int
00167 grc2gl (int I, int J)
00168 {
00169 int cp_red = (m_nurbs.m_order[1] - 2);
00170 int ncpj = (m_nurbs.m_cv_count[1] - 2 * cp_red);
00171 return ncpj * I + (J % ncpj);
00172 }
00173 int
00174 lrc2gl (int E, int F, int i, int j)
00175 {
00176 return grc2gl (E + i, F + j);
00177 }
00178 int
00179 gl2gr (int A)
00180 {
00181 return (A / m_nurbs.CVCount (1));
00182 }
00183 int
00184 gl2gc (int A)
00185 {
00186 return (A % m_nurbs.CVCount (1));
00187 }
00188
00189 };
00190
00191 }
00192 }
00193
00194 #endif