Space

Classes

class  vcg::Box< N, S >
class  vcg::Box2< BoxScalarType >
class  vcg::Box3< BoxScalarType >
class  vcg::Color4< T >
class  vcg::ColorSpace< T >
class  vcg::Line2< LineScalarType, NORM >
class  vcg::Line3< LineScalarType, NORM >
class  vcg::Plane3< T, NORM >
class  vcg::ndim::Point< N, S >
class  vcg::Point2< P2ScalarType >
class  vcg::ndim::Point2< S >
class  vcg::Point3< P3ScalarType >
class  vcg::ndim::Point3< S >
class  vcg::Point4< T >
class  vcg::ndim::Point4< S >
class  vcg::Ray2< RayScalarType, NORM >
class  vcg::Ray3< RayScalarType, NORM >
class  vcg::RayTriangleIntersectionFunctor< BACKFACETEST >
class  vcg::Segment2< SegmentScalarType >
class  vcg::Segment3< SegmentScalarType >
struct  vcg::SmallestEnclosing
class  vcg::Sphere3< T >
class  vcg::Tetra
class  vcg::Tetra3< ScalarType >
class  vcg::TexCoord2< T, NMAX >
class  vcg::TexCoord2Simple< T >
class  vcg::Triangle2< SCALAR_TYPE >
class  vcg::Triangle3< ScalarTriangleType >

Defines

#define ADD(dest, v1, v2)   dest[0]=v1[0]+v2[0]; dest[1]=v1[1]+v2[1]; dest[2]=v1[2]+v2[2];
#define COMPUTE_INTERVALS_ISECTLINE(VERT0, VERT1, VERT2, VV0, VV1, VV2, D0, D1, D2, D0D1, D0D2, isect0, isect1, isectpoint0, isectpoint1)
#define CROSS(dest, v1, v2)
#define DOT(v1, v2)   (v1[0]*v2[0]+v1[1]*v2[1]+v1[2]*v2[2])
#define DOT(v1, v2)   (v1[0]*v2[0]+v1[1]*v2[1]+v1[2]*v2[2])
#define EDGE_AGAINST_TRI_EDGES(V0, V1, U0, U1, U2)
#define EDGE_EDGE_TEST(V0, U0, U1)
#define FABS(x)   (T(fabs(x)))
#define MULT(dest, v, factor)   dest[0]=factor*v[0]; dest[1]=factor*v[1]; dest[2]=factor*v[2];
#define NEWCOMPUTE_INTERVALS(VV0, VV1, VV2, D0, D1, D2, D0D1, D0D2, A, B, C, X0, X1)
#define POINT_IN_TRI(V0, U0, U1, U2)
#define SET(dest, src)   dest[0]=src[0]; dest[1]=src[1]; dest[2]=src[2];
#define SORT(a, b)
#define SORT2(a, b, smallest)
#define SUB(dest, v1, v2)
#define TRI_TRI_INT_EPSILON   0.000001
#define USE_EPSILON_TEST

Typedefs

typedef Box< 2, double > vcg::Box2d
 Specificazione di box of double.
typedef Box< 2, float > vcg::Box2f
 Specificazione di box of float.
typedef Box< 2, int > vcg::Box2i
 Specificazione di box of int.
typedef Box< 2, short > vcg::Box2s
 Specificazione di box of short.
typedef Box< 3, double > vcg::Box3d
typedef Box< 3, float > vcg::Box3f
typedef Box< 3, int > vcg::Box3i
typedef Box< 3, short > vcg::Box3s
typedef Box3< ScalarTypevcg::Triangle3::BoxType
 The bounding box type.
typedef Color4< unsigned char > vcg::Color4b
typedef Color4< double > vcg::Color4d
typedef Color4< float > vcg::Color4f
typedef Point3< ScalarTypevcg::Triangle3::CoordType
typedef Point2< ScalarTypevcg::Triangle2::CoordType
typedef Line2< double > vcg::Line2d
typedef Line2< double, true > vcg::Line2dN
typedef Line2< float > vcg::Line2f
typedef Line2< float,true > vcg::Line2fN
typedef Line2< int > vcg::Line2i
typedef Line2< int,true > vcg::Line2iN
typedef Line2< short > vcg::Line2s
typedef Line2< short,true > vcg::Line2sN
typedef Line3< double > vcg::Line3d
typedef Line3< double, true > vcg::Line3dN
typedef Line3< float > vcg::Line3f
typedef Line3< float,true > vcg::Line3fN
typedef Line3< int > vcg::Line3i
typedef Line3< int,true > vcg::Line3iN
typedef Line3< short > vcg::Line3s
typedef Line3< short,true > vcg::Line3sN
typedef Plane3< double > vcg::Plane3d
typedef Plane3< float > vcg::Plane3f
typedef Point2< double > vcg::Point2d
typedef Point2< double > vcg::ndim::Point2d
typedef Point2< float > vcg::Point2f
typedef Point2< float > vcg::ndim::Point2f
typedef Point2< int > vcg::Point2i
typedef Point2< int > vcg::ndim::Point2i
typedef Point2< short > vcg::Point2s
typedef Point2< short > vcg::ndim::Point2s
typedef Point3< double > vcg::Point3d
typedef Point3< double > vcg::ndim::Point3d
typedef Point3< float > vcg::Point3f
typedef Point3< float > vcg::ndim::Point3f
typedef Point3< int > vcg::Point3i
typedef Point3< int > vcg::ndim::Point3i
typedef Point3< short > vcg::Point3s
typedef Point3< short > vcg::ndim::Point3s
typedef Point4< double > vcg::Point4d
typedef Point4< double > vcg::ndim::Point4d
typedef Point4< float > vcg::Point4f
typedef Point4< float > vcg::ndim::Point4f
typedef Point4< int > vcg::Point4i
typedef Point4< int > vcg::ndim::Point4i
typedef Point4< short > vcg::Point4s
typedef Point4< short > vcg::ndim::Point4s
typedef Point3< T > vcg::Plane3::PointType
typedef Ray2< double > vcg::Ray2d
typedef Ray2< double, true > vcg::Ray2dN
typedef Ray2< float > vcg::Ray2f
typedef Ray2< float,true > vcg::Ray2fN
typedef Ray2< int > vcg::Ray2i
typedef Ray2< int,true > vcg::Ray2iN
typedef Ray2< short > vcg::Ray2s
typedef Ray2< short,true > vcg::Ray2sN
typedef Ray3< double > vcg::Ray3d
typedef Ray3< double, true > vcg::Ray3dN
typedef Ray3< float > vcg::Ray3f
typedef Ray3< float,true > vcg::Ray3fN
typedef Ray3< int > vcg::Ray3i
typedef Ray3< int,true > vcg::Ray3iN
typedef Ray3< short > vcg::Ray3s
typedef Ray3< short,true > vcg::Ray3sN
typedef T vcg::Sphere3::ScalarType
typedef Segment2< double > vcg::Segment2d
typedef Segment2< float > vcg::Segment2f
typedef Segment2< int > vcg::Segment2i
typedef Segment2< short > vcg::Segment2s
typedef Segment3< double > vcg::Segment3d
typedef Segment3< float > vcg::Segment3f
typedef Segment3< int > vcg::Segment3i
typedef Segment3< short > vcg::Segment3s
typedef Sphere3< double > vcg::Sphere3d
typedef Sphere3< float > vcg::Sphere3f
typedef TexCoord2< double > vcg::TexCoord2d
typedef TexCoord2< float > vcg::TexCoord2f
typedef Triangle2< ScalarTypevcg::Triangle2::TriangleType
typedef Point2< double > vcg::ndim::Vector2d
typedef Point2< float > vcg::ndim::Vector2f
typedef Point2< int > vcg::ndim::Vector2i
typedef Point2< short > vcg::ndim::Vector2s
typedef Point3< double > vcg::ndim::Vector3d
typedef Point3< float > vcg::ndim::Vector3f
typedef Point3< int > vcg::ndim::Vector3i
typedef Point3< short > vcg::ndim::Vector3s
typedef Point4< double > vcg::ndim::Vector4d
typedef Point4< float > vcg::ndim::Vector4f
typedef Point4< int > vcg::ndim::Vector4i
typedef Point4< short > vcg::ndim::Vector4s

Enumerations

enum  vcg::ColorSpace::Illuminant {
  vcg::ColorSpace::ILLUMINANT_A = 0, vcg::ColorSpace::ILLUMINANT_B = 1, vcg::ColorSpace::ILLUMINANT_C = 2, vcg::ColorSpace::ILLUMINANT_D50 = 3,
  vcg::ColorSpace::ILLUMINANT_D55 = 4, vcg::ColorSpace::ILLUMINANT_D65 = 5, vcg::ColorSpace::ILLUMINANT_D75 = 6, vcg::ColorSpace::ILLUMINANT_E = 7,
  vcg::ColorSpace::ILLUMINANT_INVALID = 8
}
enum  vcg::ColorSpace::RGBSpaces {
  vcg::ColorSpace::ADOBE_RGB = 0, vcg::ColorSpace::APPLE_RGB = 1, vcg::ColorSpace::BEST_RGB = 2, vcg::ColorSpace::BETA_RGB = 3,
  vcg::ColorSpace::BRUCE_RGB = 4, vcg::ColorSpace::CIE_RGB = 5, vcg::ColorSpace::COLOR_MATCH = 6, vcg::ColorSpace::DON_RGB4 = 7,
  vcg::ColorSpace::ECI_RGB = 8, vcg::ColorSpace::EKTA_SPACE = 9, vcg::ColorSpace::NTSC_RGB = 10, vcg::ColorSpace::PAL_RGB = 11,
  vcg::ColorSpace::PROPHOTO = 12, vcg::ColorSpace::SMPTE_C = 13, vcg::ColorSpace::SRGB = 14, vcg::ColorSpace::WIDE_GAMUT = 15
}

Functions

template<class SCALARTYPE >
Point3< SCALARTYPE > vcg::Abs (const Point3< SCALARTYPE > &p)
void vcg::Sphere3::Add (const Sphere3 &sphere)
void vcg::Sphere3::Add (const Point3< T > &p)
template<class T >
vcg::Angle (const Point4< T > &p1, const Point4< T > &p2)
template<class P3ScalarType >
P3ScalarType vcg::Angle (Point3< P3ScalarType > const &p1, Point3< P3ScalarType > const &p2)
template<class T >
vcg::Angle (Point2< T > const &p0, Point2< T > const &p1)
template<class S >
vcg::ndim::Angle (Point3< S > const &p1, Point3< S > const &p2)
template<class P3ScalarType >
P3ScalarType vcg::AngleN (Point3< P3ScalarType > const &p1, Point3< P3ScalarType > const &p2)
template<class S >
vcg::ndim::AngleN (Point3< S > const &p1, Point3< S > const &p2)
template<class TriangleType >
Point3< typename
TriangleType::ScalarType
vcg::Barycenter (const TriangleType &t)
template<class ScalarType >
Point3< ScalarTypevcg::Barycenter (const Tetra3< ScalarType > &t)
static double vcg::ColorSpace::CA (int index)
const Point3< T > & vcg::Sphere3::Center () const
Point3< T > & vcg::Sphere3::Center ()
static void vcg::ColorSpace::chromaticAdaptation (double Xi, double Yi, double Zi, Illuminant src, double &X, double &Y, double &Z, Illuminant dst, ConeResponse response=BRADFORD)
static Color4< T > vcg::ColorSpace::chromaticAdaptation (const Color4< T > &color, Illuminant src, Illuminant dst, ConeResponse response=BRADFORD)
static double vcg::ColorSpace::CIE_EPSILON ()
static double vcg::ColorSpace::CIE_KI ()
static void vcg::ColorSpace::CIELabtoXYZ (double L, double a, double b, double &X, double &Y, double &Z, Illuminant whiteRef)
static Color4< T > vcg::ColorSpace::CIELabtoXYZ (const Color4< T > &color, Illuminant ref)
template<class ScalarType >
bool vcg::CircleLineIntersection (const vcg::Line2< ScalarType > &line, const vcg::Point2< ScalarType > &center, const ScalarType &radius, vcg::Point2< ScalarType > &p0, vcg::Point2< ScalarType > &p1)
template<class TriangleType >
Point3< typename
TriangleType::ScalarType
vcg::Circumcenter (const TriangleType &t)
Color4< float > vcg::Clamp (Color4< float > &c)
template<class ScalarType >
Point3< ScalarTypevcg::ClosestPoint (Segment3< ScalarType > s, const Point3< ScalarType > &p)
template<class ScalarType >
Point2< ScalarTypevcg::ClosestPoint (Segment2< ScalarType > s, const Point2< ScalarType > &p)
template<class ScalarType , bool NORM>
Point3< ScalarTypevcg::ClosestPoint (Ray3< ScalarType, NORM > r, const Point3< ScalarType > &p)
 returns closest point
template<class ScalarType , bool NORM>
Point3< ScalarTypevcg::ClosestPoint (Ray2< ScalarType, NORM > r, const Point3< ScalarType > &p)
 returns closest point
template<class ScalarType , bool NORM>
Point3< ScalarTypevcg::ClosestPoint (Line3< ScalarType, NORM > l, const Point3< ScalarType > &p)
 returns closest point
template<class ScalarType , bool NORM>
Point2< ScalarTypevcg::ClosestPoint (Line2< ScalarType, NORM > l, const Point2< ScalarType > &p)
 returns closest point
template<class ScalarType >
Point2< ScalarTypevcg::ClosestPoint2Box2 (const Point2< ScalarType > &test, const Box2< ScalarType > &bbox)
void vcg::Color4::ColorRamp (const float &minf, const float &maxf, float v)
 given a float and a range set the corresponding color in the well known red->green->blue color ramp. To reverse the direction of the ramp just swap minf and maxf.
