opennurbs_box.cpp
Go to the documentation of this file.
00001 #include "pcl/surface/3rdparty/opennurbs/opennurbs.h"
00002 
00003 ON_Box::ON_Box()
00004 {}
00005 
00006 ON_Box::ON_Box( const ON_BoundingBox& bbox )
00007 {
00008   Create(bbox);
00009 }
00010 
00011 ON_Box::~ON_Box()
00012 {}
00013 
00014 void ON_Box::Destroy()
00015 {
00016   plane = ON_xy_plane;
00017   dx.Destroy();
00018   dy.Destroy();
00019   dz.Destroy();
00020 }
00021 
00022 bool ON_Box::IsValid() const
00023 {
00024   return (    dx.IsIncreasing() 
00025            && dy.IsIncreasing() 
00026            && dz.IsIncreasing() 
00027            && plane.IsValid() 
00028          );
00029 }
00030 
00031 bool ON_Box::Create( const ON_BoundingBox& bbox )
00032 {
00033   plane = ON_xy_plane;
00034   dx.Set(bbox.m_min.x,bbox.m_max.x);
00035   dy.Set(bbox.m_min.y,bbox.m_max.y);
00036   dz.Set(bbox.m_min.z,bbox.m_max.z);
00037   return (dx.IsValid() && dy.IsValid() && dz.IsValid());
00038 }
00039 
00040 int ON_Box::IsDegenerate( double tolerance ) const
00041 {
00042   int rc = 0;
00043   // 0     box is not degenerate
00044   // 1     box is a rectangle (degenerate in one direction)
00045   // 2     box is a line (degenerate in two directions)
00046   // 3     box is a point (degenerate in three directions)
00047   // 4     box is not valid
00048   if ( !dx.IsIncreasing() || !dy.IsIncreasing() || !dz.IsIncreasing() )
00049   {
00050     rc = 4;
00051   }
00052   else
00053   {
00054     const ON_3dVector diag(dx.Length(),dy.Length(),dz.Length());
00055     if ( !ON_IsValid(tolerance) || tolerance < 0.0 )
00056     {
00057       // compute scale invarient tolerance
00058       tolerance = diag.MaximumCoordinate()*ON_SQRT_EPSILON;
00059     }
00060     if ( diag.x <= tolerance )
00061       rc++;
00062     if ( diag.y <= tolerance )
00063       rc++;
00064     if ( diag.z <= tolerance )
00065       rc++;
00066   }
00067   return rc;
00068 }
00069 
00070 ON_3dPoint ON_Box::Center() const
00071 {
00072   return plane.PointAt(dz.Mid(),dy.Mid(),dz.Mid());
00073 }
00074 
00075 bool ON_Box::GetCorners( ON_3dPoint* corners ) const
00076 {
00077   int i,j,k,n=0;
00078   double r,s,t;
00079   for( i= 0; i < 2; i++ )
00080   {
00081     r = dx.m_t[i];
00082     for ( j = 0; j < 2; j++ )
00083     {
00084       s = dy.m_t[j];
00085       for ( k = 0; k < 2; k++ )
00086       {
00087         t = dz.m_t[k];
00088         corners[n++] = plane.PointAt(r,s,t);
00089       }
00090     }
00091   }
00092   return true;
00093 }
00094 
00095 bool ON_Box::GetCorners( ON_SimpleArray<ON_3dPoint>& corners ) const
00096 {
00097   corners.Empty();
00098   corners.Reserve(8);
00099   bool rc = GetCorners(corners.Array());
00100   if (rc)
00101     corners.SetCount(8);
00102   return rc;
00103 }
00104 
00105 ON_BoundingBox ON_Box::BoundingBox() const
00106 {
00107   ON_BoundingBox bbox;
00108   ON_3dPoint corners[8];
00109   if ( GetCorners(corners) )
00110     bbox.Set(3,0,8,3,&corners[0].x,false);
00111   return bbox;
00112 }
00113 
00114 ON_3dPoint ON_Box::PointAt( 
00115         double r, 
00116         double s, 
00117         double t 
00118         ) const
00119 {
00120   // Do not validate - it is too slow.
00121   return plane.PointAt(r,s,t);
00122 }
00123 
00124 // returns point on cylinder that is closest to given point
00125 bool ON_Box::ClosestPointTo( ON_3dPoint point, double* r, double* s, double* t ) const
00126 {
00127   // Do not validate box - it is too slow.
00128   const ON_3dVector v = point - plane.origin;
00129 
00130   *r = v*plane.xaxis;
00131   if ( *r < dx.m_t[0] )
00132     *r = dx.m_t[0];
00133   else if ( *r > dx.m_t[1] )
00134     *r = dx.m_t[1];
00135 
00136   *s = v*plane.yaxis;
00137   if ( *s < dy.m_t[0] )
00138     *s = dy.m_t[0];
00139   else if ( *s > dy.m_t[1] )
00140     *s = dy.m_t[1];
00141 
00142   *t = v*plane.zaxis;
00143   if ( *t < dz.m_t[0] )
00144     *t = dz.m_t[0];
00145   else if ( *t > dz.m_t[1] )
00146     *t = dz.m_t[1];
00147 
00148   return true;
00149 }
00150 
00151 ON_3dPoint ON_Box::ClosestPointTo( ON_3dPoint point ) const
00152 {
00153   // Do not validate - it is too slow.
00154   double r,s,t;
00155   ClosestPointTo(point,&r,&s,&t);
00156   return PointAt(r,s,t);
00157 }
00158 
00159 // rotate box about its center
00160 bool ON_Box::Rotate(
00161       double sin_angle,
00162       double cos_angle,
00163       const ON_3dVector& axis // axis of rotation
00164       )
00165 {
00166   return Rotate(sin_angle, cos_angle, axis, Center() );
00167 }
00168 
00169 bool ON_Box::Rotate(
00170       double angle,           // angle in radians
00171       const ON_3dVector& axis // axis of rotation
00172       )
00173 {
00174   return Rotate(sin(angle), cos(angle), axis, plane.origin );
00175 }
00176 
00177 // rotate box about a point and axis
00178 bool ON_Box::Rotate(
00179       double sin_angle,
00180       double cos_angle,
00181       const ON_3dVector& axis, // axis of rotation
00182       const ON_3dPoint&  point // center of rotation
00183       )
00184 {
00185   return plane.Rotate( sin_angle, cos_angle, axis, point );
00186 }
00187 
00188 bool ON_Box::Rotate(
00189       double angle,             // angle in radians
00190       const ON_3dVector& axis,  // axis of rotation
00191       const ON_3dPoint&  point  // center of rotation
00192       )
00193 {
00194   return Rotate(sin(angle),cos(angle),axis,point);
00195 }
00196 
00197 bool ON_Box::Translate(
00198       const ON_3dVector& delta
00199       )
00200 {
00201   return plane.Translate(delta);
00202 }
00203 
00204 
00205 bool ON_Box::Transform( const ON_Xform& xform )
00206 {
00207   ON_3dPoint corners[8];
00208   bool rc = GetCorners(corners);
00209   if ( rc )
00210   {
00211     ON_Plane xplane(plane);
00212     rc = xplane.Transform(xform);
00213     if ( rc )
00214     {
00215       int i;
00216       for ( i = 0; i < 8; i++ )
00217       {
00218         corners[i] = xform*corners[i];
00219       }
00220       double x0,x1,x,y0,y1,y,z0,z1,z;
00221       ON_3dVector v = corners[7] - plane.origin;
00222       x0 = x1 = v*plane.xaxis;
00223       y0 = y1 = v*plane.yaxis;
00224       z0 = z1 = v*plane.zaxis;
00225       for ( i = 0; i < 7; i++ )
00226       {
00227         v = corners[i] - plane.origin;
00228         x = v*plane.xaxis;
00229         if ( x < x0 ) x0 = x; else if (x > x1 ) x1 = x;
00230         y = v*plane.yaxis;
00231         if ( y < y0 ) y0 = y; else if (y > y1 ) y1 = y;
00232         z = v*plane.zaxis;
00233         if ( z < z0 ) z0 = z; else if (z > z1 ) z1 = z;
00234       }
00235       double tol = ON_SQRT_EPSILON;
00236       if ( fabs(dx.ParameterAt(x0)) > tol || fabs(dx.ParameterAt(x1)-1.0) > tol )
00237         dx.Set(x0,x1);
00238       if ( fabs(dy.ParameterAt(y0)) > tol || fabs(dy.ParameterAt(y1)-1.0) > tol )
00239         dy.Set(y0,y1);
00240       if ( fabs(dz.ParameterAt(z0)) > tol || fabs(dz.ParameterAt(z1)-1.0) > tol )
00241         dz.Set(z0,z1);
00242     }
00243   }
00244   return rc;
00245 }
00246 
00247 double ON_Box::Volume() const
00248 {
00249   return dx.Length()*dy.Length()*dz.Length();
00250 }
00251 
00252 double ON_Box::Area() const
00253 {
00254   double a = dx.Length();
00255   double b = dy.Length();
00256   double c = dz.Length();
00257   return 2.0*(a*b + b*c + c*a);
00258 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:27:00