#include <tangent_field_operators.h>
Static Public Member Functions | |
static void | AdjustDirectionsOnTangentspace (MeshType &mesh) |
static void | AnglesToCrossField (FaceType &f, const ScalarType &alpha1, const ScalarType &alpha2, int RefEdge=1) |
transform a cross field into a couple of angles | |
static void | CrossFieldToAngles (const FaceType &f, ScalarType &alpha1, ScalarType &alpha2, int RefEdge=1) |
transform a cross field into a couple of angles | |
static vcg::Point2< ScalarType > | CrossToUV (FaceType &f, int numD=0) |
transform curvature to UV space | |
static void | CrossVector (const CoordType &dir0, const CoordType &norm, CoordType axis[4]) |
static void | CrossVector (const FaceType &f, CoordType axis[4]) |
static void | CrossVector (const VertexType &v, CoordType axis[4]) |
static CoordType | CrossVector (const FaceType &f, const int &index) |
static CoordType | CrossVector (const VertexType &v, const int &index) |
static FaceType::ScalarType | DifferenceCrossField (const typename FaceType::CoordType &t0, const typename FaceType::CoordType &t1, const typename FaceType::CoordType &n) |
return the difference of two cross field, values between [0,0.5] | |
static FaceType::ScalarType | DifferenceCrossField (const typename vcg::Point2< ScalarType > &t0, const typename vcg::Point2< ScalarType > &t1) |
return the difference of two cross field, values between [0,0.5] | |
static size_t | FindSeparatrices (const typename vcg::face::Pos< FaceType > &vPos, std::vector< CoordType > &directions, std::vector< FaceType * > &faces, std::vector< TriangleType > &WrongTris, int expVal=-1, int numSub=3) |
static CoordType | FollowDirection (const FaceType &f0, const FaceType &f1, const CoordType &dir0) |
static int | FollowDirection (const FaceType &f0, const FaceType &f1, int dir0) |
static int | FollowDirectionI (const FaceType &f0, const FaceType &f1, const CoordType &dir0) |
static int | FollowLineDirection (const FaceType &f0, const FaceType &f1, int dir) |
static void | GradientToCross (const FaceType &f, const vcg::Point2< ScalarType > &UV0, const vcg::Point2< ScalarType > &UV1, const vcg::Point2< ScalarType > &UV2, CoordType &dirU, CoordType &dirV) |
static int | I_K_PI (const CoordType &a, const CoordType &b, const CoordType &n) |
a and b should be in the same plane orthogonal to N | |
static void | InitDirFromWEdgeUV (MeshType &mesh) |
static CoordType | InterpolateCrossField (const CoordType &t0, const CoordType &t1, const CoordType &t2, const CoordType &n0, const CoordType &n1, const CoordType &n2, const CoordType &target_n, const CoordType &bary) |
interpolate cross field with barycentric coordinates | |
static CoordType | InterpolateCrossField (const std::vector< CoordType > &TangVect, const std::vector< ScalarType > &Weight, const std::vector< CoordType > &Norms, const CoordType &BaseNorm) |
interpolate cross field with barycentric coordinates using normalized weights | |
static FaceType::CoordType | InterpolateCrossFieldLine (const typename FaceType::CoordType &t0, const typename FaceType::CoordType &t1, const typename FaceType::CoordType &n0, const typename FaceType::CoordType &n1, const typename FaceType::CoordType &target_n, const typename FaceType::ScalarType &weight) |
interpolate cross field with scalar weight | |
static bool | IsSingularByCross (const VertexType &v, int &missmatch) |
static CoordType | K_PI (const CoordType &a, const CoordType &b, const CoordType &n) |
a and b should be in the same plane orthogonal to N | |
static void | MakeDirectionFaceCoherent (FaceType *f0, FaceType *f1) |
static void | MakeDirectionFaceCoherent (MeshType &mesh, bool normal_diff=true) |
static int | MissMatchByCross (const CoordType &dir0, const CoordType &dir1, const CoordType &N0, const CoordType &N1) |
static int | MissMatchByCross (const FaceType &f0, const FaceType &f1) |
compute the mismatch between 2 faces | |
static void | OrientDirectionFaceCoherently (MeshType &mesh) |
static CoordType | Rotate (const FaceType &f0, const FaceType &f1, const CoordType &dir3D) |
static void | SetCrossVector (FaceType &f, CoordType dir0, CoordType dir1) |
set the cross field of a given face | |
static void | SetFaceCrossVectorFromVert (FaceType &f) |
set the face cross vector from vertex one | |
static void | SetFaceCrossVectorFromVert (MeshType &mesh) |
static void | SetVertCrossVectorFromFace (VertexType &v) |
set the face cross vector from vertex one | |
static void | SetVertCrossVectorFromFace (MeshType &mesh) |
static CoordType | TangentAngleToVect (const FaceType &f, const ScalarType &angle) |
static ScalarType | TangentVectToAngle (const CoordType dirX, const CoordType dirZ, const CoordType &vect3D) |
static vcg::Matrix33< ScalarType > | TransformationMatrix (const FaceType &f) |
static void | UpdateSingularByCross (MeshType &mesh) |
select singular vertices | |
static ScalarType | VectToAngle (const FaceType &f, const CoordType &vect3D) |
find an angle with respect to the tangent frame of given face | |
Private Types | |
typedef MeshType::CoordType | CoordType |
typedef MeshType::FaceType | FaceType |
typedef vcg::face::Pos< FaceType > | PosType |
typedef MeshType::ScalarType | ScalarType |
typedef vcg::Triangle3 < ScalarType > | TriangleType |
typedef MeshType::VertexType | VertexType |
Static Private Member Functions | |
static void | FindSubDir (vcg::Triangle3< ScalarType > T3, size_t Nvert, std::vector< CoordType > &SubDEdges, int Nsub) |
static void | FindSubTriangles (const typename vcg::face::Pos< FaceType > &vPos, std::vector< TriangleType > &SubFaces, std::vector< FaceType * > &OriginalFace, int numSub=3) |
static void | InterpolateCrossSubTriangles (const std::vector< TriangleType > &SubFaces, const std::vector< FaceType * > &OriginalFace, std::vector< CoordType > &Dir, std::vector< CoordType > &NormSubF) |
static void | InterpolateDir (const CoordType &Dir0, const CoordType &Dir1, const CoordType &Sep0, const CoordType &Sep1, const TriangleType &t0, const TriangleType &t1, CoordType &Interpolated, size_t &Face) |
static void | ReduceOneDirectionField (std::vector< CoordType > &directions, std::vector< FaceType * > &faces) |
static ScalarType | Sign (ScalarType a) |
static void | SubDivideDir (const CoordType &Edge0, const CoordType &Edge1, std::vector< CoordType > &SubDEdges, int Nsub) |
static void | SubdivideTris (vcg::Triangle3< ScalarType > T3, size_t Nvert, std::vector< vcg::Triangle3< ScalarType > > &SubTris, int Nsub) |
static ScalarType | turn (const CoordType &norm, const CoordType &d0, const CoordType &d1) |
Definition at line 140 of file tangent_field_operators.h.
typedef MeshType::CoordType vcg::tri::CrossField< MeshType >::CoordType [private] |
Definition at line 144 of file tangent_field_operators.h.
typedef MeshType::FaceType vcg::tri::CrossField< MeshType >::FaceType [private] |
Definition at line 142 of file tangent_field_operators.h.
typedef vcg::face::Pos<FaceType> vcg::tri::CrossField< MeshType >::PosType [private] |
Definition at line 146 of file tangent_field_operators.h.
typedef MeshType::ScalarType vcg::tri::CrossField< MeshType >::ScalarType [private] |
Definition at line 145 of file tangent_field_operators.h.
typedef vcg::Triangle3<ScalarType> vcg::tri::CrossField< MeshType >::TriangleType [private] |
Definition at line 147 of file tangent_field_operators.h.
typedef MeshType::VertexType vcg::tri::CrossField< MeshType >::VertexType [private] |
Definition at line 143 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::AdjustDirectionsOnTangentspace | ( | MeshType & | mesh | ) | [inline, static] |
Definition at line 1340 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::AnglesToCrossField | ( | FaceType & | f, |
const ScalarType & | alpha1, | ||
const ScalarType & | alpha2, | ||
int | RefEdge = 1 |
||
) | [inline, static] |
transform a cross field into a couple of angles
Definition at line 838 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::CrossFieldToAngles | ( | const FaceType & | f, |
ScalarType & | alpha1, | ||
ScalarType & | alpha2, | ||
int | RefEdge = 1 |
||
) | [inline, static] |
transform a cross field into a couple of angles
Definition at line 813 of file tangent_field_operators.h.
static vcg::Point2<ScalarType> vcg::tri::CrossField< MeshType >::CrossToUV | ( | FaceType & | f, |
int | numD = 0 |
||
) | [inline, static] |
transform curvature to UV space
Definition at line 1444 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::CrossVector | ( | const CoordType & | dir0, |
const CoordType & | norm, | ||
CoordType | axis[4] | ||
) | [inline, static] |
return the 4 directiona of the cross field in 3D given a first direction as input
Definition at line 863 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::CrossVector | ( | const FaceType & | f, |
CoordType | axis[4] | ||
) | [inline, static] |
return the 4 direction in 3D of the cross field of a given face
Definition at line 875 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::CrossVector | ( | const VertexType & | v, |
CoordType | axis[4] | ||
) | [inline, static] |
return the 4 direction in 3D of the cross field of a given face
Definition at line 888 of file tangent_field_operators.h.
static CoordType vcg::tri::CrossField< MeshType >::CrossVector | ( | const FaceType & | f, |
const int & | index | ||
) | [inline, static] |
return a specific direction given an integer 0..3 considering the reference direction of the cross field
Definition at line 901 of file tangent_field_operators.h.
static CoordType vcg::tri::CrossField< MeshType >::CrossVector | ( | const VertexType & | v, |
const int & | index | ||
) | [inline, static] |
return a specific direction given an integer 0..3 considering the reference direction of the cross field
Definition at line 912 of file tangent_field_operators.h.
static FaceType::ScalarType vcg::tri::CrossField< MeshType >::DifferenceCrossField | ( | const typename FaceType::CoordType & | t0, |
const typename FaceType::CoordType & | t1, | ||
const typename FaceType::CoordType & | n | ||
) | [inline, static] |
return the difference of two cross field, values between [0,0.5]
Definition at line 1121 of file tangent_field_operators.h.
static FaceType::ScalarType vcg::tri::CrossField< MeshType >::DifferenceCrossField | ( | const typename vcg::Point2< ScalarType > & | t0, |
const typename vcg::Point2< ScalarType > & | t1 | ||
) | [inline, static] |
return the difference of two cross field, values between [0,0.5]
Definition at line 1132 of file tangent_field_operators.h.
static size_t vcg::tri::CrossField< MeshType >::FindSeparatrices | ( | const typename vcg::face::Pos< FaceType > & | vPos, |
std::vector< CoordType > & | directions, | ||
std::vector< FaceType * > & | faces, | ||
std::vector< TriangleType > & | WrongTris, | ||
int | expVal = -1 , |
||
int | numSub = 3 |
||
) | [inline, static] |
Definition at line 519 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::FindSubDir | ( | vcg::Triangle3< ScalarType > | T3, |
size_t | Nvert, | ||
std::vector< CoordType > & | SubDEdges, | ||
int | Nsub | ||
) | [inline, static, private] |
Definition at line 216 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::FindSubTriangles | ( | const typename vcg::face::Pos< FaceType > & | vPos, |
std::vector< TriangleType > & | SubFaces, | ||
std::vector< FaceType * > & | OriginalFace, | ||
int | numSub = 3 |
||
) | [inline, static, private] |
Definition at line 249 of file tangent_field_operators.h.
static CoordType vcg::tri::CrossField< MeshType >::FollowDirection | ( | const FaceType & | f0, |
const FaceType & | f1, | ||
const CoordType & | dir0 | ||
) | [inline, static] |
first it rotate dir to match with f1
then get the closest upf to K*PI/2 rotations
Definition at line 654 of file tangent_field_operators.h.
static int vcg::tri::CrossField< MeshType >::FollowDirection | ( | const FaceType & | f0, |
const FaceType & | f1, | ||
int | dir0 | ||
) | [inline, static] |
first it rotate dir to match with f1
then get the closest upf to K*PI/2 rotations
Definition at line 690 of file tangent_field_operators.h.
static int vcg::tri::CrossField< MeshType >::FollowDirectionI | ( | const FaceType & | f0, |
const FaceType & | f1, | ||
const CoordType & | dir0 | ||
) | [inline, static] |
first it rotate dir to match with f1
Definition at line 666 of file tangent_field_operators.h.
static int vcg::tri::CrossField< MeshType >::FollowLineDirection | ( | const FaceType & | f0, |
const FaceType & | f1, | ||
int | dir | ||
) | [inline, static] |
first it rotate dir to match with f1
then get the closest upf to K*PI/2 rotations
Definition at line 718 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::GradientToCross | ( | const FaceType & | f, |
const vcg::Point2< ScalarType > & | UV0, | ||
const vcg::Point2< ScalarType > & | UV1, | ||
const vcg::Point2< ScalarType > & | UV2, | ||
CoordType & | dirU, | ||
CoordType & | dirV | ||
) | [inline, static] |
Definition at line 1257 of file tangent_field_operators.h.
static int vcg::tri::CrossField< MeshType >::I_K_PI | ( | const CoordType & | a, |
const CoordType & | b, | ||
const CoordType & | n | ||
) | [inline, static] |
a and b should be in the same plane orthogonal to N
0 or 2
1 or 3
Definition at line 1047 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::InitDirFromWEdgeUV | ( | MeshType & | mesh | ) | [inline, static] |
Definition at line 1467 of file tangent_field_operators.h.
static CoordType vcg::tri::CrossField< MeshType >::InterpolateCrossField | ( | const CoordType & | t0, |
const CoordType & | t1, | ||
const CoordType & | t2, | ||
const CoordType & | n0, | ||
const CoordType & | n1, | ||
const CoordType & | n2, | ||
const CoordType & | target_n, | ||
const CoordType & | bary | ||
) | [inline, static] |
interpolate cross field with barycentric coordinates
Definition at line 1064 of file tangent_field_operators.h.
static CoordType vcg::tri::CrossField< MeshType >::InterpolateCrossField | ( | const std::vector< CoordType > & | TangVect, |
const std::vector< ScalarType > & | Weight, | ||
const std::vector< CoordType > & | Norms, | ||
const CoordType & | BaseNorm | ||
) | [inline, static] |
interpolate cross field with barycentric coordinates using normalized weights
Definition at line 1090 of file tangent_field_operators.h.
static FaceType::CoordType vcg::tri::CrossField< MeshType >::InterpolateCrossFieldLine | ( | const typename FaceType::CoordType & | t0, |
const typename FaceType::CoordType & | t1, | ||
const typename FaceType::CoordType & | n0, | ||
const typename FaceType::CoordType & | n1, | ||
const typename FaceType::CoordType & | target_n, | ||
const typename FaceType::ScalarType & | weight | ||
) | [inline, static] |
interpolate cross field with scalar weight
Definition at line 1101 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::InterpolateCrossSubTriangles | ( | const std::vector< TriangleType > & | SubFaces, |
const std::vector< FaceType * > & | OriginalFace, | ||
std::vector< CoordType > & | Dir, | ||
std::vector< CoordType > & | NormSubF | ||
) | [inline, static, private] |
Definition at line 289 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::InterpolateDir | ( | const CoordType & | Dir0, |
const CoordType & | Dir1, | ||
const CoordType & | Sep0, | ||
const CoordType & | Sep1, | ||
const TriangleType & | t0, | ||
const TriangleType & | t1, | ||
CoordType & | Interpolated, | ||
size_t & | Face | ||
) | [inline, static, private] |
Definition at line 385 of file tangent_field_operators.h.
static bool vcg::tri::CrossField< MeshType >::IsSingularByCross | ( | const VertexType & | v, |
int & | missmatch | ||
) | [inline, static] |
return true if a given vertex is singular, return also the missmatch
check that is on border..
Definition at line 1194 of file tangent_field_operators.h.
static CoordType vcg::tri::CrossField< MeshType >::K_PI | ( | const CoordType & | a, |
const CoordType & | b, | ||
const CoordType & | n | ||
) | [inline, static] |
a and b should be in the same plane orthogonal to N
POSSIBLE SOURCE OF BUG CHECK CROSS PRODUCT
Definition at line 1037 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::MakeDirectionFaceCoherent | ( | FaceType * | f0, |
FaceType * | f1 | ||
) | [inline, static] |
Definition at line 1324 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::MakeDirectionFaceCoherent | ( | MeshType & | mesh, |
bool | normal_diff = true |
||
) | [inline, static] |
all faces has been visited
Definition at line 1369 of file tangent_field_operators.h.
static int vcg::tri::CrossField< MeshType >::MissMatchByCross | ( | const CoordType & | dir0, |
const CoordType & | dir1, | ||
const CoordType & | N0, | ||
const CoordType & | N1 | ||
) | [inline, static] |
compute the mismatch between 2 directions each one si perpendicular to its own normal
Definition at line 1146 of file tangent_field_operators.h.
static int vcg::tri::CrossField< MeshType >::MissMatchByCross | ( | const FaceType & | f0, |
const FaceType & | f1 | ||
) | [inline, static] |
compute the mismatch between 2 faces
Definition at line 1170 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::OrientDirectionFaceCoherently | ( | MeshType & | mesh | ) | [inline, static] |
Definition at line 1358 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::ReduceOneDirectionField | ( | std::vector< CoordType > & | directions, |
std::vector< FaceType * > & | faces | ||
) | [inline, static, private] |
Definition at line 470 of file tangent_field_operators.h.
static CoordType vcg::tri::CrossField< MeshType >::Rotate | ( | const FaceType & | f0, |
const FaceType & | f1, | ||
const CoordType & | dir3D | ||
) | [inline, static] |
rotate a given vector from the tangent space of f0 to the tangent space of f1 by considering the difference of normals
find the rotation matrix that maps between normals
Definition at line 1024 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::SetCrossVector | ( | FaceType & | f, |
CoordType | dir0, | ||
CoordType | dir1 | ||
) | [inline, static] |
set the cross field of a given face
Definition at line 922 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::SetFaceCrossVectorFromVert | ( | FaceType & | f | ) | [inline, static] |
set the face cross vector from vertex one
Definition at line 931 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::SetFaceCrossVectorFromVert | ( | MeshType & | mesh | ) | [inline, static] |
Definition at line 972 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::SetVertCrossVectorFromFace | ( | VertexType & | v | ) | [inline, static] |
set the face cross vector from vertex one
find the rotation matrix that maps between normals
Definition at line 983 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::SetVertCrossVectorFromFace | ( | MeshType & | mesh | ) | [inline, static] |
Definition at line 1012 of file tangent_field_operators.h.
static ScalarType vcg::tri::CrossField< MeshType >::Sign | ( | ScalarType | a | ) | [inline, static, private] |
Definition at line 247 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::SubDivideDir | ( | const CoordType & | Edge0, |
const CoordType & | Edge1, | ||
std::vector< CoordType > & | SubDEdges, | ||
int | Nsub | ||
) | [inline, static, private] |
Definition at line 151 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::SubdivideTris | ( | vcg::Triangle3< ScalarType > | T3, |
size_t | Nvert, | ||
std::vector< vcg::Triangle3< ScalarType > > & | SubTris, | ||
int | Nsub | ||
) | [inline, static, private] |
Definition at line 231 of file tangent_field_operators.h.
static CoordType vcg::tri::CrossField< MeshType >::TangentAngleToVect | ( | const FaceType & | f, |
const ScalarType & | angle | ||
) | [inline, static] |
transform a given angle in tangent space wrt X axis of tangest space will return the sponding 3D vector
find 2D vector
then transform
Definition at line 753 of file tangent_field_operators.h.
static ScalarType vcg::tri::CrossField< MeshType >::TangentVectToAngle | ( | const CoordType | dirX, |
const CoordType | dirZ, | ||
const CoordType & | vect3D | ||
) | [inline, static] |
find an angle with respect to dirX on the plane perpendiculr to DirZ dirX and dirZ should be perpendicular
trensform the vector to the reference frame by rotating it
then put to zero to the Z coordinate
then find the angle with respact to axis 0
Definition at line 766 of file tangent_field_operators.h.
static vcg::Matrix33<ScalarType> vcg::tri::CrossField< MeshType >::TransformationMatrix | ( | const FaceType & | f | ) | [inline, static] |
fird a tranformation matrix to transform the 3D space to 2D tangent space specified by the cross field (where Z=0)
transform to 3d
Definition at line 737 of file tangent_field_operators.h.
static ScalarType vcg::tri::CrossField< MeshType >::turn | ( | const CoordType & | norm, |
const CoordType & | d0, | ||
const CoordType & | d1 | ||
) | [inline, static, private] |
Definition at line 379 of file tangent_field_operators.h.
static void vcg::tri::CrossField< MeshType >::UpdateSingularByCross | ( | MeshType & | mesh | ) | [inline, static] |
select singular vertices
Definition at line 1219 of file tangent_field_operators.h.
static ScalarType vcg::tri::CrossField< MeshType >::VectToAngle | ( | const FaceType & | f, |
const CoordType & | vect3D | ||
) | [inline, static] |
find an angle with respect to the tangent frame of given face
trensform the vector to the reference frame by rotating it
then put to zero to the Z coordinate
then find the angle with respact to axis 0
Definition at line 792 of file tangent_field_operators.h.