template<class T >
int vcg::compute_intervals_isectline (Point3< T > VERT0, Point3< T > VERT1, Point3< T > VERT2, float VV0, float VV1, float VV2, float D0, float D1, float D2, float D0D1, float D0D2, float *isect0, float *isect1, Point3< T > &isectpoint0, Point3< T > &isectpoint1)
template<class TetraType >
TetraType::ScalarType vcg::ComputeVolume (const TetraType &t)
template<class SCALAR_TYPE >
bool vcg::Convex (const Point2< SCALAR_TYPE > &p0, const Point2< SCALAR_TYPE > &p1, const Point2< SCALAR_TYPE > &p2)
 return true if the algle is convex (right rotation)
template<class T >
bool vcg::coplanar_tri_tri (const Point3< T > N, const Point3< T > V0, const Point3< T > V1, const Point3< T > V2, const Point3< T > U0, const Point3< T > U1, const Point3< T > U2)
template<class TriangleType >
TriangleType::ScalarType vcg::CosWedge (const TriangleType &t, int k)
const CoordType & vcg::Triangle3::cP0 (const int j) const
const CoordType & vcg::Triangle2::cP0 (const int j) const
const CoordType & vcg::Triangle3::cP1 (const int j) const
const CoordType & vcg::Triangle2::cP1 (const int j) const
const CoordType & vcg::Triangle3::cP2 (const int j) const
const CoordType & vcg::Triangle2::cP2 (const int j) const
int vcg::Sphere3::CreateFromBox (int n, const Point3< T > *points)
int vcg::Sphere3::CreateTight (const std::vector< Point3< T > > &points, T threshold=1.01, T speed=0.6)
int vcg::Sphere3::CreateTight (int n, const Point3< T > *points, T threshold=1.01, T speed=0.6)
template<class ScalarType >
bool vcg::Cross (const Point2< ScalarType > &p00, const Point2< ScalarType > &p01, const Point2< ScalarType > &p10, const Point2< ScalarType > &p11)
template<class T >
vcg::Distance (const Sphere3< T > &sphere, const Sphere3< T > &s)
template<class T >
vcg::Distance (const Sphere3< T > &sphere, const Point3< T > &point)
template<class T >
vcg::Distance (const Point3< T > &point, const Plane3< T > &plane)
template<class T >
vcg::Distance (const Plane3< T > &plane, const Point3< T > &point)
 Distance plane - point and vv. (Move these function to somewhere else).
template<class ScalarType , bool NORM>
ScalarType vcg::Distance (const Line3< ScalarType, NORM > &l, const Point3< ScalarType > &p)
template<class ScalarType , bool NORM>
ScalarType vcg::Distance (const Line2< ScalarType, NORM > &l, const Point2< ScalarType > &p)
template<class T >
vcg::Distance (const Point4< T > &p1, const Point4< T > &p2)
template<class P3ScalarType >
P3ScalarType vcg::Distance (Point3< P3ScalarType > const &p1, Point3< P3ScalarType > const &p2)
template<class T >
vcg::Distance (Point2< T > const &p1, Point2< T > const &p2)
template<int N, class S >
vcg::ndim::Distance (Point< N, S > const &p1, Point< N, S > const &p2)
template<class ScalarType >
ScalarType vcg::DistancePoint2Box2 (const Point2< ScalarType > &test, const Box2< ScalarType > &bbox)
template<class ScalarType >
ScalarType vcg::DistancePoint3Box3 (const Point3< ScalarType > &p, const Box3< ScalarType > &b)
template<class TriangleType >
TriangleType::ScalarType vcg::DoubleArea (const TriangleType &t)
 Return the Double of area of the triangle.
static double vcg::ColorSpace::gamma (RGBSpaces rgb_space)
template<class P3ScalarType >
void vcg::GetUV (Point3< P3ScalarType > &n, Point3< P3ScalarType > &u, Point3< P3ScalarType > &v, Point3< P3ScalarType > up=(Point3< P3ScalarType >(0, 1, 0)))
static void vcg::ColorSpace::HSLtoRGB (double H, double S, double L, double &R, double &G, double &B)
static Color4< T > vcg::ColorSpace::HSLtoRGB (const Color4< T > &color)
static void vcg::ColorSpace::HSVtoRGB (double H, double S, double V, double &R, double &G, double &B)
static Color4< T > vcg::ColorSpace::HSVtoRGB (const Color4< T > &color)
static double vcg::ColorSpace::Hue2RGB (double v1, double v2, double vH)
template<class TriangleType , class ScalarType >
bool vcg::InterpolationParameters (const TriangleType t, const Point3< ScalarType > &N, const Point3< ScalarType > &bq, ScalarType &a, ScalarType &b, ScalarType &c)
template<class TriangleType , class ScalarType >
bool vcg::InterpolationParameters (const TriangleType t, const Point3< ScalarType > &N, const Point3< ScalarType > &P, Point3< ScalarType > &L)
 Handy Wrapper of the above one that uses the passed normal N to choose the right orientation.
template<class TriangleType , class ScalarType >
bool vcg::InterpolationParameters (const TriangleType t, const int Axis, const Point3< ScalarType > &P, Point3< ScalarType > &L)
bool vcg::Triangle3::InterpolationParameters (const CoordType &bq, ScalarType &a, ScalarType &b, ScalarType &_c) const
bool vcg::Triangle2::InterpolationParameters (const CoordType &bq, ScalarType &a, ScalarType &b, ScalarType &c) const
template<class ScalarType >
bool vcg::InterpolationParameters2 (const Point2< ScalarType > &V1, const Point2< ScalarType > &V2, const Point2< ScalarType > &V3, const Point2< ScalarType > &P, Point3< ScalarType > &L)
void vcg::Sphere3::Intersect (const Sphere3 &sphere)
template<class S >
bool vcg::Intersect (int cur, int v2, std::vector< int > &next, std::vector< Point2< S > > &points2)
template<class T >
bool vcg::IntersectionLineBox (const Box3< T > &box, const Line3< T > &r, Point3< T > &coord)
template<class T >
bool vcg::IntersectionLinePlane (const Plane3< T > &pl, const Line3< T > &li, Point3< T > &po)
 intersection between line and plane
template<class T >
bool vcg::IntersectionLineSphere (const Sphere3< T > &sp, const Line3< T > &li, Point3< T > &p0, Point3< T > &p1)
 interseciton between sphere and line
template<class T >
bool vcg::IntersectionLineTriangle (const Line3< T > &line, const Point3< T > &vert0, const Point3< T > &vert1, const Point3< T > &vert2, T &t, T &u, T &v)
template<class ScalarType >
bool vcg::IntersectionPlaneBox (const vcg::Plane3< ScalarType > &pl, vcg::Box3< ScalarType > &bbox)
template<class T >
bool vcg::IntersectionPlanePlane (const Plane3< T > &plane0, const Plane3< T > &plane1, Line3< T > &line)
template<class T >
bool vcg::IntersectionPlaneSegment (const Plane3< T > &pl, const Segment3< T > &s, Point3< T > &p0)
 intersection between segment and plane
template<class ScalarType >
bool vcg::IntersectionPlaneSegmentEpsilon (const Plane3< ScalarType > &pl, const Segment3< ScalarType > &sg, Point3< ScalarType > &po, const ScalarType epsilon=ScalarType(1e-8))
 intersection between segment and plane
template<class ScalarType >
bool vcg::IntersectionPlaneSphere (const Plane3< ScalarType > &pl, const Sphere3< ScalarType > &sphere, Point3< ScalarType > &center, ScalarType &radius)
template<typename TRIANGLETYPE >
bool vcg::IntersectionPlaneTriangle (const Plane3< typename TRIANGLETYPE::ScalarType > &pl, const TRIANGLETYPE &tr, Segment3< typename TRIANGLETYPE::ScalarType > &sg)
 intersection between plane and triangle
template<class T >
bool vcg::IntersectionRayBox (const Box3< T > &box, const Ray3< T > &r, Point3< T > &coord)
template<class T >
bool vcg::IntersectionRayTriangle (const Ray3< T > &ray, const Point3< T > &vert0, const Point3< T > &vert1, const Point3< T > &vert2, T &t, T &u, T &v)
template<class ScalarType >
int vcg::IntersectionSegmentBox (const Box3< ScalarType > &box, const Segment3< ScalarType > &s, Point3< ScalarType > &coord0, Point3< ScalarType > &coord1)
template<class ScalarType >
bool vcg::IntersectionSegmentBox (const Box3< ScalarType > &box, const Segment3< ScalarType > &s, Point3< ScalarType > &coord)
template<class SCALAR_TYPE >
int vcg::IntersectionSegmentSphere (const Sphere3< SCALAR_TYPE > &sphere, const Segment3< SCALAR_TYPE > &segment, Point3< SCALAR_TYPE > &t0, Point3< SCALAR_TYPE > &t1)
template<class TriangleType >
bool vcg::IntersectionSegmentTriangle (const vcg::Segment3< typename TriangleType::ScalarType > &seg, const TriangleType &t, typename TriangleType::ScalarType &a, typename TriangleType::ScalarType &b, typename TriangleType::ScalarType &dist)
template<class ScalarType >
bool vcg::IntersectionSegmentTriangle (const vcg::Segment3< ScalarType > &seg, const Point3< ScalarType > &vert0, const Point3< ScalarType > &vert1, const Point3< ScalarType > &vert2, ScalarType &a, ScalarType &b, ScalarType &dist)
template<class SphereType >
bool vcg::IntersectionSphereSphere (const SphereType &s0, const SphereType &s1)
template<class SCALAR_TYPE , class TRIANGLETYPE >
bool vcg::IntersectionSphereTriangle (const vcg::Sphere3< SCALAR_TYPE > &sphere, TRIANGLETYPE triangle, vcg::Point3< SCALAR_TYPE > &witness, std::pair< SCALAR_TYPE, SCALAR_TYPE > *res=NULL)
template<class ScalarType >
bool vcg::IntersectionTriangleBox (const vcg::Box3< ScalarType > &bbox, const vcg::Point3< ScalarType > &p0, const vcg::Point3< ScalarType > &p1, const vcg::Point3< ScalarType > &p2)
template<class T >
bool vcg::IntersectionTriangleTriangle (Point3< T > V0, Point3< T > V1, Point3< T > V2, Point3< T > U0, Point3< T > U1, Point3< T > U2)
template<typename TRIANGLETYPE >
bool vcg::IntersectionTriangleTriangle (const TRIANGLETYPE &t0, const TRIANGLETYPE &t1)
 intersection between two triangles
template<class T >
void vcg::isect2 (Point3< T > VTX0, Point3< T > VTX1, Point3< T > VTX2, float VV0, float VV1, float VV2, float D0, float D1, float D2, float *isect0, float *isect1, Point3< T > &isectpoint0, Point3< T > &isectpoint1)
bool vcg::Sphere3::IsEmpty () const
bool vcg::Sphere3::IsIn (const Sphere3< T > &p) const
bool vcg::Sphere3::IsIn (const Point3< T > &p) const
 return true if
template<class SCALAR_TYPE >
bool vcg::IsInsideTrianglePoint (const Triangle2< SCALAR_TYPE > &t, const Point2< SCALAR_TYPE > &p)
 interseciton between point and triangle
void vcg::Color4::lerp (const Color4 &c0, const Color4 &c1, const Color4 &c2, const Point3f &ip)
void vcg::Color4::lerp (const Color4 &c0, const Color4 &c1, const float x)
template<class SCALAR_TYPE >
bool vcg::LineLineIntersection (const vcg::Line2< SCALAR_TYPE > &l0, const vcg::Line2< SCALAR_TYPE > &l1, Point2< SCALAR_TYPE > &p)
template<class SCALAR_TYPE >
bool vcg::LineSegmentIntersection (const vcg::Line2< SCALAR_TYPE > &line, const vcg::Segment2< SCALAR_TYPE > &seg, Point2< SCALAR_TYPE > &p_inters)
 interseciton between point and triangle
template<class SCALARTYPE >
Point3< SCALARTYPE > vcg::LowClampToZero (const Point3< SCALARTYPE > &p)
template<class ScalarType , bool NORM>
vcg::Point2< ScalarTypevcg::Mirror (const vcg::Line2< ScalarType, NORM > &l, const vcg::Point2< ScalarType > &p)
template<class T >
bool vcg::NoDivTriTriIsect (const Point3< T > V0, const Point3< T > V1, const Point3< T > V2, const Point3< T > U0, const Point3< T > U1, const Point3< T > U2)
template<class T >
vcg::Norm (const Point4< T > &p)
template<class P3ScalarType >
P3ScalarType vcg::Norm (Point3< P3ScalarType > const &p)
template<class T >
vcg::Norm (Point2< T > const &p)
template<int N, class S >
vcg::ndim::Norm (Point< N, S > const &p)
template<class Point3Type >
Point3Type vcg::Normal (Point3Type const &p0, Point3Type const &p1, Point3Type const &p2)
template<class TriangleType >
Point3< typename
TriangleType::ScalarType
vcg::Normal (const TriangleType &t)
 Returns the normal to the plane passing through p0,p1,p2.
template<class TetraType >
Point3< typename
TetraType::ScalarType
vcg::Normal (const TetraType &t, const int &face)
 Returns the normal to the face face of the tetrahedron t.
