00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #ifndef VCG_USE_EIGEN
00025 #include "deprecated_point3.h"
00026 #else
00027
00028 #ifndef __VCGLIB_POINT3
00029 #define __VCGLIB_POINT3
00030
00031 #include "../math/eigen.h"
00032
00033 namespace vcg{
00034 template<typename Scalar> class Point3;
00035 }
00036
00037 namespace Eigen{
00038
00039 template<typename Scalar> struct ei_traits<vcg::Point3<Scalar> > : ei_traits<Eigen::Matrix<Scalar,3,1> > {};
00040
00041 template<typename XprType> struct ei_to_vcgtype<XprType,3,1,0,3,1>
00042 { typedef vcg::Point3<typename XprType::Scalar> type; };
00043
00044 template<typename Scalar>
00045 struct NumTraits<vcg::Point3<Scalar> > : NumTraits<Scalar>
00046 {
00047 enum {
00048 ReadCost = 3,
00049 AddCost = 3,
00050 MulCost = 3
00051 };
00052 };
00053
00054 }
00055
00056 namespace vcg {
00057
00058 template<typename Scalar> class Box3;
00059
00067 template <class _Scalar> class Point3 : public Eigen::Matrix<_Scalar,3,1>
00068 {
00069
00070
00071
00072
00073 public:
00074 typedef Eigen::Matrix<_Scalar,3,1> Type;
00075
00076
00077
00078 private:
00079 typedef Eigen::Matrix<_Scalar,3,1> _Base;
00080 public:
00081
00082 using _Base::Construct;
00083 _EIGEN_GENERIC_PUBLIC_INTERFACE(Point3,_Base);
00084 VCG_EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Point3)
00085
00086
00090 inline Point3 () {}
00091 inline Point3 ( const Scalar nx, const Scalar ny, const Scalar nz ) : Base(nx,ny,nz) {}
00092 inline Point3 ( Point3 const & p ) : Base(p) {}
00093 inline Point3 ( const Scalar nv[3] ) : Base(nv) {}
00094 template<typename OtherDerived>
00095 inline Point3(const Eigen::MatrixBase<OtherDerived>& other) : Base(other) {}
00096
00097
00098
00099 template <class Q>
00100 static inline Point3 Construct( const Q & P0, const Q & P1, const Q & P2)
00101 {
00102 return Point3(Scalar(P0),Scalar(P1),Scalar(P2));
00103 }
00104 vcg::Box3<_Scalar> GetBBox(vcg::Box3<_Scalar> &bb) const;
00105
00106 };
00107
00108
00109
00110
00111 template<class Scalar>
00112 double stable_dot ( Point3<Scalar> const & p0, Point3<Scalar> const & p1 )
00113 {
00114 Scalar k0 = p0.data()[0]*p1.data()[0];
00115 Scalar k1 = p0.data()[1]*p1.data()[1];
00116 Scalar k2 = p0.data()[2]*p1.data()[2];
00117
00118 int exp0,exp1,exp2;
00119
00120 frexp( double(k0), &exp0 );
00121 frexp( double(k1), &exp1 );
00122 frexp( double(k2), &exp2 );
00123
00124 if( exp0<exp1 )
00125 {
00126 if(exp0<exp2)
00127 return (k1+k2)+k0;
00128 else
00129 return (k0+k1)+k2;
00130 }
00131 else
00132 {
00133 if(exp1<exp2)
00134 return(k0+k2)+k1;
00135 else
00136 return (k0+k1)+k2;
00137 }
00138 }
00139
00141 template<class Scalar>
00142 Scalar PSDist( const Point3<Scalar> & p,
00143 const Point3<Scalar> & v1,
00144 const Point3<Scalar> & v2,
00145 Point3<Scalar> & q )
00146 {
00147 Point3<Scalar> e = v2-v1;
00148 Scalar t = ((p-v1).dot(e))/e.SquaredNorm();
00149 if(t<0) t = 0;
00150 else if(t>1) t = 1;
00151 q = v1+e*t;
00152 return Distance(p,q);
00153 }
00154
00155 template <class Scalar>
00156 void GetUV( Point3<Scalar> &n,Point3<Scalar> &u, Point3<Scalar> &v, Point3<Scalar> up=(Point3<Scalar>(0,1,0)) )
00157 {
00158 n.Normalize();
00159 const double LocEps=double(1e-7);
00160 u=n^up;
00161 double len = u.Norm();
00162 if(len < LocEps)
00163 {
00164 if(fabs(n[0])<fabs(n[1])){
00165 if(fabs(n[0])<fabs(n[2])) up=Point3<Scalar>(1,0,0);
00166 else up=Point3<Scalar>(0,0,1);
00167 }else {
00168 if(fabs(n[1])<fabs(n[2])) up=Point3<Scalar>(0,1,0);
00169 else up=Point3<Scalar>(0,0,1);
00170 }
00171 u=n^up;
00172 }
00173 u.Normalize();
00174 v=n^u;
00175 v.Normalize();
00176 Point3<Scalar> uv=u^v;
00177 }
00178
00181 typedef Point3<short> Point3s;
00182 typedef Point3<int> Point3i;
00183 typedef Point3<float> Point3f;
00184 typedef Point3<double> Point3d;
00185
00186
00187
00188
00189
00190
00191
00192
00193
00194
00195 }
00196
00197 #endif
00198
00199 #endif