Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #ifndef __VCGLIB_GRID_UTIL
00025 #define __VCGLIB_GRID_UTIL
00026
00027 #include<vcg/space/index/base.h>
00028 #include<vcg/space/box3.h>
00029 #include <vcg/space/index/space_iterators.h>
00030
00031
00032 #ifndef WIN32
00033 #define __int64 long long
00034 #define __cdecl
00035 #endif
00036
00037 namespace vcg {
00038
00053 template <class SCALARTYPE>
00054 class BasicGrid
00055 {
00056 public:
00057
00058 typedef SCALARTYPE ScalarType;
00059 typedef Box3<ScalarType> Box3x;
00060 typedef Point3<ScalarType> CoordType;
00061 typedef BasicGrid<SCALARTYPE> GridType;
00062
00063 Box3x bbox;
00064
00065 CoordType dim;
00066 Point3i siz;
00067 CoordType voxel;
00068
00069
00070
00071
00072
00073 void ComputeDimAndVoxel()
00074 {
00075 this->dim = this->bbox.max - this->bbox.min;
00076 this->voxel[0] = this->dim[0]/this->siz[0];
00077 this->voxel[1] = this->dim[1]/this->siz[1];
00078 this->voxel[2] = this->dim[2]/this->siz[2];
00079 }
00080
00081
00082
00083
00084 inline Point3i GridP( const Point3<ScalarType> & p ) const
00085 {
00086 Point3i pi;
00087 PToIP(p, pi);
00088 return pi;
00089 }
00090
00091
00092
00093
00094
00095 inline void PToIP(const CoordType & p, Point3i &pi ) const
00096 {
00097 CoordType t = p - bbox.min;
00098 pi[0] = int( t[0] / voxel[0] );
00099 pi[1] = int( t[1] / voxel[1] );
00100 pi[2] = int( t[2] / voxel[2] );
00101 }
00102
00103
00104
00105
00106
00107 template <class OtherScalarType>
00108 inline void IPiToPf(const Point3i & pi, Point3<OtherScalarType> &p ) const
00109 {
00110 p[0] = bbox.min[0] + ((OtherScalarType)pi[0])*voxel[0];
00111 p[1] = bbox.min[1] + ((OtherScalarType)pi[1])*voxel[1];
00112 p[2] = bbox.min[2] + ((OtherScalarType)pi[2])*voxel[2];
00113 }
00114
00115
00116
00117 inline Matrix44<ScalarType> IPtoPfMatrix() const
00118 {
00119 Matrix44<ScalarType> m; m.SetScale(voxel);
00120 Matrix44<ScalarType> t; t.SetTranslate(bbox.min);
00121 return t*m;
00122 }
00123
00124
00125
00126
00127 inline void IPiToBox(const Point3i & pi, Box3x & b ) const
00128 {
00129 CoordType p;
00130 p[0] = ((ScalarType)pi[0])*voxel[0];
00131 p[1] = ((ScalarType)pi[1])*voxel[1];
00132 p[2] = ((ScalarType)pi[2])*voxel[2];
00133 p += bbox.min;
00134 b.min = p;
00135 b.max = (p + voxel);
00136 }
00137
00138
00139
00140
00141 inline void IPiToBoxCenter(const Point3i & pi, CoordType & c ) const
00142 {
00143 CoordType p;
00144 IPiToPf(pi,p);
00145 c = p + voxel/ScalarType(2.0);
00146 }
00147
00148
00149
00150 template <class OtherScalarType>
00151 void IPfToPf(const Point3<OtherScalarType> & pi, Point3<OtherScalarType> &p ) const
00152 {
00153 p[0] = ((OtherScalarType)pi[0])*voxel[0] + bbox.min[0];
00154 p[1] = ((OtherScalarType)pi[1])*voxel[1] + bbox.min[1];
00155 p[2] = ((OtherScalarType)pi[2])*voxel[2] + bbox.min[2];
00156 }
00157
00158
00159
00160
00161
00162 inline void BoxToIBox( const Box3x & b, Box3i & ib ) const
00163 {
00164 PToIP(b.min, ib.min);
00165 PToIP(b.max, ib.max);
00166
00167 }
00168
00169
00170
00171
00172
00174 void IBoxToBox( const Box3i & ib, Box3x & b ) const
00175 {
00176 IPiToPf(ib.min,b.min);
00177 IPiToPf(ib.max+Point3i(1,1,1),b.max);
00178 }
00179 };
00180
00181 template<class scalar_type>
00182 void BestDim( const Box3<scalar_type> box, const scalar_type voxel_size, Point3i & dim )
00183 {
00184 Point3<scalar_type> box_size = box.max-box.min;
00185 __int64 elem_num = (__int64)(box_size[0]/voxel_size +0.5) *( __int64)(box_size[1]/voxel_size +0.5) * (__int64)(box_size[2]/voxel_size +0.5);
00186 BestDim(elem_num,box_size,dim);
00187 }
00192 template<class scalar_type>
00193 void BestDim( const __int64 elems, const Point3<scalar_type> & size, Point3i & dim )
00194 {
00195 const __int64 mincells = 1;
00196 const double GFactor = 1;
00197 double diag = size.Norm();
00198 double eps = diag*1e-4;
00199
00200 assert(elems>0);
00201 assert(size[0]>=0.0);
00202 assert(size[1]>=0.0);
00203 assert(size[2]>=0.0);
00204
00205
00206 __int64 ncell = (__int64)(elems*GFactor);
00207 if(ncell<mincells)
00208 ncell = mincells;
00209
00210 dim[0] = 1;
00211 dim[1] = 1;
00212 dim[2] = 1;
00213
00214 if(size[0]>eps)
00215 {
00216 if(size[1]>eps)
00217 {
00218 if(size[2]>eps)
00219 {
00220 double k = pow((double)(ncell/(size[0]*size[1]*size[2])),double(1.0/3.f));
00221 dim[0] = int(size[0] * k);
00222 dim[1] = int(size[1] * k);
00223 dim[2] = int(size[2] * k);
00224 }
00225 else
00226 {
00227 dim[0] = int(::sqrt(ncell*size[0]/size[1]));
00228 dim[1] = int(::sqrt(ncell*size[1]/size[0]));
00229 }
00230 }
00231 else
00232 {
00233 if(size[2]>eps)
00234 {
00235 dim[0] = int(::sqrt(ncell*size[0]/size[2]));
00236 dim[2] = int(::sqrt(ncell*size[2]/size[0]));
00237 }
00238 else
00239 dim[0] = int(ncell);
00240 }
00241 }
00242 else
00243 {
00244 if(size[1]>eps)
00245 {
00246 if(size[2]>eps)
00247 {
00248 dim[1] = int(::sqrt(ncell*size[1]/size[2]));
00249 dim[2] = int(::sqrt(ncell*size[2]/size[1]));
00250 }
00251 else
00252 dim[1] = int(ncell);
00253 }
00254 else if(size[2]>eps)
00255 dim[2] = int(ncell);
00256 }
00257 dim[0] = std::max(dim[0],1);
00258 dim[1] = std::max(dim[1],1);
00259 dim[2] = std::max(dim[2],1);
00260 }
00261 }
00262 #endif