template<class P3ScalarType >
Point3< P3ScalarType > & vcg::Normalize (Point3< P3ScalarType > &p)
template<class T >
Point2< T > & vcg::Normalize (Point2< T > &p)
template<int N, class S >
Point< N, S > & vcg::ndim::Normalize (Point< N, S > &p)
template<class Point3Type >
Point3Type vcg::NormalizedNormal (Point3Type const &p0, Point3Type const &p1, Point3Type const &p2)
template<class TriangleType >
Point3< typename
TriangleType::ScalarType
vcg::NormalizedNormal (const TriangleType &t)
 Like the above, it returns the normal to the plane passing through p0,p1,p2, but normalized.
template<class T >
Point2< T > vcg::operator* (const T s, Point2< T > const &p)
template<class T >
Point2< T > vcg::operator- (Point2< T > const &p)
const CoordType & vcg::Triangle3::P (const int j) const
CoordType & vcg::Triangle3::P (const int j)
 Shortcut per accedere ai punti delle facce.
const CoordType & vcg::Triangle2::P (const int j) const
CoordType & vcg::Triangle2::P (const int j)
 Shortcut per accedere ai punti delle facce.
const CoordType & vcg::Triangle3::P0 (const int j) const
CoordType & vcg::Triangle3::P0 (const int j)
const CoordType & vcg::Triangle2::P0 (const int j) const
CoordType & vcg::Triangle2::P0 (const int j)
const CoordType & vcg::Triangle3::P1 (const int j) const
CoordType & vcg::Triangle3::P1 (const int j)
const CoordType & vcg::Triangle2::P1 (const int j) const
CoordType & vcg::Triangle2::P1 (const int j)
const CoordType & vcg::Triangle3::P2 (const int j) const
CoordType & vcg::Triangle3::P2 (const int j)
const CoordType & vcg::Triangle2::P2 (const int j) const
CoordType & vcg::Triangle2::P2 (const int j)
template<class TriangleType >
TriangleType::ScalarType vcg::Perimeter (const TriangleType &t)
void vcg::Triangle2::PointDistance (const CoordType &q, ScalarType &dist, CoordType &p) const
 return the distance to the point q and neighors point p
template<class P3ScalarType >
P3ScalarType vcg::PSDist (const Point3< P3ScalarType > &p, const Point3< P3ScalarType > &v1, const Point3< P3ScalarType > &v2, Point3< P3ScalarType > &q)
 Point(p) Edge(v1-v2) dist, q is the point in v1-v2 with min dist.
template<class P3ScalarType >
P3ScalarType vcg::Quality (Point3< P3ScalarType > const &p0, Point3< P3ScalarType > const &p1, Point3< P3ScalarType > const &p2)
template<class TriangleType >
TriangleType::ScalarType vcg::QualityFace (const TriangleType &t)
 Returns the normal to the plane passing through p0,p1,p2.
ScalarType vcg::Triangle3::QualityFace () const
 Return the _q of the face, the return value is in [0,sqrt(3)/2] = [0 - 0.866.. ].
template<class P3ScalarType >
P3ScalarType vcg::QualityMeanRatio (Point3< P3ScalarType > const &p0, Point3< P3ScalarType > const &p1, Point3< P3ScalarType > const &p2)
template<class P3ScalarType >
P3ScalarType vcg::QualityRadii (Point3< P3ScalarType > const &p0, Point3< P3ScalarType > const &p1, Point3< P3ScalarType > const &p2)
const T & vcg::Sphere3::Radius () const
T & vcg::Sphere3::Radius ()
template<class SCALAR_TYPE >
bool vcg::RayLineIntersection (const vcg::Line2< SCALAR_TYPE > &l, const vcg::Ray2< SCALAR_TYPE > &r, Point2< SCALAR_TYPE > &p)
template<class SCALAR_TYPE >
bool vcg::RaySegmentIntersection (const vcg::Ray2< SCALAR_TYPE > &r, const vcg::Segment2< SCALAR_TYPE > &seg, Point2< SCALAR_TYPE > &p_inters)
 interseciton between point and triangle
static Illuminant vcg::ColorSpace::refIlluminant (RGBSpaces rgb_space)
static double vcg::ColorSpace::RGB2XYZ (int index)
static void vcg::ColorSpace::RGBtoHSL (double R, double G, double B, double &H, double &S, double &L)
static Color4< T > vcg::ColorSpace::RGBtoHSL (const Color4< T > &color)
static void vcg::ColorSpace::RGBtoHSV (double R, double G, double B, double &H, double &S, double &V)
static Color4< T > vcg::ColorSpace::RGBtoHSV (const Color4< T > &color)
static void vcg::ColorSpace::RGBtoRGB (double Ri, double Gi, double Bi, RGBSpaces rgbsrc, double &R, double &G, double &B, RGBSpaces rgbdest, ConeResponse response=BRADFORD)
static Color4< T > vcg::ColorSpace::RGBtoRGB (const Color4< T > &color, RGBSpaces rgbsrc, RGBSpaces rgbdest, ConeResponse response=BRADFORD)
static void vcg::ColorSpace::RGBtoXYZ (double R, double G, double B, RGBSpaces space, double &X, double &Y, double &Z, Illuminant dest, ConeResponse response=BRADFORD)
static Color4< T > vcg::ColorSpace::RGBtoXYZ (const Color4< T > &color, RGBSpaces space, Illuminant dest, ConeResponse response=BRADFORD)
template<class SCALAR_TYPE >
bool vcg::SegmentSegmentIntersection (const vcg::Segment2< SCALAR_TYPE > &seg0, const vcg::Segment2< SCALAR_TYPE > &seg1, Point2< SCALAR_TYPE > &p_inters)
 interseciton between point and triangle
 vcg::Sphere3::Sphere3 (const Point3< T > &center, T radius)
 vcg::Sphere3::Sphere3 ()
template<class ScalarType >
ScalarType vcg::SquaredDistance (Segment3< ScalarType > &segment, Point3< ScalarType > &p)
template<class T >
vcg::SquaredDistance (const Point3< T > &point, const Plane3< T > &plane)
template<class T >
vcg::SquaredDistance (const Plane3< T > &plane, const Point3< T > &point)
template<class T >
vcg::SquaredDistance (const Point4< T > &p1, const Point4< T > &p2)
template<class P3ScalarType >
P3ScalarType vcg::SquaredDistance (Point3< P3ScalarType > const &p1, Point3< P3ScalarType > const &p2)
template<class T >
vcg::SquaredDistance (Point2< T > const &p1, Point2< T > const &p2)
template<int N, class S >
vcg::ndim::SquaredDistance (Point< N, S > const &p1, Point< N, S > const &p2)
template<class T >
vcg::SquaredNorm (const Point4< T > &p)
template<class P3ScalarType >
P3ScalarType vcg::SquaredNorm (Point3< P3ScalarType > const &p)
template<class T >
vcg::SquaredNorm (Point2< T > const &p)
template<int N, class S >
vcg::ndim::SquaredNorm (Point< N, S > const &p)
template<class P3ScalarType >
double vcg::stable_dot (Point3< P3ScalarType > const &p0, Point3< P3ScalarType > const &p1)
template<class T >
double vcg::StableDot (Point4< T > const &p0, Point4< T > const &p1)
 slower version of dot product, more stable (double precision only)
template<class POINT_CONTAINER >
void vcg::TessellatePlanarPolygon2 (POINT_CONTAINER &points2, std::vector< int > &output)
template<class POINT_CONTAINER >
void vcg::TessellatePlanarPolygon3 (POINT_CONTAINER &points, std::vector< int > &output)
template<class T >
bool vcg::tri_tri_intersect_with_isectline (Point3< T > V0, Point3< T > V1, Point3< T > V2, Point3< T > U0, Point3< T > U1, Point3< T > U2, bool &coplanar, Point3< T > &isectpt1, Point3< T > &isectpt2)
 vcg::Triangle2::Triangle2 (const CoordType &p0, const CoordType &p1, const CoordType &p2)
 vcg::Triangle2::Triangle2 ()
 vcg::Triangle3::Triangle3 (const CoordType &c0, const CoordType &c1, const CoordType &c2)
 vcg::Triangle3::Triangle3 ()
template<class TriangleType >
void vcg::TrianglePointDistance (const TriangleType &t, const typename TriangleType::CoordType &q, typename TriangleType::ScalarType &dist, typename TriangleType::CoordType &closest)
 Computes the distance between a triangle and a point.
static void vcg::ColorSpace::xyYtoXYZ (double x, double y, double _Y, double &X, double &Y, double &Z)
static Color4< T > vcg::ColorSpace::xyYtoXYZ (const Color4< T > &color)
static double vcg::ColorSpace::XYZ2RGB (int index)
static void vcg::ColorSpace::XYZtoCIELab (double X, double Y, double Z, double &L, double &a, double &b, Illuminant whiteRef)
static Color4< T > vcg::ColorSpace::XYZtoCIELab (const Color4< T > &color, Illuminant ref)
static void vcg::ColorSpace::XYZtoRGB (double X, double Y, double Z, Illuminant src, double &R, double &G, double &B, RGBSpaces space, ConeResponse response=BRADFORD)
static Color4< T > vcg::ColorSpace::XYZtoRGB (const Color4< T > &color, Illuminant src, RGBSpaces dest, ConeResponse response=BRADFORD)
static void vcg::ColorSpace::XYZtoxyY (double X, double _Y, double Z, double &x, double &y, double &Y)
static Color4< T > vcg::ColorSpace::XYZtoxyY (const Color4< T > &color)

Variables

PointType vcg::Plane3::_dir
 Direction (not necessarily normalized unless NORM is true).
ScalarType vcg::Plane3::_offset
 Distance.
vcg::Sphere3::_radius
Point3< ScalarTypevcg::Triangle3::_v [3]
 Vector of vertex pointer incident in the face.
Point2< ScalarTypevcg::Triangle2::_v [3]
 Vector of vertex pointer incident in the face.

Members to access the distance or direction

Direction() cannot be assigned directly. Use SetDirection() or Set() instead. This is mandatory to make possible the automatic autonormalization template mechanism. Note that if you have to set both direction and offset it can be more efficient to set them toghether



const PointTypevcg::Plane3::Direction () const
void vcg::Plane3::Init (const PointType &p0, const PointType &norm)
 Calculates the plane passing through a point and the normal (Rename this method.
void vcg::Plane3::Init (const PointType &p0, const PointType &p1, const PointType &p2)
 Calculates the plane passing through three points (Rename this method).
void vcg::Plane3::Normalize ()
 Function to normalize direction.
ScalarTypevcg::Plane3::Offset ()
const ScalarTypevcg::Plane3::Offset () const
bool vcg::Plane3::operator!= (Plane3 const &p) const
 Operator to dispare two lines.
bool vcg::Plane3::operator== (Plane3 const &p) const
 Operator to compare two lines.
PointType vcg::Plane3::Projection (const PointType &p) const
 Project a point on the plane.
void vcg::Plane3::Set (const PointType &dir, const ScalarType &off)
void vcg::Plane3::Set (const ScalarType &off, const PointType &dir)
 sets origin and direction.
void vcg::Plane3::SetDirection (const PointType &dir)
 sets the direction
void vcg::Plane3::SetOffset (const ScalarType &o)
 sets the origin

Classical overloading of operators

Note



Box3< P3ScalarType > vcg::Point3::GetBBox (Box3< P3ScalarType > &bb) const

Constructors



template<class Q >
void vcg::Plane3::Import (const Plane3< Q, false > &b)
 vcg::Plane3::Plane3 (const ScalarType &dist, const PointType &dir)
 The (distance, direction) constructor.
 vcg::Plane3::Plane3 ()
 The empty constructor.

Detailed Description


Define Documentation

#define ADD ( dest,
v1,
v2   )     dest[0]=v1[0]+v2[0]; dest[1]=v1[1]+v2[1]; dest[2]=v1[2]+v2[2];

Definition at line 360 of file triangle_triangle3.h.

#define COMPUTE_INTERVALS_ISECTLINE ( VERT0,
VERT1,
VERT2,
VV0,
VV1,
VV2,
D0,
D1,
D2,
D0D1,
D0D2,
isect0,
isect1,
isectpoint0,
isectpoint1   ) 
Value:
if(D0D1>0.0f)                                         \
  {                                                     \
    /* here we know that D0D2<=0.0 */                   \
    /* that is D0, D1 are on the same side, D2 on the other or on the plane */ \
    isect2(VERT2,VERT0,VERT1,VV2,VV0,VV1,D2,D0,D1,&isect0,&isect1,isectpoint0,isectpoint1);          \
  }

Definition at line 430 of file triangle_triangle3.h.

#define CROSS ( dest,
v1,
v2   ) 
Value:
{                     \
              dest[0]=v1[1]*v2[2]-v1[2]*v2[1]; \
              dest[1]=v1[2]*v2[0]-v1[0]*v2[2]; \
              dest[2]=v1[0]*v2[1]-v1[1]*v2[0];}

Definition at line 57 of file triangle_triangle3.h.

#define DOT ( v1,
v2   )     (v1[0]*v2[0]+v1[1]*v2[1]+v1[2]*v2[2])

Definition at line 359 of file triangle_triangle3.h.

#define DOT ( v1,
v2   )     (v1[0]*v2[0]+v1[1]*v2[1]+v1[2]*v2[2])

Definition at line 359 of file triangle_triangle3.h.

#define EDGE_AGAINST_TRI_EDGES ( V0,
V1,
U0,
U1,
U2   ) 
Value:
{                                              \
  T Ax,Ay,Bx,By,Cx,Cy,e,d,f;               \
  Ax=V1[i0]-V0[i0];                            \
  Ay=V1[i1]-V0[i1];                            \
  /* test edge U0,U1 against V0,V1 */          \
  EDGE_EDGE_TEST(V0,U0,U1);                    \
  /* test edge U1,U2 against V0,V1 */          \
  EDGE_EDGE_TEST(V0,U1,U2);                    \
  /* test edge U2,U1 against V0,V1 */          \
  EDGE_EDGE_TEST(V0,U2,U0);                    \
}

