00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023 #ifndef MESH_TO_MATRIX
00024 #define MESH_TO_MATRIX
00025
00026 #include <vcg/complex/complex.h>
00027 #include <vcg/complex/algorithms/update/topology.h>
00028 #include <vcg/complex/algorithms/update/quality.h>
00029 #include <vcg/complex/algorithms/harmonic.h>
00030
00031 using namespace std;
00032
00033 namespace vcg {
00034 namespace tri {
00035 template < typename MeshType >
00036 class MeshToMatrix
00037 {
00038
00039
00040
00041 typedef typename MeshType::FaceType FaceType;
00042 typedef typename MeshType::FaceIterator FaceIterator;
00043 typedef typename MeshType::VertexType VertexType;
00044 typedef typename MeshType::VertexIterator VertexIterator;
00045 typedef typename MeshType::CoordType CoordType;
00046 typedef typename MeshType::ScalarType ScalarType;
00047 typedef typename Eigen::Matrix<ScalarType, Eigen::Dynamic, Eigen::Dynamic> MatrixXm;
00048
00049 static void GetTriEdgeAdjacency(const MatrixXm& V,
00050 const Eigen::MatrixXi& F,
00051 Eigen::MatrixXi& EV,
00052 Eigen::MatrixXi& FE,
00053 Eigen::MatrixXi& EF)
00054 {
00055 (void)V;
00056
00057 std::vector<std::vector<int> > ETT;
00058 for(int f=0;f<F.rows();++f)
00059 for (int i=0;i<3;++i)
00060 {
00061
00062 int v1 = F(f,i);
00063 int v2 = F(f,(i+1)%3);
00064 if (v1 > v2) std::swap(v1,v2);
00065 std::vector<int> r(4);
00066 r[0] = v1; r[1] = v2;
00067 r[2] = f; r[3] = i;
00068 ETT.push_back(r);
00069 }
00070 std::sort(ETT.begin(),ETT.end());
00071
00072
00073 int En = 1;
00074 for(unsigned i=0;i<ETT.size()-1;++i)
00075 if (!((ETT[i][0] == ETT[i+1][0]) && (ETT[i][1] == ETT[i+1][1])))
00076 ++En;
00077
00078 EV = Eigen::MatrixXi::Constant((int)(En),2,-1);
00079 FE = Eigen::MatrixXi::Constant((int)(F.rows()),3,-1);
00080 EF = Eigen::MatrixXi::Constant((int)(En),2,-1);
00081 En = 0;
00082
00083 for(unsigned i=0;i<ETT.size();++i)
00084 {
00085 if (i == ETT.size()-1 ||
00086 !((ETT[i][0] == ETT[i+1][0]) && (ETT[i][1] == ETT[i+1][1]))
00087 )
00088 {
00089
00090 std::vector<int>& r1 = ETT[i];
00091 EV(En,0) = r1[0];
00092 EV(En,1) = r1[1];
00093 EF(En,0) = r1[2];
00094 FE(r1[2],r1[3]) = En;
00095 }
00096 else
00097 {
00098 std::vector<int>& r1 = ETT[i];
00099 std::vector<int>& r2 = ETT[i+1];
00100 EV(En,0) = r1[0];
00101 EV(En,1) = r1[1];
00102 EF(En,0) = r1[2];
00103 EF(En,1) = r2[2];
00104 FE(r1[2],r1[3]) = En;
00105 FE(r2[2],r2[3]) = En;
00106 ++i;
00107 }
00108 ++En;
00109 }
00110
00111
00112
00113
00114 for(unsigned i=0; i<EF.rows(); ++i)
00115 {
00116 int fid = EF(i,0);
00117 bool flip = true;
00118
00119 for (unsigned j=0; j<3; ++j)
00120 {
00121 if ((F(fid,j) == EV(i,0)) && (F(fid,(j+1)%3) == EV(i,1)))
00122 flip = false;
00123 }
00124
00125 if (flip)
00126 {
00127 int tmp = EF(i,0);
00128 EF(i,0) = EF(i,1);
00129 EF(i,1) = tmp;
00130 }
00131 }
00132 }
00133
00134 public:
00135
00136
00137 static void GetTriMeshData(const MeshType &mesh,
00138 Eigen::MatrixXi &faces,
00139 MatrixXm &vert)
00140 {
00141 tri::RequireCompactness(mesh);
00142
00143 vert=MatrixXm(mesh.VN(), 3);
00144
00145
00146 for (int i = 0; i < mesh.VN(); i++)
00147 for (int j = 0; j < 3; j++)
00148 vert(i,j) = mesh.vert[i].cP()[j];
00149
00150
00151 faces=Eigen::MatrixXi(mesh.FN(), 3);
00152
00153
00154 for (int i = 0; i < mesh.FN(); i++)
00155 for (int j = 0; j < 3; j++)
00156 faces(i,j) = (int)tri::Index(mesh,mesh.face[i].cV(j));
00157 }
00158
00159
00160 static void GetNormalData(const MeshType &mesh,
00161 MatrixXm &Nvert,
00162 MatrixXm &Nface)
00163 {
00164
00165 Nvert=MatrixXm(mesh.VN(), 3);
00166 Nface=MatrixXm(mesh.FN(), 3);
00167
00168
00169 for (int i = 0; i < mesh.VN(); i++)
00170 for (int j = 0; j < 3; j++)
00171 Nvert(i,j) = mesh.vert[i].cN()[j];
00172
00173
00174 for (int i = 0; i < mesh.FN(); i++)
00175 for (int j = 0; j < 3; j++)
00176 Nface(i,j) = mesh.face[i].cN()[j];
00177 }
00178
00179
00180 static void GetTriFFAdjacency(MeshType &mesh,
00181 Eigen::MatrixXi &FFp,
00182 Eigen::MatrixXi &FFi)
00183 {
00184 tri::UpdateTopology<MeshType>::FaceFace(mesh);
00185 FFp = Eigen::MatrixXi(mesh.FN(),3);
00186 FFi = Eigen::MatrixXi(mesh.FN(),3);
00187
00188 for (int i = 0; i < mesh.FN(); i++)
00189 for (int j = 0; j < 3; j++)
00190 {
00191 FaceType *AdjF=mesh.face[i].FFp(j);
00192 if (AdjF==&mesh.face[i])
00193 {
00194 FFp(i,j)=-1;
00195 FFi(i,j)=-1;
00196 }
00197 else
00198 {
00199 FFp(i,j)=tri::Index(mesh,AdjF);
00200 FFi(i,j)=mesh.face[i].FFi(j);
00201 }
00202 }
00203 }
00204
00205
00206 static void GetTriEdgeAdjacency(const MeshType &mesh,
00207 Eigen::MatrixXi& EV,
00208 Eigen::MatrixXi& FE,
00209 Eigen::MatrixXi& EF)
00210 {
00211 Eigen::MatrixXi faces;
00212 MatrixXm vert;
00213 GetTriMeshData(mesh,faces,vert);
00214 GetTriEdgeAdjacency(vert,faces,EV,FE,EF);
00215 }
00216
00217 static Eigen::Vector3d VectorFromCoord(CoordType v)
00218 {
00219 Eigen::Vector3d ret(v[0],v[1],v[2]);
00220 return ret;
00221 }
00222
00223 template< class VecType >
00224 static void PerVertexArea(MeshType &m, VecType &h)
00225 {
00226 tri::RequireCompactness(m);
00227 h.resize(m.vn);
00228 for(int i=0;i<m.vn;++i) h[i]=0;
00229 for(FaceIterator fi=m.face.begin(); fi!=m.face.end();++fi)
00230 {
00231 ScalarType a = DoubleArea(*fi)/6.0;
00232 for(int j=0;j<fi->VN();++j)
00233 h[tri::Index(m,fi->V(j))] += a;
00234 }
00235 }
00236
00237 template< class VecType >
00238 static void PerFaceArea(MeshType &m, VecType &h)
00239 {
00240 tri::RequireCompactness(m);
00241 h.resize(m.fn);
00242 for(int i=0;i<m.fn;++i)
00243 h[i] =DoubleArea(m.face[i])/2.0;
00244 }
00245
00246
00247 static void MassMatrixEntry(MeshType &m,
00248 std::vector<std::pair<int,int> > &index,
00249 std::vector<ScalarType> &entry,
00250 bool vertexCoord=true)
00251 {
00252 tri::RequireCompactness(m);
00253
00254 typename MeshType::template PerVertexAttributeHandle<ScalarType> h =
00255 tri::Allocator<MeshType>:: template GetPerVertexAttribute<ScalarType>(m, "area");
00256 for(int i=0;i<m.vn;++i) h[i]=0;
00257
00258 for(FaceIterator fi=m.face.begin(); fi!=m.face.end();++fi)
00259 {
00260 ScalarType a = DoubleArea(*fi);
00261 for(int j=0;j<fi->VN();++j)
00262 h[tri::Index(m,fi->V(j))] += a;
00263 }
00264 ScalarType maxA=0;
00265 for(int i=0;i<m.vn;++i)
00266 maxA = max(maxA,h[i]);
00267
00268
00269 for (size_t i=0;i<m.vert.size();i++)
00270 {
00271 if (vertexCoord)
00272 {
00273 for (size_t j=0;j<3;j++)
00274 {
00275 int currI=(i*3)+j;
00276 index.push_back(std::pair<int,int>(currI,currI));
00277 entry.push_back(h[i]/maxA);
00278 }
00279 }
00280 else
00281 {
00282 int currI=i;
00283 index.push_back(std::pair<int,int>(currI,currI));
00284 entry.push_back(h[i]/maxA);
00285 }
00286 }
00287 tri::Allocator<MeshType>::template DeletePerVertexAttribute<ScalarType>(m,h);
00288 }
00289
00290
00291 static void GetLaplacianEntry(MeshType &mesh,
00292 FaceType &f,
00293 std::vector<std::pair<int,int> > &index,
00294 std::vector<ScalarType> &entry,
00295 bool cotangent,
00296 ScalarType weight = 1,
00297 bool vertexCoord=true)
00298 {
00299 if (cotangent) vcg::tri::MeshAssert<MeshType>::OnlyTriFace(mesh);
00300
00301 for (int i=0;i<f.VN();i++)
00302 {
00303
00304 if (cotangent)
00305 {
00306 weight=Harmonic<MeshType>::template CotangentWeight<ScalarType>(f,i);
00307 }
00308
00309
00310 int indexV0=Index(mesh,f.V0(i));
00311 int indexV1=Index(mesh,f.V1(i));
00312
00313 if (vertexCoord)
00314 {
00315
00316 for (int j=0;j<3;j++)
00317 {
00318
00319 int currI0=(indexV0*3)+j;
00320 int currI1=(indexV1*3)+j;
00321
00322 index.push_back(std::pair<int,int>(currI0,currI0));
00323 entry.push_back(weight);
00324 index.push_back(std::pair<int,int>(currI0,currI1));
00325 entry.push_back(-weight);
00326
00327 index.push_back(std::pair<int,int>(currI1,currI1));
00328 entry.push_back(weight);
00329 index.push_back(std::pair<int,int>(currI1,currI0));
00330 entry.push_back(-weight);
00331 }
00332 }
00333 else
00334 {
00335 int currI0=(indexV0);
00336 int currI1=(indexV1);
00337
00338 index.push_back(std::pair<int,int>(currI0,currI0));
00339 entry.push_back(weight);
00340 index.push_back(std::pair<int,int>(currI0,currI1));
00341 entry.push_back(-weight);
00342
00343 index.push_back(std::pair<int,int>(currI1,currI1));
00344 entry.push_back(weight);
00345 index.push_back(std::pair<int,int>(currI1,currI0));
00346 entry.push_back(-weight);
00347 }
00348 }
00349 }
00350
00351
00352 static void GetLaplacianMatrix(MeshType &mesh,
00353 std::vector<std::pair<int,int> > &index,
00354 std::vector<ScalarType> &entry,
00355 bool cotangent,
00356 ScalarType weight = 1,
00357 bool vertexCoord=true )
00358 {
00359
00360 for (size_t i=0;i<mesh.face.size();i++)
00361 GetLaplacianEntry(mesh,mesh.face[i],index,entry,cotangent,weight,vertexCoord);
00362 }
00363
00364
00365
00366 };
00367
00368 }
00369 }
00370 #endif // MESH_TO_MATRIX_CONVERTER