IceAABB.cpp
Go to the documentation of this file.
00001 
00002 
00008 
00009 
00011 
00017 
00018 
00020 // Precompiled Header
00021 #include "Stdafx.h"
00022 
00023 using namespace IceMaths;
00024 
00026 
00031 
00032 AABB& AABB::Add(const AABB& aabb)
00033 {
00034         // Compute new min & max values
00035         Point Min;      GetMin(Min);
00036         Point Tmp;      aabb.GetMin(Tmp);
00037         Min.Min(Tmp);
00038 
00039         Point Max;      GetMax(Max);
00040         aabb.GetMax(Tmp);
00041         Max.Max(Tmp);
00042 
00043         // Update this
00044         SetMinMax(Min, Max);
00045         return *this;
00046 }
00047 
00049 
00054 
00055 float AABB::MakeCube(AABB& cube) const
00056 {
00057         Point Ext;      GetExtents(Ext);
00058         float Max = Ext.Max();
00059 
00060         Point Cnt;      GetCenter(Cnt);
00061         cube.SetCenterExtents(Cnt, Point(Max, Max, Max));
00062         return Max;
00063 }
00064 
00066 
00070 
00071 void AABB::MakeSphere(Sphere& sphere) const
00072 {
00073         GetExtents(sphere.mCenter);
00074         sphere.mRadius = sphere.mCenter.Magnitude() * 1.00001f; // To make sure sphere::Contains(*this) succeeds
00075         GetCenter(sphere.mCenter);
00076 }
00077 
00079 
00084 
00085 bool AABB::IsInside(const AABB& box) const
00086 {
00087         if(box.GetMin(0)>GetMin(0))     return false;
00088         if(box.GetMin(1)>GetMin(1))     return false;
00089         if(box.GetMin(2)>GetMin(2))     return false;
00090         if(box.GetMax(0)<GetMax(0))     return false;
00091         if(box.GetMax(1)<GetMax(1))     return false;
00092         if(box.GetMax(2)<GetMax(2))     return false;
00093         return true;
00094 }
00095 
00097 
00102 
00103 bool AABB::ComputePlanes(Plane* planes) const
00104 {
00105         // Checkings
00106         if(!planes)     return false;
00107 
00108         Point Center, Extents;
00109         GetCenter(Center);
00110         GetExtents(Extents);
00111 
00112         // Writes normals
00113         planes[0].n = Point(1.0f, 0.0f, 0.0f);
00114         planes[1].n = Point(-1.0f, 0.0f, 0.0f);
00115         planes[2].n = Point(0.0f, 1.0f, 0.0f);
00116         planes[3].n = Point(0.0f, -1.0f, 0.0f);
00117         planes[4].n = Point(0.0f, 0.0f, 1.0f);
00118         planes[5].n = Point(0.0f, 0.0f, -1.0f);
00119 
00120         // Compute a point on each plane
00121         Point p0 = Point(Center.x+Extents.x, Center.y, Center.z);
00122         Point p1 = Point(Center.x-Extents.x, Center.y, Center.z);
00123         Point p2 = Point(Center.x, Center.y+Extents.y, Center.z);
00124         Point p3 = Point(Center.x, Center.y-Extents.y, Center.z);
00125         Point p4 = Point(Center.x, Center.y, Center.z+Extents.z);
00126         Point p5 = Point(Center.x, Center.y, Center.z-Extents.z);
00127 
00128         // Compute d
00129         planes[0].d = -(planes[0].n|p0);
00130         planes[1].d = -(planes[1].n|p1);
00131         planes[2].d = -(planes[2].n|p2);
00132         planes[3].d = -(planes[3].n|p3);
00133         planes[4].d = -(planes[4].n|p4);
00134         planes[5].d = -(planes[5].n|p5);
00135 
00136         return true;
00137 }
00138 
00140 
00145 
00146 bool AABB::ComputePoints(Point* pts)    const
00147 {
00148         // Checkings
00149         if(!pts)        return false;
00150 
00151         // Get box corners
00152         Point min;      GetMin(min);
00153         Point max;      GetMax(max);
00154 
00155         //     7+------+6                       0 = ---
00156         //     /|     /|                        1 = +--
00157         //    / |    / |                        2 = ++-
00158         //   / 4+---/--+5                       3 = -+-
00159         // 3+------+2 /    y   z        4 = --+
00160         //  | /    | /     |  /         5 = +-+
00161         //  |/     |/      |/           6 = +++
00162         // 0+------+1      *---x        7 = -++
00163 
00164         // Generate 8 corners of the bbox
00165         pts[0] = Point(min.x, min.y, min.z);
00166         pts[1] = Point(max.x, min.y, min.z);
00167         pts[2] = Point(max.x, max.y, min.z);
00168         pts[3] = Point(min.x, max.y, min.z);
00169         pts[4] = Point(min.x, min.y, max.z);
00170         pts[5] = Point(max.x, min.y, max.z);
00171         pts[6] = Point(max.x, max.y, max.z);
00172         pts[7] = Point(min.x, max.y, max.z);
00173 
00174         return true;
00175 }
00176 
00178 
00183 
00184 const Point* AABB::GetVertexNormals()   const
00185 {
00186         static float VertexNormals[] = 
00187         {
00188                 -INVSQRT3,      -INVSQRT3,      -INVSQRT3,
00189                 INVSQRT3,       -INVSQRT3,      -INVSQRT3,
00190                 INVSQRT3,       INVSQRT3,       -INVSQRT3,
00191                 -INVSQRT3,      INVSQRT3,       -INVSQRT3,
00192                 -INVSQRT3,      -INVSQRT3,      INVSQRT3,
00193                 INVSQRT3,       -INVSQRT3,      INVSQRT3,
00194                 INVSQRT3,       INVSQRT3,       INVSQRT3,
00195                 -INVSQRT3,      INVSQRT3,       INVSQRT3
00196         };
00197         return (const Point*)VertexNormals;
00198 }
00199 
00201 
00205 
00206 const udword* AABB::GetEdges() const
00207 {
00208         static udword Indices[] = {
00209         0, 1,   1, 2,   2, 3,   3, 0,
00210         7, 6,   6, 5,   5, 4,   4, 7,
00211         1, 5,   6, 2,
00212         3, 7,   4, 0
00213         };
00214         return Indices;
00215 }
00216 
00218 
00222 
00223 const Point* AABB::GetEdgeNormals() const
00224 {
00225         static float EdgeNormals[] = 
00226         {
00227                 0,                      -INVSQRT2,      -INVSQRT2,      // 0-1
00228                 INVSQRT2,       0,                      -INVSQRT2,      // 1-2
00229                 0,                      INVSQRT2,       -INVSQRT2,      // 2-3
00230                 -INVSQRT2,      0,                      -INVSQRT2,      // 3-0
00231 
00232                 0,                      INVSQRT2,       INVSQRT2,       // 7-6
00233                 INVSQRT2,       0,                      INVSQRT2,       // 6-5
00234                 0,                      -INVSQRT2,      INVSQRT2,       // 5-4
00235                 -INVSQRT2,      0,                      INVSQRT2,       // 4-7
00236 
00237                 INVSQRT2,       -INVSQRT2,      0,                      // 1-5
00238                 INVSQRT2,       INVSQRT2,       0,                      // 6-2
00239                 -INVSQRT2,      INVSQRT2,       0,                      // 3-7
00240                 -INVSQRT2,      -INVSQRT2,      0                       // 4-0
00241         };
00242         return (const Point*)EdgeNormals;
00243 }
00244 
00245 // ===========================================================================
00246 //  (C) 1996-98 Vienna University of Technology
00247 // ===========================================================================
00248 //  NAME:       bboxarea
00249 //  TYPE:       c++ code
00250 //  PROJECT:    Bounding Box Area
00251 //  CONTENT:    Computes area of 2D projection of 3D oriented bounding box
00252 //  VERSION:    1.0
00253 // ===========================================================================
00254 //  AUTHORS:    ds      Dieter Schmalstieg
00255 //              ep      Erik Pojar
00256 // ===========================================================================
00257 //  HISTORY:
00258 //
00259 //  19-sep-99 15:23:03  ds      last modification
00260 //  01-dec-98 15:23:03  ep      created
00261 // ===========================================================================
00262 
00263 //----------------------------------------------------------------------------
00264 // SAMPLE CODE STARTS HERE
00265 //----------------------------------------------------------------------------
00266 
00267 // NOTE: This sample program requires OPEN INVENTOR!
00268 
00269 //indexlist: this table stores the 64 possible cases of classification of
00270 //the eyepoint with respect to the 6 defining planes of the bbox (2^6=64)
00271 //only 26 (3^3-1, where 1 is "inside" cube) of these cases are valid.
00272 //the first 6 numbers in each row are the indices of the bbox vertices that
00273 //form the outline of which we want to compute the area (counterclockwise
00274 //ordering), the 7th entry means the number of vertices in the outline.
00275 //there are 6 cases with a single face and and a 4-vertex outline, and
00276 //20 cases with 2 or 3 faces and a 6-vertex outline. a value of 0 indicates
00277 //an invalid case.
00278 
00279 
00280 // Original list was made of 7 items, I added an 8th element:
00281 // - to padd on a cache line
00282 // - to repeat the first entry to avoid modulos
00283 //
00284 // I also replaced original ints with sbytes.
00285 
00286 static const sbyte gIndexList[64][8] =
00287 {
00288     {-1,-1,-1,-1,-1,-1,-1,   0}, // 0 inside
00289     { 0, 4, 7, 3, 0,-1,-1,   4}, // 1 left
00290     { 1, 2, 6, 5, 1,-1,-1,   4}, // 2 right
00291     {-1,-1,-1,-1,-1,-1,-1,   0}, // 3 -
00292     { 0, 1, 5, 4, 0,-1,-1,   4}, // 4 bottom
00293     { 0, 1, 5, 4, 7, 3, 0,   6}, // 5 bottom, left
00294     { 0, 1, 2, 6, 5, 4, 0,   6}, // 6 bottom, right
00295     {-1,-1,-1,-1,-1,-1,-1,   0}, // 7 -
00296     { 2, 3, 7, 6, 2,-1,-1,   4}, // 8 top
00297     { 0, 4, 7, 6, 2, 3, 0,   6}, // 9 top, left
00298     { 1, 2, 3, 7, 6, 5, 1,   6}, //10 top, right
00299     {-1,-1,-1,-1,-1,-1,-1,   0}, //11 -
00300     {-1,-1,-1,-1,-1,-1,-1,   0}, //12 -
00301     {-1,-1,-1,-1,-1,-1,-1,   0}, //13 -
00302     {-1,-1,-1,-1,-1,-1,-1,   0}, //14 -
00303     {-1,-1,-1,-1,-1,-1,-1,   0}, //15 -
00304     { 0, 3, 2, 1, 0,-1,-1,   4}, //16 front
00305     { 0, 4, 7, 3, 2, 1, 0,   6}, //17 front, left
00306     { 0, 3, 2, 6, 5, 1, 0,   6}, //18 front, right
00307     {-1,-1,-1,-1,-1,-1,-1,   0}, //19 -
00308     { 0, 3, 2, 1, 5, 4, 0,   6}, //20 front, bottom
00309     { 1, 5, 4, 7, 3, 2, 1,   6}, //21 front, bottom, left
00310     { 0, 3, 2, 6, 5, 4, 0,   6}, //22 front, bottom, right
00311     {-1,-1,-1,-1,-1,-1,-1,   0}, //23 -
00312     { 0, 3, 7, 6, 2, 1, 0,   6}, //24 front, top
00313     { 0, 4, 7, 6, 2, 1, 0,   6}, //25 front, top, left
00314     { 0, 3, 7, 6, 5, 1, 0,   6}, //26 front, top, right
00315     {-1,-1,-1,-1,-1,-1,-1,   0}, //27 -
00316     {-1,-1,-1,-1,-1,-1,-1,   0}, //28 -
00317     {-1,-1,-1,-1,-1,-1,-1,   0}, //29 -
00318     {-1,-1,-1,-1,-1,-1,-1,   0}, //30 -
00319     {-1,-1,-1,-1,-1,-1,-1,   0}, //31 -
00320     { 4, 5, 6, 7, 4,-1,-1,   4}, //32 back
00321     { 0, 4, 5, 6, 7, 3, 0,   6}, //33 back, left
00322     { 1, 2, 6, 7, 4, 5, 1,   6}, //34 back, right
00323     {-1,-1,-1,-1,-1,-1,-1,   0}, //35 -
00324     { 0, 1, 5, 6, 7, 4, 0,   6}, //36 back, bottom
00325     { 0, 1, 5, 6, 7, 3, 0,   6}, //37 back, bottom, left
00326     { 0, 1, 2, 6, 7, 4, 0,   6}, //38 back, bottom, right
00327     {-1,-1,-1,-1,-1,-1,-1,   0}, //39 -
00328     { 2, 3, 7, 4, 5, 6, 2,   6}, //40 back, top
00329     { 0, 4, 5, 6, 2, 3, 0,   6}, //41 back, top, left
00330     { 1, 2, 3, 7, 4, 5, 1,   6}, //42 back, top, right
00331     {-1,-1,-1,-1,-1,-1,-1,   0}, //43 invalid
00332     {-1,-1,-1,-1,-1,-1,-1,   0}, //44 invalid
00333     {-1,-1,-1,-1,-1,-1,-1,   0}, //45 invalid
00334     {-1,-1,-1,-1,-1,-1,-1,   0}, //46 invalid
00335     {-1,-1,-1,-1,-1,-1,-1,   0}, //47 invalid
00336     {-1,-1,-1,-1,-1,-1,-1,   0}, //48 invalid
00337     {-1,-1,-1,-1,-1,-1,-1,   0}, //49 invalid
00338     {-1,-1,-1,-1,-1,-1,-1,   0}, //50 invalid
00339     {-1,-1,-1,-1,-1,-1,-1,   0}, //51 invalid
00340     {-1,-1,-1,-1,-1,-1,-1,   0}, //52 invalid
00341     {-1,-1,-1,-1,-1,-1,-1,   0}, //53 invalid
00342     {-1,-1,-1,-1,-1,-1,-1,   0}, //54 invalid
00343     {-1,-1,-1,-1,-1,-1,-1,   0}, //55 invalid
00344     {-1,-1,-1,-1,-1,-1,-1,   0}, //56 invalid
00345     {-1,-1,-1,-1,-1,-1,-1,   0}, //57 invalid
00346     {-1,-1,-1,-1,-1,-1,-1,   0}, //58 invalid
00347     {-1,-1,-1,-1,-1,-1,-1,   0}, //59 invalid
00348     {-1,-1,-1,-1,-1,-1,-1,   0}, //60 invalid
00349     {-1,-1,-1,-1,-1,-1,-1,   0}, //61 invalid
00350     {-1,-1,-1,-1,-1,-1,-1,   0}, //62 invalid
00351     {-1,-1,-1,-1,-1,-1,-1,   0}  //63 invalid
00352 };
00353 
00354 const sbyte* AABB::ComputeOutline(const Point& local_eye, sdword& num)  const
00355 {
00356         // Get box corners
00357         Point min;      GetMin(min);
00358         Point max;      GetMax(max);
00359 
00360         // Compute 6-bit code to classify eye with respect to the 6 defining planes of the bbox
00361         int pos = ((local_eye.x < min.x) ?  1 : 0)      // 1 = left
00362                         + ((local_eye.x > max.x) ?  2 : 0)      // 2 = right
00363                         + ((local_eye.y < min.y) ?  4 : 0)      // 4 = bottom
00364                         + ((local_eye.y > max.y) ?  8 : 0)      // 8 = top
00365                         + ((local_eye.z < min.z) ? 16 : 0)      // 16 = front
00366                         + ((local_eye.z > max.z) ? 32 : 0);     // 32 = back
00367 
00368         // Look up number of vertices in outline
00369         num = (sdword)gIndexList[pos][7];
00370         // Zero indicates invalid case
00371         if(!num) return null;
00372 
00373         return &gIndexList[pos][0];
00374 }
00375 
00376 // calculateBoxArea: computes the screen-projected 2D area of an oriented 3D bounding box
00377 
00378 //const Point&          eye,            //eye point (in bbox object coordinates)
00379 //const AABB&                   box,            //3d bbox
00380 //const Matrix4x4&      mat,            //free transformation for bbox
00381 //float width, float height, int& num)
00382 float AABB::ComputeBoxArea(const Point& eye, const Matrix4x4& mat, float width, float height, sdword& num)      const
00383 {
00384         const sbyte* Outline = ComputeOutline(eye, num);
00385         if(!Outline)    return -1.0f;
00386 
00387         // Compute box vertices
00388         Point vertexBox[8], dst[8];
00389         ComputePoints(vertexBox);
00390 
00391         // Transform all outline corners into 2D screen space
00392         for(sdword i=0;i<num;i++)
00393         {
00394                 HPoint Projected;
00395                 vertexBox[Outline[i]].ProjectToScreen(width, height, mat, Projected);
00396                 dst[i] = Projected;
00397         }
00398 
00399         float Sum = (dst[num-1][0] - dst[0][0]) * (dst[num-1][1] + dst[0][1]);
00400 
00401         for(int i=0; i<num-1; i++)
00402                 Sum += (dst[i][0] - dst[i+1][0]) * (dst[i][1] + dst[i+1][1]);
00403 
00404         return Sum * 0.5f;      //return computed value corrected by 0.5
00405 }


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Thu Apr 11 2019 03:30:16