Definition at line 100 of file triangle_triangle3.h.

#define EDGE_EDGE_TEST ( V0,
U0,
U1   ) 
Value:
Bx=U0[i0]-U1[i0];                                   \
  By=U0[i1]-U1[i1];                                   \
  Cx=V0[i0]-U0[i0];                                   \
  Cy=V0[i1]-U0[i1];                                   \
  f=Ay*Bx-Ax*By;                                      \
  d=By*Cx-Bx*Cy;                                      \
  if((f>0 && d>=0 && d<=f) || (f<0 && d<=0 && d>=f))  \
  {                                                   \
    e=Ax*Cy-Ay*Cx;                                    \
    if(f>0)                                           \
    {                                                 \
      if(e>=0 && e<=f) return 1;                      \
    }                                                 \
    else                                              \
    {                                                 \
      if(e<=0 && e>=f) return 1;                      \
    }                                                 \
  }

Definition at line 80 of file triangle_triangle3.h.

#define FABS (  )     (T(fabs(x)))

Triangle/triangle intersection ,based on the algorithm presented in "A Fast Triangle-Triangle Intersection Test", Journal of Graphics Tools, 2(2), 1997

Definition at line 50 of file triangle_triangle3.h.

#define MULT ( dest,
v,
factor   )     dest[0]=factor*v[0]; dest[1]=factor*v[1]; dest[2]=factor*v[2];

Definition at line 361 of file triangle_triangle3.h.

#define NEWCOMPUTE_INTERVALS ( VV0,
VV1,
VV2,
D0,
D1,
D2,
D0D1,
D0D2,
A,
B,
C,
X0,
X1   ) 

Definition at line 201 of file triangle_triangle3.h.

#define POINT_IN_TRI ( V0,
U0,
U1,
U2   ) 
Value:
{                                           \
  T a,b,c,d0,d1,d2;                     \
  /* is T1 completly inside T2? */          \
  /* check if V0 is inside tri(U0,U1,U2) */ \
  a=U1[i1]-U0[i1];                          \
  b=-(U1[i0]-U0[i0]);                       \
  c=-a*U0[i0]-b*U0[i1];                     \
  d0=a*V0[i0]+b*V0[i1]+c;                   \
                                            \
  a=U2[i1]-U1[i1];                          \
  b=-(U2[i0]-U1[i0]);                       \
  c=-a*U1[i0]-b*U1[i1];                     \
  d1=a*V0[i0]+b*V0[i1]+c;                   \
                                            \
  a=U0[i1]-U2[i1];                          \
  b=-(U0[i0]-U2[i0]);                       \
  c=-a*U2[i0]-b*U2[i1];                     \
  d2=a*V0[i0]+b*V0[i1]+c;                   \
  if(d0*d1>0.0)                             \
  {                                         \
    if(d0*d2>0.0) return 1;                 \
  }                                         \
}

Definition at line 113 of file triangle_triangle3.h.

#define SET ( dest,
src   )     dest[0]=src[0]; dest[1]=src[1]; dest[2]=src[2];

Definition at line 362 of file triangle_triangle3.h.

#define SORT ( a,
 ) 
Value:
if(a>b)    \
             {          \
               T c; \
               c=a;     \
               a=b;     \
               b=c;     \
             }

Definition at line 70 of file triangle_triangle3.h.

#define SORT2 ( a,
b,
smallest   ) 
Value:
if(a>b)       \
             {             \
               float c;    \
               c=a;        \
               a=b;        \
               b=c;        \
               smallest=1; \
             }             \
             else smallest=0;

Definition at line 364 of file triangle_triangle3.h.

#define SUB ( dest,
v1,
v2   ) 
Value:
{         \
            dest[0]=v1[0]-v2[0]; \
            dest[1]=v1[1]-v2[1]; \
            dest[2]=v1[2]-v2[2];}

Definition at line 64 of file triangle_triangle3.h.

#define TRI_TRI_INT_EPSILON   0.000001

Definition at line 53 of file triangle_triangle3.h.

#define USE_EPSILON_TEST

Definition at line 52 of file triangle_triangle3.h.


Typedef Documentation

typedef Box2< double > vcg::Box2d

Specificazione di box of double.

Definition at line 386 of file box.h.

typedef Box2< float > vcg::Box2f

Specificazione di box of float.

Definition at line 385 of file box.h.

typedef Box2< int > vcg::Box2i

Specificazione di box of int.

Definition at line 384 of file box.h.

typedef Box2< short > vcg::Box2s

Specificazione di box of short.

Definition at line 383 of file box.h.

typedef Box3< double > vcg::Box3d

Definition at line 381 of file box.h.

typedef Box3< float > vcg::Box3f

Definition at line 380 of file box.h.

typedef Box3< int > vcg::Box3i

Definition at line 379 of file box.h.

typedef Box3< short > vcg::Box3s

Definition at line 378 of file box.h.

template<class ScalarTriangleType >
typedef Box3<ScalarType> vcg::Triangle3< ScalarTriangleType >::BoxType [inherited]

The bounding box type.

Definition at line 116 of file triangle3.h.

typedef Color4<unsigned char> vcg::Color4b

Definition at line 403 of file color4.h.

typedef Color4<double> vcg::Color4d

Definition at line 405 of file color4.h.

typedef Color4<float> vcg::Color4f

Definition at line 404 of file color4.h.

template<class ScalarTriangleType >
typedef Point3< ScalarType > vcg::Triangle3< ScalarTriangleType >::CoordType [inherited]

Definition at line 114 of file triangle3.h.

template<class SCALAR_TYPE >
typedef Point2< ScalarType > vcg::Triangle2< SCALAR_TYPE >::CoordType [inherited]

Definition at line 47 of file triangle2.h.

typedef Line2<double> vcg::Line2d

Definition at line 179 of file line2.h.

typedef Line2<double,true> vcg::Line2dN

Definition at line 184 of file line2.h.

typedef Line2<float> vcg::Line2f

Definition at line 178 of file line2.h.

typedef Line2<float ,true> vcg::Line2fN

Definition at line 183 of file line2.h.

typedef Line2<int> vcg::Line2i

Definition at line 177 of file line2.h.

typedef Line2<int ,true> vcg::Line2iN

Definition at line 182 of file line2.h.

typedef Line2<short> vcg::Line2s

Definition at line 176 of file line2.h.

typedef Line2<short ,true> vcg::Line2sN

Definition at line 181 of file line2.h.

typedef Line3<double> vcg::Line3d

Definition at line 195 of file line3.h.

typedef Line3<double,true> vcg::Line3dN

Definition at line 200 of file line3.h.

typedef Line3<float> vcg::Line3f

Definition at line 194 of file line3.h.

typedef Line3<float ,true> vcg::Line3fN

Definition at line 199 of file line3.h.

typedef Line3<int> vcg::Line3i

Definition at line 193 of file line3.h.

typedef Line3<int ,true> vcg::Line3iN

Definition at line 198 of file line3.h.

typedef Line3<short> vcg::Line3s

Definition at line 192 of file line3.h.

typedef Line3<short ,true> vcg::Line3sN

Definition at line 197 of file line3.h.

typedef Plane3<double> vcg::Plane3d

Definition at line 175 of file plane3.h.

typedef Plane3<float> vcg::Plane3f

Definition at line 174 of file plane3.h.

typedef Point2<double> vcg::Point2d

Definition at line 360 of file deprecated_point2.h.

typedef Point2<double> vcg::ndim::Point2d

Definition at line 940 of file deprecated_point.h.

typedef Point2<float> vcg::Point2f

Definition at line 359 of file deprecated_point2.h.

typedef Point2<float> vcg::ndim::Point2f

Definition at line 939 of file deprecated_point.h.

typedef Point2<int> vcg::Point2i

Definition at line 358 of file deprecated_point2.h.

typedef Point2<int> vcg::ndim::Point2i

Definition at line 938 of file deprecated_point.h.

typedef Point2<short> vcg::Point2s

Definition at line 357 of file deprecated_point2.h.

typedef Point2<short> vcg::ndim::Point2s

Definition at line 937 of file deprecated_point.h.

typedef Point3<double> vcg::Point3d

Definition at line 565 of file deprecated_point3.h.

typedef Point3<double> vcg::ndim::Point3d

Definition at line 949 of file deprecated_point.h.

typedef Point3<float> vcg::Point3f

Definition at line 564 of file deprecated_point3.h.

typedef Point3<float> vcg::ndim::Point3f

Definition at line 948 of file deprecated_point.h.

typedef Point3<int> vcg::Point3i

Definition at line 563 of file deprecated_point3.h.

typedef Point3<int> vcg::ndim::Point3i

Definition at line 947 of file deprecated_point.h.

typedef Point3<short> vcg::Point3s

Definition at line 562 of file deprecated_point3.h.

typedef Point3<short> vcg::ndim::Point3s

Definition at line 946 of file deprecated_point.h.

typedef Point4<double> vcg::Point4d

Definition at line 383 of file deprecated_point4.h.

typedef Point4<double> vcg::ndim::Point4d

Definition at line 959 of file deprecated_point.h.

typedef Point4<float> vcg::Point4f

Definition at line 382 of file deprecated_point4.h.

typedef Point4<float> vcg::ndim::Point4f

Definition at line 958 of file deprecated_point.h.

typedef Point4<int> vcg::Point4i

Definition at line 381 of file deprecated_point4.h.

typedef Point4<int> vcg::ndim::Point4i

Definition at line 957 of file deprecated_point.h.

typedef Point4<short> vcg::Point4s

Definition at line 380 of file deprecated_point4.h.

typedef Point4<short> vcg::ndim::Point4s

Definition at line 956 of file deprecated_point.h.

template<class T, bool NORM = true>
typedef Point3<T> vcg::Plane3< T, NORM >::PointType [inherited]

Definition at line 85 of file plane3.h.

typedef Ray2<double> vcg::Ray2d

Definition at line 180 of file ray2.h.

typedef Ray2<double,true> vcg::Ray2dN

Definition at line 185 of file ray2.h.

typedef Ray2<float> vcg::Ray2f

Definition at line 179 of file ray2.h.

typedef Ray2<float ,true> vcg::Ray2fN

Definition at line 184 of file ray2.h.

typedef Ray2<int> vcg::Ray2i

Definition at line 178 of file ray2.h.

typedef Ray2<int ,true> vcg::Ray2iN

Definition at line 183 of file ray2.h.

typedef Ray2<short> vcg::Ray2s

Definition at line 177 of file ray2.h.

typedef Ray2<short ,true> vcg::Ray2sN

Definition at line 182 of file ray2.h.

typedef Ray3<double> vcg::Ray3d

Definition at line 186 of file ray3.h.

typedef Ray3<double,true> vcg::Ray3dN

Definition at line 191 of file ray3.h.

typedef Ray3<float> vcg::Ray3f

Definition at line 185 of file ray3.h.

typedef Ray3<float ,true> vcg::Ray3fN

Definition at line 190 of file ray3.h.

typedef Ray3<int> vcg::Ray3i

Definition at line 184 of file ray3.h.

typedef Ray3<int ,true> vcg::Ray3iN

Definition at line 189 of file ray3.h.

typedef Ray3<short> vcg::Ray3s

Definition at line 183 of file ray3.h.

typedef Ray3<short ,true> vcg::Ray3sN

Definition at line 188 of file ray3.h.

template<class T>
typedef T vcg::Sphere3< T >::ScalarType [inherited]

Definition at line 80 of file sphere3.h.

typedef Segment2<double> vcg::Segment2d

Definition at line 144 of file segment2.h.

typedef Segment2<float> vcg::Segment2f

Definition at line 143 of file segment2.h.

typedef Segment2<int> vcg::Segment2i

Definition at line 142 of file segment2.h.

typedef Segment2<short> vcg::Segment2s

Definition at line 141 of file segment2.h.

typedef Segment3<double> vcg::Segment3d

Definition at line 157 of file segment3.h.

typedef Segment3<float> vcg::Segment3f

Definition at line 156 of file segment3.h.

typedef Segment3<int> vcg::Segment3i

Definition at line 155 of file segment3.h.

typedef Segment3<short> vcg::Segment3s

Definition at line 154 of file segment3.h.

typedef Sphere3<double> vcg::Sphere3d

Definition at line 123 of file sphere3.h.

typedef Sphere3<float> vcg::Sphere3f

Definition at line 122 of file sphere3.h.

typedef TexCoord2<double> vcg::TexCoord2d

Definition at line 200 of file texcoord2.h.

typedef TexCoord2<float> vcg::TexCoord2f

Definition at line 199 of file texcoord2.h.

template<class SCALAR_TYPE >
typedef Triangle2<ScalarType> vcg::Triangle2< SCALAR_TYPE >::TriangleType [inherited]

Definition at line 48 of file triangle2.h.

typedef Point2<double> vcg::ndim::Vector2d

Definition at line 944 of file deprecated_point.h.

typedef Point2<float> vcg::ndim::Vector2f

Definition at line 943 of file deprecated_point.h.

typedef Point2<int> vcg::ndim::Vector2i

Definition at line 942 of file deprecated_point.h.

typedef Point2<short> vcg::ndim::Vector2s

Definition at line 941 of file deprecated_point.h.

typedef Point3<double> vcg::ndim::Vector3d

Definition at line 953 of file deprecated_point.h.

typedef Point3<float> vcg::ndim::Vector3f

Definition at line 952 of file deprecated_point.h.

typedef Point3<int> vcg::ndim::Vector3i

Definition at line 951 of file deprecated_point.h.

typedef Point3<short> vcg::ndim::Vector3s

Definition at line 950 of file deprecated_point.h.

typedef Point4<double> vcg::ndim::Vector4d

Definition at line 963 of file deprecated_point.h.

typedef Point4<float> vcg::ndim::Vector4f

Definition at line 962 of file deprecated_point.h.

typedef Point4<int> vcg::ndim::Vector4i

Definition at line 961 of file deprecated_point.h.

typedef Point4<short> vcg::ndim::Vector4s

Definition at line 960 of file deprecated_point.h.


Enumeration Type Documentation

template<typename T >
enum vcg::ColorSpace::Illuminant [inherited]
Enumerator:
ILLUMINANT_A 
ILLUMINANT_B 
ILLUMINANT_C 
ILLUMINANT_D50 
ILLUMINANT_D55 
ILLUMINANT_D65 
ILLUMINANT_D75 
ILLUMINANT_E 
ILLUMINANT_INVALID 

Definition at line 120 of file colorspace.h.

template<typename T >
enum vcg::ColorSpace::RGBSpaces [inherited]
Enumerator:
ADOBE_RGB 
APPLE_RGB 
BEST_RGB 
BETA_RGB 
BRUCE_RGB 
CIE_RGB 
COLOR_MATCH 
DON_RGB4 
ECI_RGB 
EKTA_SPACE 
NTSC_RGB 
PAL_RGB 
PROPHOTO 
SMPTE_C 
SRGB 
WIDE_GAMUT 

Definition at line 133 of file colorspace.h.


Function Documentation

template<class SCALARTYPE >
Point3<SCALARTYPE> vcg::Abs ( const Point3< SCALARTYPE > &  p  )  [inline]

Definition at line 553 of file deprecated_point3.h.

template<class T>
void vcg::Sphere3< T >::Add ( const Sphere3< T > &  sphere  )  [inline, inherited]

Definition at line 125 of file sphere3.h.

template<class T>
void vcg::Sphere3< T >::Add ( const Point3< T > &  p  )  [inline, inherited]

Definition at line 151 of file sphere3.h.

template<class T >
T vcg::Angle ( const Point4< T > &  p1,
const Point4< T > &  p2 
) [inline]

Definition at line 340 of file deprecated_point4.h.

template<class P3ScalarType >
P3ScalarType vcg::Angle ( Point3< P3ScalarType > const &  p1,
Point3< P3ScalarType > const &  p2 
) [inline]

Definition at line 423 of file deprecated_point3.h.

template<class T >
T vcg::Angle ( Point2< T > const &  p0,
Point2< T > const &  p1 
) [inline]

Definition at line 317 of file deprecated_point2.h.

template<class S >
S vcg::ndim::Angle ( Point3< S > const &  p1,
Point3< S > const &  p2 
) [inline]

Definition at line 860 of file deprecated_point.h.

template<class P3ScalarType >
P3ScalarType vcg::AngleN ( Point3< P3ScalarType > const &  p1,
Point3< P3ScalarType > const &  p2 
) [inline]

Definition at line 435 of file deprecated_point3.h.

template<class S >
S vcg::ndim::AngleN ( Point3< S > const &  p1,
Point3< S > const &  p2 
) [inline]

Definition at line 872 of file deprecated_point.h.

template<class TriangleType >
Point3<typename TriangleType::ScalarType> vcg::Barycenter ( const TriangleType &  t  )  [inline]

Definition at line 466 of file triangle3.h.

template<class ScalarType >
Point3<ScalarType> vcg::Barycenter ( const Tetra3< ScalarType > &  t  )  [inline]

Definition at line 491 of file tetra3.h.

template<typename T >
static double vcg::ColorSpace< T >::CA ( int  index  )  [inline, static, private, inherited]

Definition at line 352 of file colorspace.h.

template<class T>
const Point3<T>& vcg::Sphere3< T >::Center (  )  const [inline, inherited]

Definition at line 87 of file sphere3.h.

template<class T>
Point3<T>& vcg::Sphere3< T >::Center (  )  [inline, inherited]

Definition at line 86 of file sphere3.h.

template<typename T >
static void vcg::ColorSpace< T >::chromaticAdaptation ( double  Xi,
double  Yi,
double  Zi,
Illuminant  src,
double &  X,
double &  Y,
double &  Z,
Illuminant  dst,
ConeResponse  response = BRADFORD 
) [inline, static, inherited]

Definition at line 1938 of file colorspace.h.

template<typename T >
static Color4<T> vcg::ColorSpace< T >::chromaticAdaptation ( const Color4< T > &  color,
Illuminant  src,
Illuminant  dst,
ConeResponse  response = BRADFORD 
) [inline, static, inherited]

Definition at line 1926 of file colorspace.h.

template<typename T >
static double vcg::ColorSpace< T >::CIE_EPSILON (  )  [inline, static, private, inherited]

Definition at line 156 of file colorspace.h.

template<typename T >
static double vcg::ColorSpace< T >::CIE_KI (  )  [inline, static, private, inherited]

Definition at line 161 of file colorspace.h.

template<typename T >
static void vcg::ColorSpace< T >::CIELabtoXYZ ( double  L,
double  a,
double  b,
double &  X,
double &  Y,
double &  Z,
Illuminant  whiteRef 
) [inline, static, inherited]

Definition at line 1727 of file colorspace.h.

template<typename T >
static Color4<T> vcg::ColorSpace< T >::CIELabtoXYZ ( const Color4< T > &  color,
Illuminant  ref 
) [inline, static, inherited]

Definition at line 1718 of file colorspace.h.

template<class ScalarType >
bool vcg::CircleLineIntersection ( const vcg::Line2< ScalarType > &  line,
const vcg::Point2< ScalarType > &  center,
const ScalarType radius,
vcg::Point2< ScalarType > &  p0,
vcg::Point2< ScalarType > &  p1 
) [inline]

translate with origin on the center

no intersection

Definition at line 216 of file intersection2.h.

template<class TriangleType >
Point3<typename TriangleType::ScalarType> vcg::Circumcenter ( const TriangleType &  t  )  [inline]

Definition at line 480 of file triangle3.h.

Color4<float> vcg::Clamp ( Color4< float > &  c  )  [inline]

Definition at line 382 of file color4.h.

template<class ScalarType >
Point3<ScalarType> vcg::ClosestPoint ( Segment3< ScalarType s,
const Point3< ScalarType > &  p 
) [inline]

Definition at line 182 of file segment3.h.

template<class ScalarType >
Point2<ScalarType> vcg::ClosestPoint ( Segment2< ScalarType s,
const Point2< ScalarType > &  p 
) [inline]

Definition at line 147 of file segment2.h.

template<class ScalarType , bool NORM>
Point3<ScalarType> vcg::ClosestPoint ( Ray3< ScalarType, NORM >  r,
const Point3< ScalarType > &  p 
) [inline]

returns closest point

Definition at line 195 of file ray3.h.

template<class ScalarType , bool NORM>
Point3<ScalarType> vcg::ClosestPoint ( Ray2< ScalarType, NORM >  r,
const Point3< ScalarType > &  p 
) [inline]

returns closest point

Definition at line 189 of file ray2.h.

template<class ScalarType , bool NORM>
Point3<ScalarType> vcg::ClosestPoint ( Line3< ScalarType, NORM >  l,
const Point3< ScalarType > &  p 
) [inline]

returns closest point

Definition at line 204 of file line3.h.

template<class ScalarType , bool NORM>
Point2<ScalarType> vcg::ClosestPoint ( Line2< ScalarType, NORM >  l,
const Point2< ScalarType > &  p 
) [inline]

returns closest point

Definition at line 188 of file line2.h.

template<class ScalarType >
Point2<ScalarType> vcg::ClosestPoint2Box2 ( const Point2< ScalarType > &  test,
const Box2< ScalarType > &  bbox 
) [inline]

Definition at line 312 of file box2.h.

template<class T >
void vcg::Color4< T >::ColorRamp ( const float &  minf,
const float &  maxf,
float  v 
) [inline, inherited]

given a float and a range set the corresponding color in the well known red->green->blue color ramp. To reverse the direction of the ramp just swap minf and maxf.

Definition at line 278 of file color4.h.

template<class T >
int vcg::compute_intervals_isectline ( Point3< T >  VERT0,
Point3< T >  VERT1,
Point3< T >  VERT2,
float  VV0,
float  VV1,
float  VV2,
float  D0,
float  D1,
float  D2,
float  D0D1,
float  D0D2,
float *  isect0,
float *  isect1,
Point3< T > &  isectpoint0,
Point3< T > &  isectpoint1 
) [inline]

Definition at line 393 of file triangle_triangle3.h.

template<class TetraType >
TetraType::ScalarType vcg::ComputeVolume ( const TetraType &  t  )  [inline]

Definition at line 498 of file tetra3.h.

template<class SCALAR_TYPE >
bool vcg::Convex ( const Point2< SCALAR_TYPE > &  p0,
const Point2< SCALAR_TYPE > &  p1,
const Point2< SCALAR_TYPE > &  p2 
) [inline]

return true if the algle is convex (right rotation)

Function computing the intersection between couple of geometric primitives in 2 dimension

Definition at line 52 of file intersection2.h.

template<class T >
bool vcg::coplanar_tri_tri ( const Point3< T >  N,
const Point3< T >  V0,
const Point3< T >  V1,
const Point3< T >  V2,
const Point3< T >  U0,
const Point3< T >  U1,
const Point3< T >  U2 
) [inline]

CHeck two triangles for coplanarity

Parameters:
N 
V0 A vertex of the first triangle
V1 A vertex of the first triangle
V2 A vertex of the first triangle
U0 A vertex of the second triangle
U1 A vertex of the second triangle
U2 A vertex of the second triangle
Returns:
true se due triangoli sono cooplanari, false altrimenti

Definition at line 150 of file triangle_triangle3.h.

template<class TriangleType >
TriangleType::ScalarType vcg::CosWedge ( const TriangleType &  t,
int  k 
) [inline]

Definition at line 457 of file triangle3.h.

template<class ScalarTriangleType >
const CoordType& vcg::Triangle3< ScalarTriangleType >::cP0 ( const int  j  )  const [inline, inherited]

Definition at line 138 of file triangle3.h.

template<class SCALAR_TYPE >
const CoordType& vcg::Triangle2< SCALAR_TYPE >::cP0 ( const int  j  )  const [inline, inherited]

Definition at line 74 of file triangle2.h.

template<class ScalarTriangleType >
const CoordType& vcg::Triangle3< ScalarTriangleType >::cP1 ( const int  j  )  const [inline, inherited]

Definition at line 139 of file triangle3.h.

template<class SCALAR_TYPE >
const CoordType& vcg::Triangle2< SCALAR_TYPE >::cP1 ( const int  j  )  const [inline, inherited]

Definition at line 75 of file triangle2.h.

template<class ScalarTriangleType >
const CoordType& vcg::Triangle3< ScalarTriangleType >::cP2 ( const int  j  )  const [inline, inherited]

Definition at line 140 of file triangle3.h.

template<class SCALAR_TYPE >
const CoordType& vcg::Triangle2< SCALAR_TYPE >::cP2 ( const int  j  )  const [inline, inherited]

Definition at line 76 of file triangle2.h.

template<class T>
int vcg::Sphere3< T >::CreateFromBox ( int  n,
const Point3< T > *  points 
) [inline, inherited]

Definition at line 187 of file sphere3.h.

template<class T>
int vcg::Sphere3< T >::CreateTight ( const std::vector< Point3< T > > &  points,
T  threshold = 1.01,
T  speed = 0.6 
) [inline, inherited]

Definition at line 257 of file sphere3.h.

template<class T>
int vcg::Sphere3< T >::CreateTight ( int  n,
const Point3< T > *  points,
T  threshold = 1.01,
T  speed = 0.6 
) [inline, inherited]

Definition at line 200 of file sphere3.h.

template<class ScalarType >
bool vcg::Cross ( const Point2< ScalarType > &  p00,
const Point2< ScalarType > &  p01,
const Point2< ScalarType > &  p10,
const Point2< ScalarType > &  p11 
) [inline]

A very simple earcut tessellation of planar 2D polygon. Input: a vector or Point2<> Output: a vector of faces as a triple of indices to the input vector

Definition at line 41 of file planar_polygon_tessellation.h.

template<class T, bool NORM = true>
const PointType& vcg::Plane3< T, NORM >::Direction (  )  const [inline, inherited]

Definition at line 120 of file plane3.h.

template<class T >
T vcg::Distance ( const Sphere3< T > &  sphere,
const Sphere3< T > &  s 
) [inline]

Definition at line 114 of file sphere3.h.

template<class T >
T vcg::Distance ( const Sphere3< T > &  sphere,
const Point3< T > &  point 
) [inline]

Definition at line 107 of file sphere3.h.

template<class T >
T vcg::Distance ( const Point3< T > &  point,
const Plane3< T > &  plane 
) [inline]

Definition at line 189 of file plane3.h.

template<class T >
T vcg::Distance ( const Plane3< T > &  plane,
const Point3< T > &  point 
) [inline]

Distance plane - point and vv. (Move these function to somewhere else).

Definition at line 178 of file plane3.h.

template<class ScalarType , bool NORM>
ScalarType vcg::Distance ( const Line3< ScalarType, NORM > &  l,
const Point3< ScalarType > &  p 
) [inline]

Definition at line 210 of file line3.h.

template<class ScalarType , bool NORM>
ScalarType vcg::Distance ( const Line2< ScalarType, NORM > &  l,
const Point2< ScalarType > &  p 
) [inline]

Definition at line 194 of file line2.h.

template<class T >
T vcg::Distance ( const Point4< T > &  p1,
const Point4< T > &  p2 
) [inline]

Definition at line 362 of file deprecated_point4.h.

template<class P3ScalarType >
P3ScalarType vcg::Distance ( Point3< P3ScalarType > const &  p1,
Point3< P3ScalarType > const &  p2 
) [inline]

Definition at line 466 of file deprecated_point3.h.

template<class T >
T vcg::Distance ( Point2< T > const &  p1,
Point2< T > const &  p2 
) [inline]

Definition at line 348 of file deprecated_point2.h.

template<int N, class S >
S vcg::ndim::Distance ( Point< N, S > const &  p1,
Point< N, S > const &  p2 
) [inline]

Definition at line 903 of file deprecated_point.h.

template<class ScalarType >
ScalarType vcg::DistancePoint2Box2 ( const Point2< ScalarType > &  test,
const Box2< ScalarType > &  bbox 
) [inline]

test possible position respect to bounding box

Definition at line 263 of file box2.h.

template<class ScalarType >
ScalarType vcg::DistancePoint3Box3 ( const Point3< ScalarType > &  p,
const Box3< ScalarType > &  b 
) [inline]

if fall inside return distance to a face

Definition at line 381 of file box3.h.

template<class TriangleType >
TriangleType::ScalarType vcg::DoubleArea ( const TriangleType &  t  )  [inline]

Return the Double of area of the triangle.

Definition at line 451 of file triangle3.h.

template<typename T >
static double vcg::ColorSpace< T >::gamma ( RGBSpaces  rgb_space  )  [inline, static, inherited]

Definition at line 1312 of file colorspace.h.

template<class T>
Box3< T > vcg::Point3< T >::GetBBox ( Box3< T > &  bb  )  const [inline, inherited]

Definition at line 375 of file box3.h.

template<class P3ScalarType >
void vcg::GetUV ( Point3< P3ScalarType > &  n,
Point3< P3ScalarType > &  u,
Point3< P3ScalarType > &  v,
Point3< P3ScalarType >  up = (Point3<P3ScalarType>(0,1,0)) 
) [inline]

Definition at line 528 of file deprecated_point3.h.

template<typename T >
static void vcg::ColorSpace< T >::HSLtoRGB ( double  H,
double  S,
double  L,
double &  R,
double &  G,
double &  B 
) [inline, static, inherited]

Definition at line 1843 of file colorspace.h.

template<typename T >
static Color4<T> vcg::ColorSpace< T >::HSLtoRGB ( const Color4< T > &  color  )  [inline, static, inherited]

Definition at line 1833 of file colorspace.h.

template<typename T >
static void vcg::ColorSpace< T >::HSVtoRGB ( double  H,
double  S,
double  V,
double &  R,
double &  G,
double &  B 
) [inline, static, inherited]

Definition at line 1508 of file colorspace.h.

template<typename T >
static Color4<T> vcg::ColorSpace< T >::HSVtoRGB ( const Color4< T > &  color  )  [inline, static, inherited]

Definition at line 1499 of file colorspace.h.

template<typename T >
static double vcg::ColorSpace< T >::Hue2RGB ( double  v1,
double  v2,
double  vH 
) [inline, static, inherited]

Definition at line 1869 of file colorspace.h.

template<class T, bool NORM = true>
template<class Q >
void vcg::Plane3< T, NORM >::Import ( const Plane3< Q, false > &  b  )  [inline, inherited]

Definition at line 103 of file plane3.h.

template<class T, bool NORM = true>
void vcg::Plane3< T, NORM >::Init ( const PointType p0,
const PointType norm 
) [inline, inherited]

Calculates the plane passing through a point and the normal (Rename this method.

Definition at line 168 of file plane3.h.

template<class T, bool NORM = true>
void vcg::Plane3< T, NORM >::Init ( const PointType p0,
const PointType p1,
const PointType p2 
) [inline, inherited]

Calculates the plane passing through three points (Rename this method).

Definition at line 161 of file plane3.h.

template<class TriangleType , class ScalarType >
bool vcg::InterpolationParameters ( const TriangleType  t,
const Point3< ScalarType > &  N,
const Point3< ScalarType > &  bq,
ScalarType a,
ScalarType b,
ScalarType c 
) [inline]

Calcola i coefficienti della combinazione convessa.

Parameters:
bq Punto appartenente alla faccia
a Valore di ritorno per il vertice V(0)
b Valore di ritorno per il vertice V(1)
_c Valore di ritorno per il vertice V(2)
Returns:
true se bq appartiene alla faccia, false altrimenti

Definition at line 254 of file triangle3.h.

template<class TriangleType , class ScalarType >
bool vcg::InterpolationParameters ( const TriangleType  t,
const Point3< ScalarType > &  N,
const Point3< ScalarType > &  P,
Point3< ScalarType > &  L 
) [inline]

Handy Wrapper of the above one that uses the passed normal N to choose the right orientation.

Definition at line 189 of file triangle3.h.

template<class TriangleType , class ScalarType >
bool vcg::InterpolationParameters ( const TriangleType  t,
const int  Axis,
const Point3< ScalarType > &  P,
Point3< ScalarType > &  L 
) [inline]

Definition at line 178 of file triangle3.h.

template<class ScalarTriangleType >
bool vcg::Triangle3< ScalarTriangleType >::InterpolationParameters ( const CoordType bq,
ScalarType a,
ScalarType b,
ScalarType _c 
) const [inline, inherited]

Definition at line 144 of file triangle3.h.

template<class SCALAR_TYPE >
bool vcg::Triangle2< SCALAR_TYPE >::InterpolationParameters ( const CoordType bq,
ScalarType a,
ScalarType b,
ScalarType c 
) const [inline, inherited]

evaluate barycentric coordinates

Parameters:
bq Point on the face
a barycentric value for V(0)
b barycentric value for V(1)
c barycentric value for V(2)
Returns:
true se bq appartain to the face, false otherwise

test inside/outside

approximation errors

Definition at line 85 of file triangle2.h.

template<class ScalarType >
bool vcg::InterpolationParameters2 ( const Point2< ScalarType > &  V1,
const Point2< ScalarType > &  V2,
const Point2< ScalarType > &  V3,
const Point2< ScalarType > &  P,
Point3< ScalarType > &  L 
) [inline]

Definition at line 213 of file triangle3.h.

template<class T >
void vcg::Sphere3< T >::Intersect ( const Sphere3< T > &  sphere  )  [inline, inherited]

Definition at line 176 of file sphere3.h.

template<class S >
bool vcg::Intersect ( int  cur,
int  v2,
std::vector< int > &  next,
std::vector< Point2< S > > &  points2 
) [inline]

Definition at line 54 of file planar_polygon_tessellation.h.

template<class T >
bool vcg::IntersectionLineBox ( const Box3< T > &  box,
const Line3< T > &  r,
Point3< T > &  coord 
) [inline]

Definition at line 530 of file intersection3.h.

template<class T >
bool vcg::IntersectionLinePlane ( const Plane3< T > &  pl,
const Line3< T > &  li,
Point3< T > &  po 
) [inline]

intersection between line and plane

Definition at line 339 of file intersection3.h.

template<class T >
bool vcg::IntersectionLineSphere ( const Sphere3< T > &  sp,
const Line3< T > &  li,
Point3< T > &  p0,
Point3< T > &  p1 
) [inline]

interseciton between sphere and line

Function computing the intersection between couple of geometric primitives in 3 dimension

Definition at line 165 of file intersection3.h.

template<class T >
bool vcg::IntersectionLineTriangle ( const Line3< T > &  line,
const Point3< T > &  vert0,
const Point3< T > &  vert1,
const Point3< T > &  vert2,
T &  t,
T &  u,
T &  v 
) [inline]

Definition at line 457 of file intersection3.h.

template<class ScalarType >
bool vcg::IntersectionPlaneBox ( const vcg::Plane3< ScalarType > &  pl,
vcg::Box3< ScalarType > &  bbox 
) [inline]

Definition at line 711 of file intersection3.h.

template<class T >
bool vcg::IntersectionPlanePlane ( const Plane3< T > &  plane0,
const Plane3< T > &  plane1,
Line3< T > &  line 
) [inline]

Definition at line 828 of file intersection3.h.

template<class T >
bool vcg::IntersectionPlaneSegment ( const Plane3< T > &  pl,
const Segment3< T > &  s,
Point3< T > &  p0 
) [inline]

intersection between segment and plane

Definition at line 352 of file intersection3.h.

template<class ScalarType >
bool vcg::IntersectionPlaneSegmentEpsilon ( const Plane3< ScalarType > &  pl,
const Segment3< ScalarType > &  sg,
Point3< ScalarType > &  po,
const ScalarType  epsilon = ScalarType(1e-8) 
) [inline]

intersection between segment and plane

Definition at line 362 of file intersection3.h.

template<class ScalarType >
bool vcg::IntersectionPlaneSphere ( const Plane3< ScalarType > &  pl,
const Sphere3< ScalarType > &  sphere,
Point3< ScalarType > &  center,
ScalarType radius 
) [inline]

if exists return the center and ardius of circle that is the intersectionk between the sphere and

Definition at line 736 of file intersection3.h.

template<typename TRIANGLETYPE >
bool vcg::IntersectionPlaneTriangle ( const Plane3< typename TRIANGLETYPE::ScalarType > &  pl,
const TRIANGLETYPE &  tr,
Segment3< typename TRIANGLETYPE::ScalarType > &  sg 
) [inline]

intersection between plane and triangle

Definition at line 381 of file intersection3.h.

template<class T >
bool vcg::IntersectionRayBox ( const Box3< T > &  box,
const Ray3< T > &  r,
Point3< T > &  coord 
) [inline]

Definition at line 604 of file intersection3.h.

template<class T >
bool vcg::IntersectionRayTriangle ( const Ray3< T > &  ray,
const Point3< T > &  vert0,
const Point3< T > &  vert1,
const Point3< T > &  vert2,
T &  t,
T &  u,
T &  v 
) [inline]

Definition at line 516 of file intersection3.h.

template<class ScalarType >
int vcg::IntersectionSegmentBox ( const Box3< ScalarType > &  box,
const Segment3< ScalarType > &  s,
Point3< ScalarType > &  coord0,
Point3< ScalarType > &  coord1 
) [inline]

Definition at line 639 of file intersection3.h.

template<class ScalarType >
bool vcg::IntersectionSegmentBox ( const Box3< ScalarType > &  box,
const Segment3< ScalarType > &  s,
Point3< ScalarType > &  coord 
) [inline]

Definition at line 614 of file intersection3.h.

template<class SCALAR_TYPE >
int vcg::IntersectionSegmentSphere ( const Sphere3< SCALAR_TYPE > &  sphere,
const Segment3< SCALAR_TYPE > &  segment,
Point3< SCALAR_TYPE > &  t0,
Point3< SCALAR_TYPE > &  t1 
) [inline]

Definition at line 202 of file intersection3.h.

template<class TriangleType >
bool vcg::IntersectionSegmentTriangle ( const vcg::Segment3< typename TriangleType::ScalarType > &  seg,
const TriangleType &  t,
typename TriangleType::ScalarType a,
typename TriangleType::ScalarType b,
typename TriangleType::ScalarType dist 
) [inline]

Compute the intersection between a segment and a triangle. Wrapper of the above function

Definition at line 703 of file intersection3.h.

template<class ScalarType >
bool vcg::IntersectionSegmentTriangle ( const vcg::Segment3< ScalarType > &  seg,
const Point3< ScalarType > &  vert0,
const Point3< ScalarType > &  vert1,
const Point3< ScalarType > &  vert2,
ScalarType a,
ScalarType b,
ScalarType dist 
) [inline]

Compute the intersection between a segment and a triangle. It relies on the lineTriangle Intersection

Parameters:
[in] segment 
[in] triangle vertices
[out] (t,u,v) the intersection point, meaningful only if the line of segment intersects the triangle t is the baricentric coord of the point on the segment (u,v) are the baricentric coords of the intersection point in the segment

Definition at line 669 of file intersection3.h.

template<class SphereType >
bool vcg::IntersectionSphereSphere ( const SphereType &  s0,
const SphereType &  s1 
) [inline]

Definition at line 823 of file intersection3.h.

template<class SCALAR_TYPE , class TRIANGLETYPE >
bool vcg::IntersectionSphereTriangle ( const vcg::Sphere3< SCALAR_TYPE > &  sphere,
TRIANGLETYPE  triangle,
vcg::Point3< SCALAR_TYPE > &  witness,
std::pair< SCALAR_TYPE, SCALAR_TYPE > *  res = NULL 
) [inline]

Compute the intersection between a sphere and a triangle.

Parameters:
[in] sphere the input sphere
[in] triangle the input triangle
[out] witness it is the point on the triangle nearest to the center of the sphere (even when there isn't intersection)
[out] res if not null, in the first item is stored the minimum distance between the triangle and the sphere, while in the second item is stored the penetration depth
Returns:
true iff there is an intersection between the sphere and the triangle

Definition at line 253 of file intersection3.h.

template<class ScalarType >
bool vcg::IntersectionTriangleBox ( const vcg::Box3< ScalarType > &  bbox,
const vcg::Point3< ScalarType > &  p0,
const vcg::Point3< ScalarType > &  p1,
const vcg::Point3< ScalarType > &  p2 
) [inline]

control bounding box collision

control if each point is inside the bouding box

then control intersection of segments with box

control intersection of diagonal of the cube with triangle

Definition at line 775 of file intersection3.h.

template<class T >
bool vcg::IntersectionTriangleTriangle ( Point3< T >  V0,
Point3< T >  V1,
Point3< T >  V2,
Point3< T >  U0,
Point3< T >  U1,
Point3< T >  U2 
) [inline]

Definition at line 414 of file intersection3.h.

template<typename TRIANGLETYPE >
bool vcg::IntersectionTriangleTriangle ( const TRIANGLETYPE &  t0,
const TRIANGLETYPE &  t1 
) [inline]

intersection between two triangles

Definition at line 408 of file intersection3.h.

template<class T >
void vcg::isect2 ( Point3< T >  VTX0,
Point3< T >  VTX1,
Point3< T >  VTX2,
float  VV0,
float  VV1,
float  VV2,
float  D0,
float  D1,
float  D2,
float *  isect0,
float *  isect1,
Point3< T > &  isectpoint0,
Point3< T > &  isectpoint1 
) [inline]

Definition at line 376 of file triangle_triangle3.h.

template<class T>
bool vcg::Sphere3< T >::IsEmpty (  )  const [inline, inherited]

Definition at line 89 of file sphere3.h.

template<class T>
bool vcg::Sphere3< T >::IsIn ( const Sphere3< T > &  p  )  const [inline, inherited]

Definition at line 169 of file sphere3.h.

template<class T>
bool vcg::Sphere3< T >::IsIn ( const Point3< T > &  p  )  const [inline, inherited]

return true if

Parameters:
p - Center() <= Radius()

Definition at line 163 of file sphere3.h.

template<class SCALAR_TYPE >
bool vcg::IsInsideTrianglePoint ( const Triangle2< SCALAR_TYPE > &  t,
const Point2< SCALAR_TYPE > &  p 
) [inline]

interseciton between point and triangle

first test with bounding box

then text convex

Definition at line 193 of file intersection2.h.

template<class T >
void vcg::Color4< T >::lerp ( const Color4< T > &  c0,
const Color4< T > &  c1,
const Color4< T > &  c2,
const Point3f ip 
) [inline, inherited]

Definition at line 266 of file color4.h.

template<class T >
void vcg::Color4< T >::lerp ( const Color4< T > &  c0,
const Color4< T > &  c1,
const float  x 
) [inline, inherited]

Definition at line 254 of file color4.h.

template<class SCALAR_TYPE >
bool vcg::LineLineIntersection ( const vcg::Line2< SCALAR_TYPE > &  l0,
const vcg::Line2< SCALAR_TYPE > &  l1,
Point2< SCALAR_TYPE > &  p 
) [inline]

return if exist the intersection point between 2 lines in a 2d plane

first line

second line

then find intersection

denominator

Definition at line 61 of file intersection2.h.

template<class SCALAR_TYPE >
bool vcg::LineSegmentIntersection ( const vcg::Line2< SCALAR_TYPE > &  line,
const vcg::Segment2< SCALAR_TYPE > &  seg,
Point2< SCALAR_TYPE > &  p_inters 
) [inline]

interseciton between point and triangle

first compute intersection between lines

then test if intersection point is nearest to both extremes then lenght of the segment

Definition at line 137 of file intersection2.h.

template<class SCALARTYPE >
Point3<SCALARTYPE> vcg::LowClampToZero ( const Point3< SCALARTYPE > &  p  )  [inline]

Definition at line 558 of file deprecated_point3.h.

template<class ScalarType , bool NORM>
vcg::Point2<ScalarType> vcg::Mirror ( const vcg::Line2< ScalarType, NORM > &  l,
const vcg::Point2< ScalarType > &  p 
) [inline]

Definition at line 201 of file line2.h.

template<class T >
bool vcg::NoDivTriTriIsect ( const Point3< T >  V0,
const Point3< T >  V1,
const Point3< T >  V2,
const Point3< T >  U0,
const Point3< T >  U1,
const Point3< T >  U2 
) [inline]

Definition at line 245 of file triangle_triangle3.h.

template<class T >
T vcg::Norm ( const Point4< T > &  p  )  [inline]

Definition at line 350 of file deprecated_point4.h.

template<class P3ScalarType >
P3ScalarType vcg::Norm ( Point3< P3ScalarType > const &  p  )  [inline]

Definition at line 447 of file deprecated_point3.h.

template<class T >
T vcg::Norm ( Point2< T > const &  p  )  [inline]

Definition at line 333 of file deprecated_point2.h.

template<int N, class S >
S vcg::ndim::Norm ( Point< N, S > const &  p  )  [inline]

Definition at line 884 of file deprecated_point.h.

template<class Point3Type >
Point3Type vcg::Normal ( Point3Type const &  p0,
Point3Type const &  p1,
Point3Type const &  p2 
) [inline]

Definition at line 423 of file triangle3.h.

template<class TriangleType >
Point3<typename TriangleType::ScalarType> vcg::Normal ( const TriangleType &  t  )  [inline]

Returns the normal to the plane passing through p0,p1,p2.

Definition at line 418 of file triangle3.h.

template<class TetraType >
Point3<typename TetraType::ScalarType> vcg::Normal ( const TetraType &  t,
const int &  face 
) [inline]

Returns the normal to the face face of the tetrahedron t.

Definition at line 504 of file tetra3.h.

template<class T, bool NORM = true>
void vcg::Plane3< T, NORM >::Normalize ( void   )  [inline, inherited]

Function to normalize direction.

Definition at line 156 of file plane3.h.

template<class P3ScalarType >
Point3<P3ScalarType>& vcg::Normalize ( Point3< P3ScalarType > &  p  )  [inline]

Definition at line 459 of file deprecated_point3.h.

template<class T >
Point2<T>& vcg::Normalize ( Point2< T > &  p  )  [inline]

Definition at line 343 of file deprecated_point2.h.

template<int N, class S >
Point<N,S>& vcg::ndim::Normalize ( Point< N, S > &  p  )  [inline]

Definition at line 896 of file deprecated_point.h.

template<class Point3Type >
Point3Type vcg::NormalizedNormal ( Point3Type const &  p0,
Point3Type const &  p1,
Point3Type const &  p2 
) [inline]

Definition at line 436 of file triangle3.h.

template<class TriangleType >
Point3<typename TriangleType::ScalarType> vcg::NormalizedNormal ( const TriangleType &  t  )  [inline]

Like the above, it returns the normal to the plane passing through p0,p1,p2, but normalized.

Definition at line 431 of file triangle3.h.

template<class T, bool NORM = true>
ScalarType& vcg::Plane3< T, NORM >::Offset (  )  [inline, inherited]

Definition at line 116 of file plane3.h.

template<class T, bool NORM = true>
const ScalarType& vcg::Plane3< T, NORM >::Offset (  )  const [inline, inherited]

Definition at line 115 of file plane3.h.

template<class T, bool NORM = true>
bool vcg::Plane3< T, NORM >::operator!= ( Plane3< T, NORM > const &  p  )  const [inline, inherited]

Operator to dispare two lines.

Definition at line 145 of file plane3.h.

template<class T >
Point2<T> vcg::operator* ( const T  s,
Point2< T > const &  p 
) [inline]

Definition at line 328 of file deprecated_point2.h.

template<class T >
Point2<T> vcg::operator- ( Point2< T > const &  p  )  [inline]

Definition at line 323 of file deprecated_point2.h.

template<class T, bool NORM = true>
bool vcg::Plane3< T, NORM >::operator== ( Plane3< T, NORM > const &  p  )  const [inline, inherited]

Operator to compare two lines.

Definition at line 141 of file plane3.h.

template<class ScalarTriangleType >
const CoordType& vcg::Triangle3< ScalarTriangleType >::P ( const int  j  )  const [inline, inherited]

Definition at line 134 of file triangle3.h.

template<class ScalarTriangleType >
CoordType& vcg::Triangle3< ScalarTriangleType >::P ( const int  j  )  [inline, inherited]

Shortcut per accedere ai punti delle facce.

Definition at line 130 of file triangle3.h.

template<class SCALAR_TYPE >
const CoordType& vcg::Triangle2< SCALAR_TYPE >::P ( const int  j  )  const [inline, inherited]

Definition at line 70 of file triangle2.h.

template<class SCALAR_TYPE >
CoordType& vcg::Triangle2< SCALAR_TYPE >::P ( const int  j  )  [inline, inherited]

Shortcut per accedere ai punti delle facce.

Definition at line 66 of file triangle2.h.

template<class ScalarTriangleType >
const CoordType& vcg::Triangle3< ScalarTriangleType >::P0 ( const int  j  )  const [inline, inherited]

Definition at line 135 of file triangle3.h.

template<class ScalarTriangleType >
CoordType& vcg::Triangle3< ScalarTriangleType >::P0 ( const int  j  )  [inline, inherited]

Definition at line 131 of file triangle3.h.

template<class SCALAR_TYPE >
const CoordType& vcg::Triangle2< SCALAR_TYPE >::P0 ( const int  j  )  const [inline, inherited]

Definition at line 71 of file triangle2.h.

template<class SCALAR_TYPE >
CoordType& vcg::Triangle2< SCALAR_TYPE >::P0 ( const int  j  )  [inline, inherited]

Definition at line 67 of file triangle2.h.

template<class ScalarTriangleType >
const CoordType& vcg::Triangle3< ScalarTriangleType >::P1 ( const int  j  )  const [inline, inherited]

Definition at line 136 of file triangle3.h.

template<class ScalarTriangleType >
CoordType& vcg::Triangle3< ScalarTriangleType >::P1 ( const int  j  )  [inline, inherited]

Definition at line 132 of file triangle3.h.

template<class SCALAR_TYPE >
const CoordType& vcg::Triangle2< SCALAR_TYPE >::P1 ( const int  j  )  const [inline, inherited]

Definition at line 72 of file triangle2.h.

template<class SCALAR_TYPE >
CoordType& vcg::Triangle2< SCALAR_TYPE >::P1 ( const int  j  )  [inline, inherited]

Definition at line 68 of file triangle2.h.

template<class ScalarTriangleType >
const CoordType& vcg::Triangle3< ScalarTriangleType >::P2 ( const int  j  )  const [inline, inherited]

Definition at line 137 of file triangle3.h.

template<class ScalarTriangleType >
CoordType& vcg::Triangle3< ScalarTriangleType >::P2 ( const int  j  )  [inline, inherited]

Definition at line 133 of file triangle3.h.

template<class SCALAR_TYPE >
const CoordType& vcg::Triangle2< SCALAR_TYPE >::P2 ( const int  j  )  const [inline, inherited]

Definition at line 73 of file triangle2.h.

template<class SCALAR_TYPE >
CoordType& vcg::Triangle2< SCALAR_TYPE >::P2 ( const int  j  )  [inline, inherited]

Definition at line 69 of file triangle2.h.

template<class TriangleType >
TriangleType::ScalarType vcg::Perimeter ( const TriangleType &  t  )  [inline]

Definition at line 472 of file triangle3.h.

template<class T, bool NORM = true>
vcg::Plane3< T, NORM >::Plane3 ( const ScalarType dist,
const PointType dir 
) [inline, inherited]

The (distance, direction) constructor.

Definition at line 100 of file plane3.h.

template<class T, bool NORM = true>
vcg::Plane3< T, NORM >::Plane3 (  )  [inline, inherited]

The empty constructor.

Definition at line 98 of file plane3.h.

template<class SCALAR_TYPE >
void vcg::Triangle2< SCALAR_TYPE >::PointDistance ( const CoordType q,
ScalarType dist,
CoordType p 
) const [inline, inherited]

return the distance to the point q and neighors point p

find distance to each segment and take minimum

Definition at line 124 of file triangle2.h.

template<class T, bool NORM = true>
PointType vcg::Plane3< T, NORM >::Projection ( const PointType p  )  const [inline, inherited]

Project a point on the plane.

Definition at line 150 of file plane3.h.

template<class P3ScalarType >
P3ScalarType vcg::PSDist ( const Point3< P3ScalarType > &  p,
const Point3< P3ScalarType > &  v1,
const Point3< P3ScalarType > &  v2,
Point3< P3ScalarType > &  q 
) [inline]

Point(p) Edge(v1-v2) dist, q is the point in v1-v2 with min dist.

Definition at line 513 of file deprecated_point3.h.

template<class P3ScalarType >
P3ScalarType vcg::Quality ( Point3< P3ScalarType > const &  p0,
Point3< P3ScalarType > const &  p1,
Point3< P3ScalarType > const &  p2 
) [inline]

Compute a shape quality measure of the triangle composed by points p0,p1,p2 It Returns 2*AreaTri/(MaxEdge^2), the range is range [0.0, 0.866] e.g. Equilateral triangle sqrt(3)/2, halfsquare: 1/2, ... up to a line that has zero quality.

Definition at line 359 of file triangle3.h.

template<class TriangleType >
TriangleType::ScalarType vcg::QualityFace ( const TriangleType &  t  )  [inline]

Returns the normal to the plane passing through p0,p1,p2.

Definition at line 162 of file triangle3.h.

template<class ScalarTriangleType >
ScalarType vcg::Triangle3< ScalarTriangleType >::QualityFace (  )  const [inline, inherited]

Return the _q of the face, the return value is in [0,sqrt(3)/2] = [0 - 0.866.. ].

Definition at line 153 of file triangle3.h.

template<class P3ScalarType >
P3ScalarType vcg::QualityMeanRatio ( Point3< P3ScalarType > const &  p0,
Point3< P3ScalarType > const &  p1,
Point3< P3ScalarType > const &  p2 
) [inline]

Compute a shape quality measure of the triangle composed by points p0,p1,p2 It Returns mean ratio 2sqrt(a, b)/(a+b) where a+b are the eigenvalues of the M^tM of the transformation matrix into a regular simplex the range is range [0, 1]

Definition at line 403 of file triangle3.h.

template<class P3ScalarType >
P3ScalarType vcg::QualityRadii ( Point3< P3ScalarType > const &  p0,
Point3< P3ScalarType > const &  p1,
Point3< P3ScalarType > const &  p2 
) [inline]

Compute a shape quality measure of the triangle composed by points p0,p1,p2 It Returns inradius/circumradius the range is range [0, 1] e.g. Equilateral triangle 1, halfsquare: 0.81, ... up to a line that has zero quality.

Definition at line 382 of file triangle3.h.

template<class T>
const T& vcg::Sphere3< T >::Radius (  )  const [inline, inherited]

Definition at line 85 of file sphere3.h.

template<class T>
T& vcg::Sphere3< T >::Radius (  )  [inline, inherited]

Definition at line 84 of file sphere3.h.

template<class SCALAR_TYPE >
bool vcg::RayLineIntersection ( const vcg::Line2< SCALAR_TYPE > &  l,
const vcg::Ray2< SCALAR_TYPE > &  r,
Point2< SCALAR_TYPE > &  p 
) [inline]

return if exist the intersection point between 2 lines in a 2d plane

construct line from ray

Definition at line 98 of file intersection2.h.

template<class SCALAR_TYPE >
bool vcg::RaySegmentIntersection ( const vcg::Ray2< SCALAR_TYPE > &  r,
const vcg::Segment2< SCALAR_TYPE > &  seg,
Point2< SCALAR_TYPE > &  p_inters 
) [inline]

interseciton between point and triangle

first compute intersection between lines

then test if intersection point is nearest to both extremes then lenght of the segment

Definition at line 115 of file intersection2.h.

template<typename T >
static Illuminant vcg::ColorSpace< T >::refIlluminant ( RGBSpaces  rgb_space  )  [inline, static, inherited]

Definition at line 1381 of file colorspace.h.

template<typename T >
static double vcg::ColorSpace< T >::RGB2XYZ ( int  index  )  [inline, static, private, inherited]

Definition at line 166 of file colorspace.h.

template<typename T >
static void vcg::ColorSpace< T >::RGBtoHSL ( double  R,
double  G,
double  B,
double &  H,
double &  S,
double &  L 
) [inline, static, inherited]

Definition at line 1790 of file colorspace.h.

template<typename T >
static Color4<T> vcg::ColorSpace< T >::RGBtoHSL ( const Color4< T > &  color  )  [inline, static, inherited]

Definition at line 1780 of file colorspace.h.

template<typename T >
static void vcg::ColorSpace< T >::RGBtoHSV ( double  R,
double  G,
double  B,
double &  H,
double &  S,
double &  V 
) [inline, static, inherited]

Definition at line 1464 of file colorspace.h.

template<typename T >
static Color4<T> vcg::ColorSpace< T >::RGBtoHSV ( const Color4< T > &  color  )  [inline, static, inherited]

Definition at line 1455 of file colorspace.h.

template<typename T >
static void vcg::ColorSpace< T >::RGBtoRGB ( double  Ri,
double  Gi,
double  Bi,
RGBSpaces  rgbsrc,
double &  R,
double &  G,
double &  B,
RGBSpaces  rgbdest,
ConeResponse  response = BRADFORD 
) [inline, static, inherited]

Definition at line 1962 of file colorspace.h.

template<typename T >
static Color4<T> vcg::ColorSpace< T >::RGBtoRGB ( const Color4< T > &  color,
RGBSpaces  rgbsrc,
RGBSpaces  rgbdest,
ConeResponse  response = BRADFORD 
) [inline, static, inherited]

Definition at line 1950 of file colorspace.h.

template<typename T >
static void vcg::ColorSpace< T >::RGBtoXYZ ( double  R,
double  G,
double  B,
RGBSpaces  space,
double &  X,
double &  Y,
double &  Z,
Illuminant  dest,
ConeResponse  response = BRADFORD 
) [inline, static, inherited]

Definition at line 1632 of file colorspace.h.

template<typename T >
static Color4<T> vcg::ColorSpace< T >::RGBtoXYZ ( const Color4< T > &  color,
RGBSpaces  space,
Illuminant  dest,
ConeResponse  response = BRADFORD 
) [inline, static, inherited]

Definition at line 1622 of file colorspace.h.

template<class SCALAR_TYPE >
bool vcg::SegmentSegmentIntersection ( const vcg::Segment2< SCALAR_TYPE > &  seg0,
const vcg::Segment2< SCALAR_TYPE > &  seg1,
Point2< SCALAR_TYPE > &  p_inters 
) [inline]

interseciton between point and triangle

Definition at line 159 of file intersection2.h.

template<class T, bool NORM = true>
void vcg::Plane3< T, NORM >::Set ( const PointType dir,
const ScalarType off 
) [inline, inherited]

Definition at line 138 of file plane3.h.

template<class T, bool NORM = true>
void vcg::Plane3< T, NORM >::Set ( const ScalarType off,
const PointType dir 
) [inline, inherited]

sets origin and direction.

Definition at line 127 of file plane3.h.

template<class T, bool NORM = true>
void vcg::Plane3< T, NORM >::SetDirection ( const PointType dir  )  [inline, inherited]

sets the direction

Definition at line 122 of file plane3.h.

template<class T, bool NORM = true>
void vcg::Plane3< T, NORM >::SetOffset ( const ScalarType o  )  [inline, inherited]

sets the origin

Definition at line 118 of file plane3.h.

template<class T>
vcg::Sphere3< T >::Sphere3 ( const Point3< T > &  center,
T  radius 
) [inline, inherited]

Definition at line 82 of file sphere3.h.

template<class T>
vcg::Sphere3< T >::Sphere3 (  )  [inline, inherited]

Definition at line 81 of file sphere3.h.

template<class ScalarType >
ScalarType vcg::SquaredDistance ( Segment3< ScalarType > &  segment,
Point3< ScalarType > &  p 
) [inline]

Definition at line 166 of file segment3.h.

template<class T >
T vcg::SquaredDistance ( const Point3< T > &  point,
const Plane3< T > &  plane 
) [inline]

Definition at line 194 of file plane3.h.

template<class T >
T vcg::SquaredDistance ( const Plane3< T > &  plane,
const Point3< T > &  point 
) [inline]

Definition at line 183 of file plane3.h.

template<class T >
T vcg::SquaredDistance ( const Point4< T > &  p1,
const Point4< T > &  p2 
) [inline]

Definition at line 368 of file deprecated_point4.h.

template<class P3ScalarType >
P3ScalarType vcg::SquaredDistance ( Point3< P3ScalarType > const &  p1,
Point3< P3ScalarType > const &  p2 
) [inline]

Definition at line 472 of file deprecated_point3.h.

template<class T >
T vcg::SquaredDistance ( Point2< T > const &  p1,
Point2< T > const &  p2 
) [inline]

Definition at line 353 of file deprecated_point2.h.

template<int N, class S >
S vcg::ndim::SquaredDistance ( Point< N, S > const &  p1,
Point< N, S > const &  p2 
) [inline]

Definition at line 909 of file deprecated_point.h.

template<class T >
T vcg::SquaredNorm ( const Point4< T > &  p  )  [inline]

Definition at line 356 of file deprecated_point4.h.

template<class P3ScalarType >
P3ScalarType vcg::SquaredNorm ( Point3< P3ScalarType > const &  p  )  [inline]

Definition at line 453 of file deprecated_point3.h.

template<class T >
T vcg::SquaredNorm ( Point2< T > const &  p  )  [inline]

Definition at line 338 of file deprecated_point2.h.

template<int N, class S >
S vcg::ndim::SquaredNorm ( Point< N, S > const &  p  )  [inline]

Definition at line 890 of file deprecated_point.h.

template<class P3ScalarType >
double vcg::stable_dot ( Point3< P3ScalarType > const &  p0,
Point3< P3ScalarType > const &  p1 
) [inline]

Definition at line 481 of file deprecated_point3.h.

template<class T >
double vcg::StableDot ( Point4< T > const &  p0,
Point4< T > const &  p1 
) [inline]

slower version of dot product, more stable (double precision only)

Definition at line 375 of file deprecated_point4.h.

template<class POINT_CONTAINER >
void vcg::TessellatePlanarPolygon2 ( POINT_CONTAINER &  points2,
std::vector< int > &  output 
) [inline]

Definition at line 64 of file planar_polygon_tessellation.h.

template<class POINT_CONTAINER >
void vcg::TessellatePlanarPolygon3 ( POINT_CONTAINER &  points,
std::vector< int > &  output 
) [inline]

A very simple earcut tessellation of planar 2D polygon. Input: a vector or Point3<> Output: a vector of faces as a triple of indices to the input vector

Definition at line 114 of file planar_polygon_tessellation.h.

template<class T >
bool vcg::tri_tri_intersect_with_isectline ( Point3< T >  V0,
Point3< T >  V1,
Point3< T >  V2,
Point3< T >  U0,
Point3< T >  U1,
Point3< T >  U2,
bool &  coplanar,
Point3< T > &  isectpt1,
Point3< T > &  isectpt2 
) [inline]

Definition at line 465 of file triangle_triangle3.h.

template<class SCALAR_TYPE >
vcg::Triangle2< SCALAR_TYPE >::Triangle2 ( const CoordType p0,
const CoordType p1,
const CoordType p2 
) [inline, inherited]

Definition at line 58 of file triangle2.h.

template<class SCALAR_TYPE >
vcg::Triangle2< SCALAR_TYPE >::Triangle2 (  )  [inline, inherited]

Definition at line 55 of file triangle2.h.

template<class ScalarTriangleType >
vcg::Triangle3< ScalarTriangleType >::Triangle3 ( const CoordType c0,
const CoordType c1,
const CoordType c2 
) [inline, inherited]

Definition at line 123 of file triangle3.h.

template<class ScalarTriangleType >
vcg::Triangle3< ScalarTriangleType >::Triangle3 (  )  [inline, inherited]

Definition at line 122 of file triangle3.h.

template<class TriangleType >
void vcg::TrianglePointDistance ( const TriangleType &  t,
const typename TriangleType::CoordType &  q,
typename TriangleType::ScalarType dist,
typename TriangleType::CoordType &  closest 
) [inline]

Computes the distance between a triangle and a point.

Parameters:
t reference to the triangle
q point location
dist distance from p to t
closest perpendicular projection of p onto t

find distance on the plane

control if inside/outside

find minimum distance

Definition at line 502 of file triangle3.h.

template<typename T >
static void vcg::ColorSpace< T >::xyYtoXYZ ( double  x,
double  y,
double  _Y,
double &  X,
double &  Y,
double &  Z 
) [inline, static, inherited]

Definition at line 1900 of file colorspace.h.

template<typename T >
static Color4<T> vcg::ColorSpace< T >::xyYtoXYZ ( const Color4< T > &  color  )  [inline, static, inherited]

Definition at line 1889 of file colorspace.h.

template<typename T >
static double vcg::ColorSpace< T >::XYZ2RGB ( int  index  )  [inline, static, private, inherited]

Definition at line 259 of file colorspace.h.

template<typename T >
static void vcg::ColorSpace< T >::XYZtoCIELab ( double  X,
double  Y,
double  Z,
double &  L,
double &  a,
double &  b,
Illuminant  whiteRef 
) [inline, static, inherited]

Definition at line 1680 of file colorspace.h.

template<typename T >
static Color4<T> vcg::ColorSpace< T >::XYZtoCIELab ( const Color4< T > &  color,
Illuminant  ref 
) [inline, static, inherited]

Definition at line 1671 of file colorspace.h.

template<typename T >
static void vcg::ColorSpace< T >::XYZtoRGB ( double  X,
double  Y,
double  Z,
Illuminant  src,
double &  R,
double &  G,
double &  B,
RGBSpaces  space,
ConeResponse  response = BRADFORD 
) [inline, static, inherited]

Definition at line 1584 of file colorspace.h.

template<typename T >
static Color4<T> vcg::ColorSpace< T >::XYZtoRGB ( const Color4< T > &  color,
Illuminant  src,
RGBSpaces  dest,
ConeResponse  response = BRADFORD 
) [inline, static, inherited]

Definition at line 1574 of file colorspace.h.

template<typename T >
static void vcg::ColorSpace< T >::XYZtoxyY ( double  X,
double  _Y,
double  Z,
double &  x,
double &  y,
double &  Y 
) [inline, static, inherited]

Definition at line 1918 of file colorspace.h.

template<typename T >
static Color4<T> vcg::ColorSpace< T >::XYZtoxyY ( const Color4< T > &  color  )  [inline, static, inherited]

Definition at line 1907 of file colorspace.h.


Variable Documentation

template<class T, bool NORM = true>
PointType vcg::Plane3< T, NORM >::_dir [private, inherited]

Direction (not necessarily normalized unless NORM is true).

Definition at line 91 of file plane3.h.

template<class T, bool NORM = true>
ScalarType vcg::Plane3< T, NORM >::_offset [private, inherited]

Distance.

Definition at line 89 of file plane3.h.

template<class T>
T vcg::Sphere3< T >::_radius [protected, inherited]

Definition at line 78 of file sphere3.h.

template<class ScalarTriangleType >
Point3<ScalarType> vcg::Triangle3< ScalarTriangleType >::_v[3] [protected, inherited]

Vector of vertex pointer incident in the face.

Definition at line 126 of file triangle3.h.

template<class SCALAR_TYPE >
Point2<ScalarType> vcg::Triangle2< SCALAR_TYPE >::_v[3] [protected, inherited]

Vector of vertex pointer incident in the face.

Definition at line 52 of file triangle2.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


vcglib
Author(s): Christian Bersch
autogenerated on Fri Jan 11 09:21:30 2013