opennurbs_viewport.cpp
Go to the documentation of this file.
00001 /* $NoKeywords: $ */
00002 /*
00003 //
00004 // Copyright (c) 1993-2012 Robert McNeel & Associates. All rights reserved.
00005 // OpenNURBS, Rhinoceros, and Rhino3D are registered trademarks of Robert
00006 // McNeel & Associates.
00007 //
00008 // THIS SOFTWARE IS PROVIDED "AS IS" WITHOUT EXPRESS OR IMPLIED WARRANTY.
00009 // ALL IMPLIED WARRANTIES OF FITNESS FOR ANY PARTICULAR PURPOSE AND OF
00010 // MERCHANTABILITY ARE HEREBY DISCLAIMED.
00011 //                              
00012 // For complete openNURBS copyright information see <http://www.opennurbs.org>.
00013 //
00015 */
00016 
00017 #include "pcl/surface/3rdparty/opennurbs/opennurbs.h"
00018 
00019 ON_OBJECT_IMPLEMENT( ON_Viewport, ON_Geometry, "D66E5CCF-EA39-11d3-BFE5-0010830122F0" );
00020 
00021 static double len2d( double x, double y )
00022 {
00023   double d= 0.0;
00024   double fx = fabs(x);
00025   double fy = fabs(y);
00026   if ( fx > fy ) {
00027     d = fy/fx;
00028     d = fx*sqrt(1.0+d*d);
00029   }
00030   else if ( fy > fx ){
00031     d = fx/fy;
00032     d = fy*sqrt(1.0+d*d);
00033   }
00034   return d;
00035 }
00036 
00037 static void unitize2d( double x, double y, double* ux, double* uy )
00038 {
00039   const double eps = 2.0*ON_SQRT_EPSILON;
00040   // carefully turn two numbers into a 2d unit vector
00041   double s, c, d;
00042   c = x;
00043   s = y;
00044   if ( s == 0.0 ) {
00045     c = (c < 0.0) ? -1.0 : 1.0;
00046   }
00047   else {
00048     if ( fabs(s) > fabs(c) ) {
00049       d = c/s;
00050       d = fabs(s)*sqrt(1.0+d*d);
00051     }
00052     else {
00053       d = s/c;
00054       d = fabs(c)*sqrt(1.0+d*d);
00055     }
00056     d = 1.0/d;
00057     if ( fabs(d-1.0) > eps ) {
00058       s *= d;
00059       c *= d;
00060     }
00061     if ( fabs(s) <= eps || fabs(c) >= 1.0-eps ) {
00062       s = 0.0;
00063       c = (c < 0.0) ? -1.0 : 1.0;
00064     }
00065     else if ( fabs(c) < eps || fabs(s) >= 1.0-eps) {
00066       c = 0.0;
00067       s = (s < 0.0) ? -1.0 : 1.0;
00068     }
00069   }
00070   if ( ux ) 
00071     *ux = c;
00072   if ( uy )
00073     *uy = s;
00074 }
00075 
00076 
00077 static
00078 bool ON__IsCameraFrameUnitVectorHelper( const ON_3dVector& v )
00079 {
00080   // looser standard than ON_3dVector::IsUnitVector() so
00081   // going to/from floats in OpenGL and Direct3d doesn't
00082   // create "invalid" views.
00083   return (v.x != ON_UNSET_VALUE && v.y != ON_UNSET_VALUE && v.z != ON_UNSET_VALUE && fabs(v.Length() - 1.0) <= 1.0e-6);
00084 }
00085 
00086 static
00087 bool ON__IsCameraFramePerpindicular( const ON_3dVector& unit_vector0,const ON_3dVector& unit_vector1 )
00088 {
00089   return ( fabs(unit_vector0.x*unit_vector1.x + unit_vector0.y*unit_vector1.y + unit_vector0.z*unit_vector1.z) <= 1.0e-6 );
00090 }
00091 
00092 bool 
00093 ON_GetViewportRotationAngles( 
00094     const ON_3dVector& X, // X,Y,Z must be a right handed orthonormal basis
00095     const ON_3dVector& Y, 
00096     const ON_3dVector& Z,
00097     double* angle1, // returns rotation about world Z
00098     double* angle2, // returns rotation about world X ( 0 <= a2 <= pi )
00099     double* angle3  // returns rotation about world Z
00100     )
00101 {
00102   // double a1 = 0.0;  // rotation about world Z
00103   // double a2 = 0.0;  // rotation about world X ( 0 <= a2 <= pi )
00104   // double a3 = 0.0;  // rotation about world Z
00105   bool bValidFrame = false;
00106   double sin_a1 = 0.0;
00107   double cos_a1 = 1.0;
00108   double sin_a2 = 0.0;
00109   double cos_a2 = 1.0;
00110   double sin_a3 = 0.0;
00111   double cos_a3 = 1.0;
00112 
00113   // If si = sin(ai) and ci = cos(ai), then the relationship between the camera
00114   // frame and the angles is defined by the matrix equation C = R3*R2*R1, where:
00115   //
00116   //      c1 -s1  0        1   0   0         c3 -s3  0
00117   // R1 = s1  c1  0  R2 =  0  c2 -s2   R3 =  s3  c3  0
00118   //       0   0  1        0  s2  c2          0   0  1
00119   //
00120   //     CamX[0]  CamY[0] CamZ[0]
00121   // C = CamX[1]  CamY[1] CamZ[1]
00122   //     CamX[2]  CamY[2] CamZ[2]
00123   //
00124   //              .       .     s2*s3
00125   //
00126   // R3*R2*R1 =   .       .    -s2*c3
00127   //
00128   //            s1*s2   c1*s2    c2
00129   //
00130 
00131   {
00132     // don't attempt to work with slop
00133     const double eps = 8.0*ON_SQRT_EPSILON;
00134     double dx,dy,dz,d;
00135     dx = X*X;
00136     dy = Y*Y;
00137     dz = Z*Z;
00138     if ( fabs(dx-1.0) <= eps && fabs(dy-1.0) <= eps && fabs(dz-1.0) <= eps ) {
00139       dx = X*Y;
00140       dy = Y*Z;
00141       dz = Z*X;
00142       if ( fabs(dx) <= eps && fabs(dy) <= eps && fabs(dz) <= eps ) {
00143         d = ON_TripleProduct( X, Y, Z );
00144         bValidFrame = (d > 0.0);
00145       }
00146     }
00147   }
00148 
00149   if ( bValidFrame ) 
00150   {
00151     // Usually "Z" = opposite of unitized camera direction.
00152     //         "Y" = camera up made ortho to "Z" and unitized.
00153     //         "X" = YxZ.
00154     // So, when possible, I solve for angles in terms
00155     // of "Z" and "Y" since "X" will generally have the most noise.
00156     //         
00157     // Use C = R3*R2*R1 to get sin(a2), cos(a2).
00158     cos_a2 = Z.z;
00159     sin_a2 = len2d(Z.x,Z.y);
00160     unitize2d(cos_a2,sin_a2,&cos_a2,&sin_a2); // kill noise
00161 
00162     if ( sin_a2 > 0.0 ) {
00163       // use bottom row to get angle1.
00164       sin_a1 = X.z;
00165       cos_a1 = Y.z;
00166       unitize2d(cos_a1,sin_a1,&cos_a1,&sin_a1); // kill noise
00167 
00168       // use right column to get angle3
00169       cos_a3 = -Z.y;
00170       sin_a3 =  Z.x;
00171       unitize2d(cos_a3,sin_a3,&cos_a3,&sin_a3); // kill noise
00172     }
00173     else if ( cos_a2 == 1.0 ) {
00174       // R2 = identity and C determines (angle1+angle3)
00175       //      arbitrarily set angle1 = 0.
00176       cos_a3 =  Y.y; // = cos(angle3+angle1)
00177       sin_a3 = -Y.x; // = sin(angle3+angle1)
00178     }
00179     else if ( cos_a2 == -1.0 ) {
00180       // R2 = [1 0 0 / 0 -1 0/ 0 0 -1] and C determines (angle3-angle1)
00181       //      arbitrarily set angle1 = 0
00182       cos_a3 = -Y.y; // = cos(angle3-angle1)
00183       sin_a3 =  Y.x; // = sin(angle3-angle1)
00184     }
00185   }
00186 
00187 
00188   if ( cos_a1 == -1.0 && sin_a1 == 0.0 ) {
00189     // when a1 = pi, juggle angles to get a1 = 0 with
00190     // same effective rotation to keep legacy 3d apps
00191     // happy.
00192     // a1: pi -> 0
00193     // a2: a2 -> 2pi - a2
00194     // a1: a3 ->  pi + a3
00195     sin_a1 = 0.0;
00196     cos_a1 = 0.0;
00197     sin_a2 = -sin_a2;
00198     sin_a3 = -sin_a3;
00199     cos_a3 = -cos_a3;
00200   }
00201   
00202   if ( angle1 )
00203     *angle1 = atan2( sin_a1, cos_a1 );
00204   if ( angle2 )
00205     *angle2 = atan2( sin_a2, cos_a2 );
00206   if ( angle3 )
00207     *angle3 = atan2( sin_a3, cos_a3 );
00208 
00209   return bValidFrame;
00210 }
00211 
00212 void ON_Viewport::SetPerspectiveClippingPlaneConstraints(
00213         unsigned int depth_buffer_bit_depth
00214         )
00215 {
00216   double min_near_dist = 0.0;
00217   double min_near_over_far = 0.0;
00218   ON_Viewport::GetPerspectiveClippingPlaneConstraints(m_CamLoc,depth_buffer_bit_depth,&min_near_dist,&min_near_over_far);
00219   SetPerspectiveMinNearDist(min_near_dist);
00220   SetPerspectiveMinNearOverFar(min_near_over_far);
00221 }
00222 
00223 
00224 void ON_Viewport::SetPerspectiveMinNearOverFar(double min_near_over_far)
00225 {
00226   if (    ON_IsValid(min_near_over_far) 
00227        && min_near_over_far > ON_ZERO_TOLERANCE
00228        && min_near_over_far < 1.0-ON_ZERO_TOLERANCE
00229      )
00230   {
00231     m__MIN_NEAR_OVER_FAR = min_near_over_far;
00232   }
00233 }
00234 
00235 double ON_Viewport::PerspectiveMinNearOverFar() const
00236 {
00237   return m__MIN_NEAR_OVER_FAR;
00238 }
00239 
00240 void ON_Viewport::SetPerspectiveMinNearDist(double min_near_dist)
00241 {
00242   if ( ON_IsValid(min_near_dist) && min_near_dist > ON_ZERO_TOLERANCE )
00243   {
00244     m__MIN_NEAR_DIST = min_near_dist;
00245   }
00246 }
00247 
00248 double ON_Viewport::PerspectiveMinNearDist() const
00249 {
00250   return m__MIN_NEAR_DIST;
00251 }
00252 
00253 
00254 
00255 // Discuss any changes of these values with Dale Lear
00256 const double ON_Viewport::DefaultNearDist = 0.005;
00257 const double ON_Viewport::DefaultFarDist = 1000.0;
00258 const double ON_Viewport::DefaultMinNearDist = 0.0001;
00259 const double ON_Viewport::DefaultMinNearOverFar = 0.0001;
00260 
00261 // For 32 bit float based OpenGL drivers, the value of
00262 // the ON_Viewport::DefaultMinNearOverFar constant must 
00263 // be <0.01 and >= 0.0001.  
00264 // If you change this value, you need to retest RR 8902 on OpenGL
00265 // drivers that (internally) use float precision transformations.
00266 // Some OpenGL drivers, like the Microsoft software emulation
00267 // driver for XP crash in some cases when near/far > 1e8.
00268 //
00269 // ON_Viewport::DefaultMinNearOverFar = 0.001    // used in Rhino 3.0 beta testing until 11 Sep 2002
00270 // ON_Viewport::DefaultMinNearOverFar = 0.01     // used for Rhino 3.0 CD1 and CD2
00271 // ON_Viewport::DefaultMinNearOverFar = 0.000001 // used for Rhino 3.0 CD3
00272 // ON_Viewport::DefaultMinNearOverFar = 0.0001   // used for Rhino 4.0 Fixes RR 8902
00273 
00274 void
00275 ON_Viewport::Initialize()
00276 {
00277   m__MIN_NEAR_DIST     = ON_Viewport::DefaultMinNearDist;
00278   m__MIN_NEAR_OVER_FAR = ON_Viewport::DefaultMinNearOverFar;
00279 
00280   m_bValidCamera = true;
00281   m_bValidFrustum = true;
00282   m_bValidPort = false;
00283   m_reserved1 = 0;
00284   m_projection = ON::parallel_view;
00285 
00286   m_bLockCamUp = false;
00287   m_bLockCamDir = false;
00288   m_bLockCamLoc = false;
00289   m_frustum_symmetry_flags = 0;
00290 
00291   m_CamLoc.x =   0.0;
00292   m_CamLoc.y =   0.0;
00293   m_CamLoc.z = 100.0;
00294   m_CamDir = -ON_zaxis;
00295   m_CamUp = ON_yaxis;
00296   m_CamX = ON_xaxis;
00297   m_CamY = ON_yaxis;
00298   m_CamZ = ON_zaxis;
00299   m_frus_left = -20.0;
00300   m_frus_right = 20.0;
00301   m_frus_bottom = -20.0;
00302   m_frus_top = 20.0;
00303   m_frus_near = m__MIN_NEAR_DIST;
00304   m_frus_far = ON_Viewport::DefaultFarDist;
00305   m_port_left = 0;
00306   m_port_right = 1000;
00307   m_port_bottom = 0;
00308   m_port_top = 1000;
00309   m_port_near = 0;//0xffff;
00310   m_port_far =  1;//0;
00311   m_clip_mods.Identity();
00312   m_clip_mods_inverse.Identity();
00313   m_target_point = ON_UNSET_POINT;
00314   m_viewport_id = ON_nil_uuid;
00315 }
00316 
00317 const ON_3dVector ON_Viewport::Default3dCameraDirection(-0.43301270189221932338186158537647,0.75,-0.5);
00318 
00319 ON_Viewport::ON_Viewport()
00320 {
00321   Initialize();
00322 }
00323 
00324 ON_Viewport::~ON_Viewport()
00325 {}
00326 
00327 ON_Viewport& ON_Viewport::operator=( const ON_Viewport& src )
00328 {
00329   if ( this != &src ) 
00330   {
00331     ON_Object::operator=(src);
00332 
00333     m_bValidCamera   = src.m_bValidCamera;
00334     m_bValidFrustum  = src.m_bValidFrustum;
00335     m_bValidPort     = src.m_bValidPort;
00336 
00337     m_projection     = src.m_projection;
00338 
00339     m_bLockCamUp  = src.m_bLockCamUp;
00340     m_bLockCamDir = src.m_bLockCamDir;
00341     m_bLockCamLoc = src.m_bLockCamLoc;
00342     m_frustum_symmetry_flags = src.m_frustum_symmetry_flags;
00343 
00344     m_CamLoc = src.m_CamLoc;
00345     m_CamDir = src.m_CamDir;
00346     m_CamUp  = src.m_CamUp;
00347     m_CamX   = src.m_CamX;
00348     m_CamY   = src.m_CamY;
00349     m_CamZ   = src.m_CamZ;
00350 
00351     m_frus_left      = src.m_frus_left;
00352     m_frus_right     = src.m_frus_right;
00353     m_frus_bottom    = src.m_frus_bottom;
00354     m_frus_top       = src.m_frus_top;
00355     m_frus_near      = src.m_frus_near;
00356     m_frus_far       = src.m_frus_far;
00357 
00358     m_port_left      = src.m_port_left;
00359     m_port_right     = src.m_port_right;
00360     m_port_bottom    = src.m_port_bottom;
00361     m_port_top       = src.m_port_top;
00362     m_port_near      = src.m_port_near;
00363     m_port_far       = src.m_port_far;
00364 
00365     m_target_point = src.m_target_point;
00366 
00367     m_clip_mods         = src.m_clip_mods;
00368     m_clip_mods_inverse = src.m_clip_mods_inverse;
00369 
00370     m__MIN_NEAR_OVER_FAR = src.m__MIN_NEAR_OVER_FAR;
00371     m__MIN_NEAR_DIST     = src.m__MIN_NEAR_DIST;
00372 
00373     m_viewport_id = src.m_viewport_id;
00374   }
00375   return *this;
00376 }
00377 
00378 
00379 ON_BOOL32 ON_Viewport::Read( ON_BinaryArchive& file )
00380 {
00381   Initialize();
00382   int major_version = 0;
00383   int minor_version = 1;
00384   bool rc = file.Read3dmChunkVersion(&major_version,&minor_version);
00385   if (rc && major_version==1) 
00386   {
00387     // common to all 1.x versions
00388     int i=0;
00389     if (rc) rc = file.ReadInt( &i );
00390     if (rc) m_bValidCamera = (i?true:false);
00391     if (rc) rc = file.ReadInt( &i );
00392     if (rc) m_bValidFrustum = (i?true:false);
00393     if (rc) rc = file.ReadInt( &i );
00394     if (rc) m_bValidPort = (i?true:false);
00395     if (rc) rc = file.ReadInt( &i );
00396     if (rc) m_projection = ON::ViewProjection(i);
00397     if (rc) rc = file.ReadPoint( m_CamLoc );
00398     if (rc) rc = file.ReadVector( m_CamDir );
00399     if (rc) rc = file.ReadVector( m_CamUp );
00400     if (rc) rc = file.ReadVector( m_CamX );
00401     if (rc) rc = file.ReadVector( m_CamY );
00402     if (rc) rc = file.ReadVector( m_CamZ );
00403     if (rc) rc = file.ReadDouble( &m_frus_left );
00404     if (rc) rc = file.ReadDouble( &m_frus_right );
00405     if (rc) rc = file.ReadDouble( &m_frus_bottom );
00406     if (rc) rc = file.ReadDouble( &m_frus_top );
00407     if (rc) rc = file.ReadDouble( &m_frus_near );
00408     if (rc) rc = file.ReadDouble( &m_frus_far );
00409     if (rc) rc = file.ReadInt( &m_port_left );
00410     if (rc) rc = file.ReadInt( &m_port_right );
00411     if (rc) rc = file.ReadInt( &m_port_bottom );
00412     if (rc) rc = file.ReadInt( &m_port_top );
00413     if (rc) rc = file.ReadInt( &m_port_near );
00414     if (rc) rc = file.ReadInt( &m_port_far );   
00415 
00416     if (rc && minor_version >= 1 )
00417     {
00418       // 1.1 fields
00419       if (rc) rc = file.ReadUuid(m_viewport_id);
00420 
00421       if (rc && minor_version >= 2 )
00422       {
00423         // 1.2 fields 
00424         bool b;
00425         b = false;
00426         if (rc) rc = file.ReadBool(&b);
00427         if (rc) SetCameraUpLock(b);
00428 
00429         b = false;
00430         if (rc) rc = file.ReadBool(&b);
00431         if (rc) SetCameraDirectionLock(b);
00432 
00433         b = false;
00434         if (rc) rc = file.ReadBool(&b);
00435         if (rc) SetCameraLocationLock(b);
00436 
00437         b = false;
00438         if (rc) rc = file.ReadBool(&b);
00439         if (rc) SetFrustumLeftRightSymmetry(b);
00440 
00441         b = false;
00442         if (rc) rc = file.ReadBool(&b);
00443         if (rc) SetFrustumTopBottomSymmetry(b);
00444       }
00445     }
00446 
00447     if ( m_bValidCamera )
00448     {
00449       if ( !m_CamLoc.IsValid() || !m_CamUp.IsValid() || !m_CamDir.IsValid() )
00450       {
00451         ON_ERROR("ON_Viewport.m_bValidCamera in file was true and it should be false.");
00452         m_bValidCamera = false;
00453       }
00454     }
00455 
00456     if( m_bValidFrustum )
00457     {
00458       if (    !ON_IsValid(m_frus_left) || !ON_IsValid(m_frus_right)
00459            || !ON_IsValid(m_frus_top)  || !ON_IsValid(m_frus_bottom)
00460            || !ON_IsValid(m_frus_near) || !ON_IsValid(m_frus_far)
00461            || m_frus_right <= m_frus_left
00462            || m_frus_top   <= m_frus_bottom
00463            || m_frus_near  <= 0.0
00464            || m_frus_far   <= m_frus_near
00465          )
00466       {
00467         ON_ERROR("ON_Viewport.m_bValidFrustum in file was true and it should be false.");
00468         m_bValidFrustum = false;
00469       }
00470     }
00471   }
00472   return rc;
00473 }
00474 
00475 ON_BOOL32 ON_Viewport::Write( ON_BinaryArchive& file ) const
00476 {
00477   int i;
00478   bool rc = file.Write3dmChunkVersion(1,2);
00479   if (rc) 
00480   {
00481     i = m_bValidCamera?1:0;
00482     if (rc) rc = file.WriteInt( i );
00483     i = m_bValidFrustum?1:0;
00484     if (rc) rc = file.WriteInt( i );
00485     i = m_bValidPort?1:0;
00486     if (rc) rc = file.WriteInt( i );
00487     i = m_projection;
00488     if ( file.Archive3dmVersion() <= 4 && IsPerspectiveProjection() )
00489     {
00490       // V4 files do not support 2 point perspective projection
00491       i = ON::perspective_view;
00492     }
00493     if (rc) rc = file.WriteInt( i );
00494     if (rc) rc = file.WritePoint( m_CamLoc );
00495     if (rc) rc = file.WriteVector( m_CamDir );
00496     if (rc) rc = file.WriteVector( m_CamUp );
00497     if (rc) rc = file.WriteVector( m_CamX );
00498     if (rc) rc = file.WriteVector( m_CamY );
00499     if (rc) rc = file.WriteVector( m_CamZ );
00500     if (rc) rc = file.WriteDouble( m_frus_left );
00501     if (rc) rc = file.WriteDouble( m_frus_right );
00502     if (rc) rc = file.WriteDouble( m_frus_bottom );
00503     if (rc) rc = file.WriteDouble( m_frus_top );
00504     if (rc) rc = file.WriteDouble( m_frus_near );
00505     if (rc) rc = file.WriteDouble( m_frus_far );
00506     if (rc) rc = file.WriteInt( m_port_left );
00507     if (rc) rc = file.WriteInt( m_port_right );
00508     if (rc) rc = file.WriteInt( m_port_bottom );
00509     if (rc) rc = file.WriteInt( m_port_top );
00510     if (rc) rc = file.WriteInt( m_port_near );
00511     if (rc) rc = file.WriteInt( m_port_far );    
00512 
00513     // 1.1 fields
00514     if (rc) rc = file.WriteUuid(m_viewport_id);
00515 
00516     // 1.2 fields 
00517     bool b;
00518 
00519     b = CameraUpIsLocked();
00520     if (rc) rc = file.WriteBool(b);
00521 
00522     b = CameraDirectionIsLocked();
00523     if (rc) rc = file.WriteBool(b);
00524 
00525     b = CameraLocationIsLocked();
00526     if (rc) rc = file.WriteBool(b);
00527 
00528     b = FrustumIsLeftRightSymmetric();
00529     if (rc) rc = file.WriteBool(b);
00530 
00531     b = FrustumIsTopBottomSymmetric();
00532     if (rc) rc = file.WriteBool(b);
00533   }
00534   return rc;
00535 }
00536 
00537 bool ON_Viewport::IsValidCamera() const
00538 {
00539   return ( m_bValidCamera );
00540 }
00541 
00542 bool ON_Viewport::IsValidFrustum() const
00543 {
00544   return ( m_bValidFrustum );
00545 }
00546 
00547 ON_BOOL32 ON_Viewport::IsValid( ON_TextLog* text_log ) const
00548 {
00549   if ( !IsValidCamera() )
00550   {
00551     if ( 0 != text_log )
00552     {
00553       text_log->Print("invalid viewport camera settings.\n");
00554     }
00555     return false;
00556   }
00557   if ( !IsValidFrustum() )
00558   {
00559     if ( 0 != text_log )
00560     {
00561       text_log->Print("invalid viewport frustum settings.\n");
00562     }
00563     return false;
00564   }
00565   if ( !m_bValidPort )
00566   {
00567     if ( 0 != text_log )
00568     {
00569       text_log->Print("invalid viewport port extents settings.\n");
00570     }
00571     return false;
00572   }
00573   return true;
00574 }
00575 
00576 
00577 int ON_Viewport::Dimension() const
00578 {
00579   return 3;
00580 }
00581 
00582 bool ON_Viewport::GetNearPlane( ON_Plane& near_plane ) const
00583 {
00584   bool rc = IsValidFrustum() && IsValidCamera();
00585   if ( rc ) 
00586   {
00587     near_plane.origin = m_CamLoc - m_frus_near*m_CamZ;
00588     near_plane.xaxis = m_CamX;
00589     near_plane.yaxis = m_CamY;
00590     near_plane.zaxis = m_CamZ;
00591     near_plane.UpdateEquation();
00592   }
00593   return rc;
00594 }
00595 
00596 bool ON_Viewport::GetNearPlaneEquation( 
00597   ON_PlaneEquation& near_plane_equation 
00598   ) const
00599 {
00600   bool rc = m_bValidCamera && m_bValidFrustum;
00601   if (rc)
00602   {
00603     near_plane_equation.ON_3dVector::operator=(m_CamZ);
00604     near_plane_equation.d = -near_plane_equation.ON_3dVector::operator*(m_CamLoc - m_frus_near*m_CamZ);
00605   }
00606   return rc;
00607 }
00608 
00609 
00610 bool ON_Viewport::GetFarPlane( ON_Plane& far_plane ) const
00611 {
00612   bool rc = IsValidFrustum() && IsValidCamera();
00613   if ( rc ) 
00614   {
00615     far_plane.origin = m_CamLoc - m_frus_far*m_CamZ;
00616     far_plane.xaxis = m_CamX;
00617     far_plane.yaxis = m_CamY;
00618     far_plane.zaxis = m_CamZ;
00619     far_plane.UpdateEquation();
00620   }
00621   return rc;
00622 }
00623 
00624 bool ON_Viewport::GetFarPlaneEquation( 
00625   ON_PlaneEquation& far_plane_equation 
00626   ) const
00627 {
00628   bool rc = m_bValidCamera && m_bValidFrustum;
00629   if (rc)
00630   {
00631     far_plane_equation.ON_3dVector::operator=(m_CamZ);
00632     far_plane_equation.d = -far_plane_equation.ON_3dVector::operator*(m_CamLoc - m_frus_far*m_CamZ);
00633   }
00634   return rc;
00635 }
00636 
00637 
00638 bool ON_Viewport::GetViewPlane( 
00639   double view_plane_depth,
00640   ON_Plane& view_plane 
00641   ) const
00642 {
00643   bool rc = IsValidFrustum() && IsValidCamera();
00644   if ( rc ) 
00645   {
00646     view_plane.origin = m_CamLoc - view_plane_depth*m_CamZ;
00647     view_plane.xaxis = m_CamX;
00648     view_plane.yaxis = m_CamY;
00649     view_plane.zaxis = m_CamZ;
00650     view_plane.UpdateEquation();
00651   }
00652   return rc;
00653 }
00654 
00655 bool ON_Viewport::GetViewPlaneEquation( 
00656   double view_plane_depth,
00657   ON_PlaneEquation& view_plane_equation 
00658   ) const
00659 {
00660   bool rc = m_bValidCamera && m_bValidFrustum;
00661   if (rc)
00662   {
00663     view_plane_equation.ON_3dVector::operator=(m_CamZ);
00664     view_plane_equation.d = -view_plane_equation.ON_3dVector::operator*(m_CamLoc - view_plane_depth*m_CamZ);
00665   }
00666   return rc;
00667 }
00668 
00669 
00670 bool ON_Viewport::GetNearRect( 
00671        ON_3dPoint& left_bottom,
00672        ON_3dPoint& right_bottom,
00673        ON_3dPoint& left_top,
00674        ON_3dPoint& right_top
00675        ) const
00676 {
00677   ON_Plane near_plane;
00678   bool rc = GetNearPlane( near_plane );
00679   if (rc ) {
00680     double x = 1.0, y = 1.0;
00681     GetViewScale(&x,&y);
00682     x = 1.0/x;
00683     y = 1.0/y;
00684     left_bottom  = near_plane.PointAt( x*m_frus_left,  y*m_frus_bottom );
00685     right_bottom = near_plane.PointAt( x*m_frus_right, y*m_frus_bottom );
00686     left_top     = near_plane.PointAt( x*m_frus_left,  y*m_frus_top );
00687     right_top    = near_plane.PointAt( x*m_frus_right, y*m_frus_top );
00688   }
00689   return rc;
00690 }
00691 
00692 bool ON_Viewport::GetFarRect( 
00693        ON_3dPoint& left_bottom,
00694        ON_3dPoint& right_bottom,
00695        ON_3dPoint& left_top,
00696        ON_3dPoint& right_top
00697        ) const
00698 {
00699   ON_Plane far_plane;
00700   bool rc = GetFarPlane( far_plane );
00701   if (rc )
00702   {
00703     double s = IsPerspectiveProjection()
00704             ? m_frus_far/m_frus_near
00705             : 1.0;
00706     double x = 1.0, y = 1.0;
00707     GetViewScale(&x,&y);
00708     x = 1.0/x;
00709     y = 1.0/y;
00710     left_bottom  = far_plane.PointAt( s*x*m_frus_left,  s*y*m_frus_bottom );
00711     right_bottom = far_plane.PointAt( s*x*m_frus_right, s*y*m_frus_bottom );
00712     left_top     = far_plane.PointAt( s*x*m_frus_left,  s*y*m_frus_top );
00713     right_top    = far_plane.PointAt( s*x*m_frus_right, s*y*m_frus_top );
00714   }
00715   return rc;
00716 }
00717 
00718 bool ON_Viewport::GetViewPlaneRect(
00719         double view_plane_depth,
00720         ON_3dPoint& left_bottom,
00721         ON_3dPoint& right_bottom,
00722         ON_3dPoint& left_top,
00723         ON_3dPoint& right_top
00724         ) const
00725 {
00726   ON_Plane view_plane;
00727   bool rc = GetViewPlane( view_plane_depth, view_plane );
00728   if (rc )
00729   {
00730     double s = IsPerspectiveProjection()
00731             ? view_plane_depth/m_frus_near
00732             : 1.0;
00733     double x = 1.0, y = 1.0;
00734     GetViewScale(&x,&y);
00735     x = 1.0/x;
00736     y = 1.0/y;
00737     left_bottom  = view_plane.PointAt( s*x*m_frus_left,  s*y*m_frus_bottom );
00738     right_bottom = view_plane.PointAt( s*x*m_frus_right, s*y*m_frus_bottom );
00739     left_top     = view_plane.PointAt( s*x*m_frus_left,  s*y*m_frus_top );
00740     right_top    = view_plane.PointAt( s*x*m_frus_right, s*y*m_frus_top );
00741   }
00742   return rc;
00743 }
00744 
00745 
00746 ON_BOOL32 ON_Viewport::GetBBox( 
00747        double* boxmin,
00748        double* boxmax,
00749        ON_BOOL32 bGrowBox
00750        ) const
00751 {
00752   ON_3dPoint corners[9];
00753   bool rc = GetNearRect(corners[0],corners[1],corners[2],corners[3]);
00754   if (rc)
00755     rc = GetFarRect(corners[4],corners[5],corners[6],corners[7]);
00756   corners[8] = m_CamLoc;
00757   if (rc)
00758   {
00759     rc = ON_GetPointListBoundingBox( 
00760             3, 0, 9, 
00761             3, &corners[0].x, 
00762             boxmin, boxmax,  bGrowBox?true:false
00763             );
00764   }
00765   return rc;
00766 }
00767 
00768 ON_BOOL32 ON_Viewport::Transform( const ON_Xform& xform )
00769 {
00770   ON_BOOL32 rc = IsValidCamera();
00771   if (rc) {
00772     // save input settings
00773     const ON_3dPoint c0 = m_CamLoc;
00774     const ON_3dPoint u0 = m_CamUp;
00775     const ON_3dPoint d0 = m_CamDir;
00776     const ON_3dPoint x0 = m_CamX;
00777     const ON_3dPoint y0 = m_CamY;
00778     const ON_3dPoint z0 = m_CamZ;
00779 
00780     // compute transformed settings
00781     ON_3dPoint c = xform*c0;
00782     ON_3dVector u = (xform*(c0 + u0)) - c;
00783     ON_3dVector d = (xform*(c0 + d0)) - c;
00784 
00785     if ( m_bLockCamLoc )
00786       c = m_CamLoc;
00787     if ( m_bLockCamUp )
00788       u = m_CamY;
00789     if ( m_bLockCamDir )
00790       d = -m_CamZ;
00791 
00792     if (    !u.IsValid() || !d.IsValid() 
00793          || u.IsTiny()   || d.IsTiny() 
00794          || ON_CrossProduct(u,d).IsTiny() ) 
00795     {
00796       rc = false;
00797     }
00798     else 
00799     {
00800       if ( m_bLockCamUp && !m_bLockCamDir )
00801       {
00802         d.Unitize();
00803         if ( fabs(d*u) <= ON_ZERO_TOLERANCE )
00804           d = -m_CamZ;
00805       }
00806       else if ( m_bLockCamDir && !m_bLockCamUp )
00807       {
00808         u.Unitize();
00809         if ( fabs(d*u) <= ON_ZERO_TOLERANCE )
00810           u = m_CamY;
00811       }
00812 
00813       // set new camera position
00814       if ( !m_bLockCamLoc )
00815         SetCameraLocation(c);
00816       if ( !m_bLockCamDir )
00817         SetCameraDirection(d);
00818       if ( !m_bLockCamUp)
00819         SetCameraUp(u);
00820       rc = SetCameraFrame();
00821       if ( !rc ) 
00822       {
00823         // restore input settings
00824         m_CamLoc = c0;
00825         m_CamUp  = u0;
00826         m_CamDir = d0;
00827         m_CamX = x0;
00828         m_CamY = y0;
00829         m_CamZ = z0;
00830       }
00831     }
00832   }
00833   return rc;
00834 }
00835 
00836 bool ON_Viewport::SetCameraLocation( const ON_3dPoint& p )
00837 {
00838   if ( m_bLockCamLoc )
00839   {
00840     if ( m_CamLoc.IsValid() )
00841     {
00842       return (p == m_CamLoc);
00843     }
00844   }
00845   if ( p != ON_3dPoint::UnsetPoint && !p.IsValid() )
00846     return false;
00847   m_CamLoc = p;
00848   if ( !m_CamLoc.IsValid() )
00849     m_bValidCamera = false;
00850   return m_bValidCamera;
00851 }
00852 
00853 bool ON_Viewport::SetCameraDirection( const ON_3dVector& v )
00854 {
00855   if ( m_bLockCamDir )
00856   {
00857     if ( m_CamDir.IsValid() && !m_CamDir.IsTiny() )
00858     {
00859       return (v == m_CamDir);
00860     }
00861   }
00862   if ( !v.IsValid() || v.IsTiny() )
00863     return false;
00864   m_CamDir = v;
00865   return SetCameraFrame();
00866 }
00867 
00868 bool ON_Viewport::SetCameraUp( const ON_3dVector& v )
00869 {
00870   if ( m_bLockCamUp )
00871   {
00872     if ( m_CamUp.IsValid() && !m_CamUp.IsTiny() )
00873     {
00874       return (v == m_CamUp);
00875     }
00876   }
00877   if ( !v.IsValid() || v.IsTiny() )
00878     return false;
00879   m_CamUp = v;
00880   return SetCameraFrame();
00881 }
00882 
00883 //ON_BOOL32 ON_Viewport::SetTargetDistance( double d )
00884 //{
00885 //  m_target_distance = (d>0.0) ? d : 0.0;
00886 //  return (d>=0.0) ? true : false;
00887 //}
00888 
00889 bool ON_Viewport::SetCameraFrame()
00890 {
00891   m_bValidCamera = false;
00892 
00893   if ( !m_CamDir.IsValid() || !m_CamUp.IsValid() )
00894     return false;
00895 
00896   double d;
00897   ON_3dVector CamX, CamY, CamZ;
00898 
00899   if ( m_bLockCamUp && !m_bLockCamDir )
00900   {
00901     // up takes precedence over direction
00902     CamY = m_CamUp;
00903     if ( !CamY.IsValid() )
00904       return false;
00905     if ( !CamY.Unitize() )
00906       return false;
00907 
00908     d = m_CamDir*CamY;
00909     CamZ = -m_CamDir + d*CamY;
00910     if ( !CamZ.IsValid() )
00911       return false;
00912     if ( !CamZ.Unitize() )
00913       return false;
00914   }
00915   else
00916   {
00917     // direction takes precedence over up
00918     CamZ = -m_CamDir;
00919     if ( !CamZ.IsValid() )
00920       return false;
00921     if ( !CamZ.Unitize() )
00922       return false;
00923 
00924     d = m_CamUp*CamZ;
00925     CamY = m_CamUp - d*CamZ;
00926     if ( !CamY.IsValid() )
00927       return false;
00928     if ( !CamY.Unitize() )
00929       return false;
00930   }
00931 
00932   CamX = ON_CrossProduct( CamY, CamZ );
00933   if ( !CamX.IsValid() )
00934     return false;
00935   if ( !CamX.Unitize() )
00936     return false;
00937 
00938   // Gaurd against garbage resulting from nearly parallel 
00939   // and/or ultra short short dir and up.
00940   if ( !ON__IsCameraFrameUnitVectorHelper(CamX) )
00941     return false;
00942   if ( !ON__IsCameraFrameUnitVectorHelper(CamY) )
00943     return false;
00944   if ( !ON__IsCameraFrameUnitVectorHelper(CamZ) )
00945     return false;
00946   if ( !ON__IsCameraFramePerpindicular(CamX,CamY) )
00947     return false;
00948   if ( !ON__IsCameraFramePerpindicular(CamY,CamZ) )
00949     return false;
00950   if ( !ON__IsCameraFramePerpindicular(CamZ,CamX) )
00951     return false;
00952 
00953   m_CamX = CamX;
00954   m_CamY = CamY;
00955   m_CamZ = CamZ;
00956 
00957   m_bValidCamera = m_CamLoc.IsValid();
00958   return m_bValidCamera;
00959 }
00960 
00961 ON_3dPoint ON_Viewport::CameraLocation() const
00962 {
00963   return m_CamLoc;
00964 }
00965 
00966 ON_3dVector ON_Viewport::CameraDirection() const
00967 {
00968   return m_CamDir;
00969 }
00970 
00971 ON_3dVector ON_Viewport::CameraUp() const
00972 {
00973   return m_CamUp;
00974 }
00975 
00976 bool ON_Viewport::CameraLocationIsLocked() const
00977 {
00978   return m_bLockCamLoc;
00979 }
00980 
00981 bool ON_Viewport::CameraDirectionIsLocked() const
00982 {
00983   return m_bLockCamDir;
00984 }
00985 
00986 bool ON_Viewport::CameraUpIsLocked() const
00987 {
00988   return m_bLockCamUp;
00989 }
00990 
00991 bool ON_Viewport::FrustumIsLeftRightSymmetric() const
00992 {
00993   return (0 != (0x02 & m_frustum_symmetry_flags));
00994 }
00995 
00996 bool ON_Viewport::FrustumIsTopBottomSymmetric() const
00997 {
00998   return (0 != (0x01 & m_frustum_symmetry_flags));
00999 }
01000 
01001 void ON_Viewport::UnlockCamera()
01002 {
01003   SetCameraLocationLock(false);
01004   SetCameraDirectionLock(false);
01005   SetCameraUpLock(false);
01006 }
01007 
01008 void ON_Viewport::UnlockFrustumSymmetry()
01009 {
01010   SetFrustumLeftRightSymmetry(false);
01011   SetFrustumTopBottomSymmetry(false);
01012 }
01013 
01014 void ON_Viewport::SetCameraLocationLock( bool bLockCameraLocation )
01015 {
01016   m_bLockCamLoc = bLockCameraLocation ? true : false;
01017 }
01018 
01019 void ON_Viewport::SetCameraDirectionLock( bool bLockCameraDirection ) 
01020 {
01021   m_bLockCamDir = bLockCameraDirection ? true : false;
01022 }
01023 
01024 void ON_Viewport::SetCameraUpLock( bool bLockCameraUp )
01025 {
01026   m_bLockCamUp = bLockCameraUp ? true : false;
01027 }
01028 
01029 void ON_Viewport::SetFrustumLeftRightSymmetry( bool bForceLeftRightSymmetry )
01030 {
01031   if ( bForceLeftRightSymmetry )
01032     m_frustum_symmetry_flags |= 0x02; // set bit 2
01033   else 
01034     m_frustum_symmetry_flags &= 0xFD; // clear bit 2
01035 }
01036 
01037 void ON_Viewport::SetFrustumTopBottomSymmetry( bool bForceTopBottomSymmetry )
01038 {
01039   if ( bForceTopBottomSymmetry )
01040     m_frustum_symmetry_flags |= 0x01; // set bit 1
01041   else 
01042     m_frustum_symmetry_flags &= 0xFE; // clear bit 1
01043 }
01044 
01045 
01046 
01047 bool ON_Viewport::GetDollyCameraVector(
01048          int x0, int y0,    // (x,y) screen coords of start point
01049          int x1, int y1,    // (x,y) screen coords of end point
01050          double distance_to_camera, // distance from camera
01051          ON_3dVector& dolly_vector// dolly vector returned here
01052          ) const
01053 {
01054   int port_left, port_right, port_bottom, port_top;
01055   ON_Xform c2w;
01056   dolly_vector.Zero();
01057   bool rc = GetScreenPort( &port_left, &port_right, &port_bottom, &port_top );
01058   if ( rc )
01059     rc = GetXform( ON::clip_cs, ON::world_cs, c2w );
01060   if ( rc ) {
01061     double dx = 0.5*(port_right - port_left);
01062     double dy = 0.5*(port_top - port_bottom);
01063     double dz = 0.5*(FrustumFar() - FrustumNear());
01064     if ( dx == 0.0 || dy == 0.0 || dz == 0.0 )
01065       rc = false;
01066     else {
01067       double z = (distance_to_camera - FrustumNear())/dz - 1.0;
01068       ON_3dPoint c0( (x0-port_left)/dx-1.0, (y0-port_bottom)/dy-1.0, z );
01069       ON_3dPoint c1( (x1-port_left)/dx-1.0, (y1-port_bottom)/dy-1.0, z );
01070       ON_3dPoint w0 = c2w*c0;
01071       ON_3dPoint w1 = c2w*c1;
01072       dolly_vector = w0 - w1;
01073     }
01074   }
01075   return rc;
01076 }
01077 
01078 bool ON_Viewport::DollyCamera( const ON_3dVector& dolly )
01079 {
01080   bool rc = false;
01081   if ( m_CamLoc.IsValid() && dolly.IsValid() )
01082   {
01083     m_CamLoc += dolly;
01084     rc = m_bValidCamera;
01085   }
01086   return rc;
01087 }
01088 
01089 bool ON_Viewport::DollyFrustum( double dollyDistance )
01090 {
01091   bool rc = false;
01092   double new_near, new_far, scale;
01093   if ( m_bValidFrustum ) 
01094   {
01095     new_near = m_frus_near + dollyDistance;
01096     new_far  = m_frus_far + dollyDistance;
01097     if ( IsPerspectiveProjection() && new_near < m__MIN_NEAR_DIST ) 
01098     {
01099       new_near = m__MIN_NEAR_DIST;
01100     }
01101     scale = ( IsPerspectiveProjection() ) 
01102           ? new_near/m_frus_near 
01103           : 1.0;
01104     if ( new_near > 0.0 && new_far > new_near && scale > 0.0 ) 
01105     {
01106       m_frus_near = new_near;
01107       m_frus_far  = new_far;
01108       m_frus_left   *= scale;
01109       m_frus_right  *= scale;
01110       m_frus_top    *= scale;
01111       m_frus_bottom *= scale;
01112       rc = true;
01113     }
01114   }
01115   return rc;
01116 }
01117 
01118 bool ON_Viewport::GetCameraFrame(
01119     double* CameraLocation,
01120     double* CameraX,
01121     double* CameraY,
01122     double* CameraZ
01123     ) const
01124 {
01125   if ( CameraLocation ) {
01126     CameraLocation[0] = m_CamLoc.x;
01127     CameraLocation[1] = m_CamLoc.y;
01128     CameraLocation[2] = m_CamLoc.z;
01129   }
01130   if ( CameraX ) {
01131     CameraX[0] = m_CamX.x;
01132     CameraX[1] = m_CamX.y;
01133     CameraX[2] = m_CamX.z;
01134   }
01135   if ( CameraY ) {
01136     CameraY[0] = m_CamY.x;
01137     CameraY[1] = m_CamY.y;
01138     CameraY[2] = m_CamY.z;
01139   }
01140   if ( CameraZ ) {
01141     CameraZ[0] = m_CamZ.x;
01142     CameraZ[1] = m_CamZ.y;
01143     CameraZ[2] = m_CamZ.z;
01144   }
01145   return m_bValidCamera;
01146 }
01147 
01148 ON_3dVector ON_Viewport::CameraX() const
01149 {
01150   return m_CamX;
01151 }
01152 
01153 ON_3dVector ON_Viewport::CameraY() const
01154 {
01155   return m_CamY;
01156 }
01157 
01158 ON_3dVector ON_Viewport::CameraZ() const
01159 {
01160   return m_CamZ;
01161 }
01162 
01163 bool ON_Viewport::IsCameraFrameWorldPlan( 
01164       int* xindex,
01165       int* yindex,
01166       int* zindex
01167       )
01168 {
01169   int i;
01170   int ix = 0;
01171   int iy = 0;
01172   int iz = 0;
01173   double X[3], Y[3], Z[3];
01174   bool rc = GetCameraFrame( NULL, X, Y, Z );
01175   if ( rc ) {
01176     for ( i = 0; i < 3; i++ ) {
01177       if ( X[i] == 1.0 ) {
01178         ix = i+1;
01179         break;
01180       }
01181       if ( X[i] == -1.0 ) {
01182         ix = -(i+1);
01183         break;
01184       }
01185     }
01186     for ( i = 0; i < 3; i++ ) {
01187       if ( Y[i] == 1.0 ) {
01188         iy = i+1;
01189         break;
01190       }
01191       if ( Y[i] == -1.0 ) {
01192         iy = -(i+1);
01193         break;
01194       }
01195     }
01196     for ( i = 0; i < 3; i++ ) {
01197       if ( Z[i] == 1.0 ) {
01198         iz = i+1;
01199         break;
01200       }
01201       if ( Z[i] == -1.0 ) {
01202         iz = -(i+1);
01203         break;
01204       }
01205     }
01206     rc = ( iz != 0 ) ? 1 : 0;
01207   }
01208   if ( xindex ) *xindex = ix;
01209   if ( yindex ) *yindex = iy;
01210   if ( zindex ) *zindex = iz;
01211   return rc;
01212 }
01213 
01214 
01215 bool ON_Viewport::GetCameraExtents( 
01216     // returns bounding box in camera coordinates - this is useful information
01217     // for setting view frustrums to include the point list
01218     int count,            // count = number of 3d points
01219     int stride,           // stride = number of doubles to skip between points (>=3)
01220     const double* points, // 3d points in world coordinates
01221     ON_BoundingBox& cbox, // bounding box in camera coordinates
01222     int bGrowBox         // set to true to grow existing box
01223     ) const
01224 {
01225   ON_Xform w2c;
01226   bool rc = bGrowBox?true:false;
01227   int i;
01228   if ( count > 0 && stride >= 3 && points != NULL ) {
01229     rc = false;
01230     if ( GetXform( ON::world_cs, ON::camera_cs, w2c ) ) {
01231       rc = true;
01232       for ( i = 0; i < count && rc; i++, points += stride ) {
01233         rc = cbox.Set( w2c*ON_3dPoint(points), bGrowBox );
01234         bGrowBox = true;
01235       }
01236     }
01237   }
01238   return rc;
01239 }
01240 
01241 bool ON_Viewport::GetCameraExtents( 
01242     // returns bounding box in camera coordinates - this is useful information
01243     // for setting view frustrums to include the point list
01244     const ON_BoundingBox& wbox, // world coordinate bounding box
01245     ON_BoundingBox& cbox, // bounding box in camera coordinates
01246     int bGrowBox         // set to true to grow existing box
01247     ) const
01248 {
01249   bool rc = false;
01250   ON_3dPointArray corners;
01251   if ( wbox.GetCorners( corners ) ) {
01252     rc = GetCameraExtents( corners.Count(), 3, &corners.Array()[0].x, cbox, bGrowBox );
01253   }
01254   return rc;
01255 }
01256 
01257 bool ON_Viewport::GetCameraExtents( 
01258     // returns bounding box in camera coordinates - this is useful information
01259     // for setting view frustrums to include the point list
01260     ON_3dPoint& worldSphereCenter,
01261     double worldSphereRadius,
01262     ON_BoundingBox& cbox, // bounding box in camera coordinates
01263     int bGrowBox         // set to true to grow existing box
01264     ) const
01265 {
01266   bool rc = false;
01267   ON_BoundingBox sbox;
01268   if ( GetCameraExtents( 1, 3, &worldSphereCenter.x, sbox, false ) ) {
01269     const double r = fabs( worldSphereRadius );
01270     sbox[0][0] -= r;
01271     sbox[0][1] -= r;
01272     sbox[0][2] -= r;
01273     sbox[1][0] += r;
01274     sbox[1][1] += r;
01275     sbox[1][2] += r;
01276     if ( bGrowBox )
01277       cbox.Union( sbox );
01278     else
01279       cbox = sbox;
01280     rc = true;
01281   }
01282   return rc;
01283 }
01284 
01285 
01286 static void UpdateTargetPointHelper( ON_Viewport& vp, double target_distance )
01287 {
01288   if ( !vp.IsValidCamera() || !vp.IsValidFrustum() )
01289     return;
01290   if ( !ON_IsValid(target_distance) || target_distance <= 0.0 )
01291     return;
01292 
01293   ON_3dPoint old_tp = vp.TargetPoint();
01294 
01295   // Put the target directly in front of the camera.
01296   // The target_tol test is here to avoid making insignificant 
01297   // changes that appear in the user interface and upset users
01298   // who find 1.00000000001 to be grossly different from 1.0.
01299   double target_tol = 1.0e-5*(vp.FrustumWidth()+vp.FrustumHeight())
01300                     + ON_ZERO_TOLERANCE;
01301   ON_3dPoint new_tp = vp.CameraLocation() - target_distance*vp.CameraZ();
01302   if ( new_tp.IsValid() 
01303        && (!old_tp.IsValid() || new_tp.DistanceTo(old_tp) > target_tol)
01304      )
01305   {
01306     vp.SetTargetPoint(new_tp); 
01307   }
01308 }
01309 
01310 bool ON_Viewport::ChangeToParallelProjection( bool bSymmetricFrustum )
01311 {
01312   bool rc = (m_bValidCamera && m_bValidFrustum);
01313 
01314   SetCameraUpLock(false);
01315   SetCameraDirectionLock(false);
01316 
01317   if (    ON::parallel_view == m_projection 
01318        && (bSymmetricFrustum?true:false) == FrustumIsLeftRightSymmetric()
01319        && (bSymmetricFrustum?true:false) == FrustumIsTopBottomSymmetric()
01320      )
01321   {
01322     // no changes are required
01323     return rc;
01324   }
01325 
01326   // if needed, make frustum symmetric
01327   // If bSymmetricFrustum is true and the input frustum is not symmetric, 
01328   // then this will dolly the camera location.
01329   ChangeToSymmetricFrustum(bSymmetricFrustum,bSymmetricFrustum,ON_UNSET_VALUE);
01330   SetFrustumTopBottomSymmetry(bSymmetricFrustum);
01331   SetFrustumLeftRightSymmetry(bSymmetricFrustum);
01332 
01333   const ON::view_projection old_projection = m_projection;
01334   double target_distance = TargetDistance(true);
01335   if ( !ON_IsValid(target_distance) 
01336        || !m_bValidFrustum
01337        || !ON_IsValid(m_frus_near)
01338        || m_frus_near <= 0.0
01339        || target_distance <= m_frus_near 
01340        )
01341   {
01342     target_distance = 0.0; // makes it easier to check for valid target distance
01343   }
01344 
01345   // if needed change projection
01346   if ( ON::parallel_view != old_projection )
01347   {
01348     if ( !SetProjection(ON::parallel_view) )
01349       rc = false;
01350   }
01351 
01352   if ( rc )
01353   {
01354     if ( ON::perspective_view == old_projection )
01355     {
01356       // change from a perspective to a parallel projection
01357       if ( target_distance > 0.0 && 0.0 < m_frus_near && m_frus_near < m_frus_far )
01358       {
01359         // Update the frustum so that the plane through the target point
01360         // is the one that is parallel projected.  This is generally
01361         // the best choice when switching from perspective to
01362         // parallel projection. If needed, SetFrustum() will make the
01363         // frustum symmetric
01364         double s = target_distance/m_frus_near;
01365         double l = m_frus_left*s; 
01366         double r = m_frus_right*s; 
01367         double t = m_frus_top*s; 
01368         double b = m_frus_bottom*s;
01369         if ( !SetFrustum( l, r, b, t, m_frus_near, m_frus_far ))
01370           rc = false;
01371       }
01372     }
01373     if ( m_target_point.IsValid() )
01374       UpdateTargetPointHelper(*this,target_distance);
01375   }
01376 
01377   return rc;
01378 }
01379 
01380 static bool ChangeFromParallelToPerspectiveHelper( ON_Viewport& vp, double target_distance, double lens_length )
01381 {
01382   // helper use by ChangeToPerspectiveProjection() and ChangeToTwoPointPerspectiveProjection()
01383   if ( ON::perspective_view == vp.Projection() )
01384     return true;
01385 
01386   if ( !vp.SetProjection(ON::perspective_view) )
01387     return false;
01388 
01389   // change from a parallel to a perspective  projection
01390   double frus_left,frus_right,frus_bottom,frus_top,frus_near,frus_far;
01391   if ( !vp.GetFrustum(&frus_left,&frus_right,&frus_bottom,&frus_top,&frus_near,&frus_far) )
01392     return false;
01393 
01394   // Using width because it works for both two point and ordinary perspective
01395   const double width = fabs(frus_right - frus_left);
01396   const ON_3dPoint width_point = ( ON_IsValid(target_distance) && target_distance > 0.0) 
01397                                ? vp.CameraLocation() - target_distance*vp.CameraZ()
01398                                : ON_3dPoint::UnsetPoint;
01399 
01400   if ( frus_near < 1.0e-8 && frus_far >= 1.0e-7)
01401   {
01402     frus_near = 1.0e-8;
01403     vp.SetFrustum(frus_left,frus_right,frus_bottom,frus_top,frus_near,frus_far);
01404     vp.GetFrustum(&frus_left,&frus_right,&frus_bottom,&frus_top,&frus_near,&frus_far);
01405   }
01406 
01407   bool rc = false;
01408 
01409   if ( ON_IsValid(lens_length) && lens_length > 0.0 )
01410   {
01411     rc = vp.SetCamera35mmLensLength(lens_length);
01412     if ( rc 
01413          && width_point.IsValid()
01414          && !vp.CameraLocationIsLocked() 
01415          && vp.GetFrustum(&frus_left,&frus_right,&frus_bottom,&frus_top,&frus_near,&frus_far)
01416          && frus_near > 0.0
01417        )
01418     {
01419       double d = (vp.CameraLocation() - width_point)*vp.CameraZ();
01420       if ( d > frus_near )
01421       {
01422         // make sure target plane is visible
01423         double w = fabs(frus_right - frus_left)*d/frus_near;
01424         if ( width > w && w > 0.0 )
01425         {
01426           // move camera back to increase "w" back up to "width"
01427           ON_3dPoint cam_loc0 = vp.CameraLocation();
01428           double dz = d*(width/w - 1.0);
01429           ON_3dPoint cam_loc1 = cam_loc0 + dz*vp.CameraZ();
01430           vp.SetCameraLocation(cam_loc1);
01431         }
01432       }
01433     }
01434   }
01435   return rc;
01436 }
01437 
01438 bool ON_Viewport::ChangeToPerspectiveProjection( 
01439           double target_distance,
01440           bool bSymmetricFrustum,
01441           double lens_length
01442         )
01443 {
01444   bool rc = (m_bValidCamera && m_bValidFrustum);
01445 
01446   SetCameraUpLock(false);
01447   SetCameraDirectionLock(false);
01448 
01449   if (    ON::perspective_view == m_projection 
01450        && (bSymmetricFrustum?true:false) == FrustumIsLeftRightSymmetric()
01451        && (bSymmetricFrustum?true:false) == FrustumIsTopBottomSymmetric()
01452      )
01453   {
01454     double current_lens_length = lens_length;
01455     if ( ON_IsValid(lens_length) 
01456          && lens_length > 0.0 
01457          && GetCamera35mmLensLength(&current_lens_length) 
01458          && fabs(current_lens_length - lens_length) > 0.125
01459         )
01460     {
01461       SetCamera35mmLensLength(lens_length);
01462     }
01463     // no other changes are required
01464     return rc;
01465   }
01466 
01467   if ( !ON_IsValid(target_distance) || target_distance <= 0.0 )
01468     target_distance = TargetDistance(true);
01469 
01470   // If needed, make frustum symmetric.  This may move the 
01471   // camera location in a direction perpendicular to m_CamZ.
01472   ChangeToSymmetricFrustum(bSymmetricFrustum,bSymmetricFrustum,target_distance);
01473   SetFrustumTopBottomSymmetry(bSymmetricFrustum);
01474   SetFrustumLeftRightSymmetry(bSymmetricFrustum);
01475 
01476   // If needed change projection to perspective.  If
01477   // the input projection is parallel, this may move
01478   // the camera in the m_CamZ direction to preserve
01479   // viewing the target plane.
01480   if (!ChangeFromParallelToPerspectiveHelper(*this,target_distance,lens_length))
01481     rc = false;
01482 
01483   if ( rc && m_target_point.IsValid() )
01484     UpdateTargetPointHelper(*this,target_distance);
01485 
01486   return rc;
01487 }
01488 
01489 static
01490 bool GetTwoPointPerspectiveUpAndDirHelper( const ON_3dVector& up,
01491                                            const ON_3dVector& CamDir,
01492                                            const ON_3dVector& CamY,
01493                                            const ON_3dVector& CamZ,
01494                                            ON_3dVector& new_up,
01495                                            ON_3dVector& new_dir
01496                                            )
01497 {
01498   // get up direction
01499   ON_3dVector unit_up;
01500   ON_3dVector unit_dir;
01501   if ( up.IsZero() && CamY.IsValid() && CamY.IsUnitVector() )
01502   {
01503     new_up = CamY;
01504     if ( fabs(new_up.z) >= fabs(new_up.y) && fabs(new_up.z) >= fabs(new_up.x) )
01505       new_up.Set(0.0,0.0,new_up.z<0.0?-1.0:1.0);
01506     else if ( fabs(new_up.y) >= fabs(new_up.z) && fabs(new_up.y) >= fabs(new_up.x) )
01507       new_up.Set(0.0,new_up.y<0.0?-1.0:1.0,0.0);
01508     else
01509       new_up.Set(new_up.x<0.0?-1.0:1.0,0.0,0.0);
01510     unit_up = new_up;
01511   }
01512   else if ( up.IsValid() && !up.IsTiny() )
01513   {
01514     unit_up = up;
01515     if ( !unit_up.IsUnitVector() && !unit_up.Unitize() )
01516       return false;
01517     new_up = up;
01518   }
01519   else
01520   {
01521     return false;
01522   }
01523 
01524   // get camera dir
01525   if ( CamDir.IsValid() && !CamDir.IsTiny() )
01526   {
01527     new_dir = CamDir;
01528     unit_dir = new_dir;
01529     if ( unit_dir.Unitize() && ON__IsCameraFramePerpindicular(unit_up,unit_dir) )
01530       return true;
01531     unit_dir = unit_dir - (unit_dir*unit_up)*unit_up;
01532     if ( unit_dir.IsValid() && !unit_dir.IsTiny() && unit_dir.Unitize() )
01533     {
01534       new_dir = unit_dir;
01535       return true;
01536     }
01537   }
01538 
01539   if ( CamZ.IsValid() && CamZ.IsUnitVector() )
01540   {
01541     new_dir = -CamZ;
01542     unit_dir = new_dir;
01543     if ( unit_dir.Unitize() && ON__IsCameraFramePerpindicular(unit_up,unit_dir) )
01544       return true;
01545     unit_dir = unit_dir - (new_dir*unit_up)*unit_up;
01546     if ( unit_dir.IsValid() && !unit_dir.IsTiny() && unit_dir.Unitize() )
01547     {
01548       new_dir = unit_dir;
01549       return true;
01550     }
01551   }
01552 
01553   return false;
01554 }
01555 
01556 bool ON_Viewport::ChangeToTwoPointPerspectiveProjection( 
01557         double target_distance,
01558         ON_3dVector up,
01559         double lens_length
01560         )
01561 {
01562   bool rc = (m_bValidCamera && m_bValidFrustum);
01563 
01564   SetCameraDirectionLock(false);
01565 
01566   if ( IsTwoPointPerspectiveProjection() )
01567   {
01568     double current_lens_length = lens_length;
01569     if ( ON_IsValid(lens_length) 
01570          && lens_length > 0.0 
01571          && GetCamera35mmLensLength(&current_lens_length) 
01572          && fabs(current_lens_length - lens_length) > 0.125
01573         )
01574     {
01575       SetCamera35mmLensLength(lens_length);
01576     }
01577     // no other changes are required
01578     return rc;
01579   }
01580 
01581   if ( !ON_IsValid(target_distance) || target_distance <= 0.0 )
01582     target_distance = TargetDistance(true);
01583 
01584   // if needed, make frustum left/right symmetric. This may move the 
01585   // camera location in a direction perpendicular to m_CamZ.
01586   ChangeToSymmetricFrustum(true,false,target_distance);
01587   SetFrustumLeftRightSymmetry(true);
01588   SetFrustumTopBottomSymmetry(false);
01589 
01590   // If needed change projection to perspective.  If
01591   // the input projection is parallel, this may move
01592   // the camera in the m_CamZ direction to preserve
01593   // viewing the target plane.
01594   if (!ChangeFromParallelToPerspectiveHelper(*this,target_distance,lens_length))
01595     rc = false;
01596 
01597   if ( rc )
01598   {
01599     ON_3dVector new_up = m_CamY;
01600     ON_3dVector new_dir = -m_CamZ;
01601     ON_3dPoint  new_loc = m_CamLoc;
01602     if ( !GetTwoPointPerspectiveUpAndDirHelper(up,m_CamDir,m_CamY,m_CamZ,new_up,new_dir) )
01603     {
01604       rc = false;
01605     }
01606     else
01607     {
01608       // move location so the stuff that is currently visible
01609       // tends to end up in someplace in the new frustum.
01610       ON_3dPoint center_point = FrustumCenterPoint(target_distance);
01611       if ( center_point.IsValid() && (new_loc-center_point)*m_CamZ > 0.0 )
01612       {
01613         ON_Xform rot;
01614         rot.Rotation(m_CamY,new_up,center_point);
01615         new_loc = rot*m_CamLoc;
01616         if ( !new_loc.IsValid() )
01617           new_loc = m_CamLoc;
01618       }
01619 
01620       ON_3dVector saved_up = m_CamUp;
01621       ON_3dVector saved_dir = m_CamDir;
01622       bool bSavedLockCamUp = m_bLockCamUp;
01623       m_CamUp = new_up;    // intentionally ignoring m_bLockCamUp
01624       m_CamDir = new_dir;  // intentionally ignoring m_bLockDirUp
01625       SetCameraUpLock(true);
01626       if ( !SetCameraFrame() )
01627       {
01628         rc = false;
01629         m_CamUp = saved_up;
01630         m_CamDir = saved_dir;
01631         m_bLockCamUp = bSavedLockCamUp;
01632       }
01633       SetCameraLocation(new_loc);
01634 
01635       UpdateTargetPointHelper(*this,target_distance);
01636     }
01637 
01638   }
01639 
01640   return rc;
01641 }
01642 
01643 bool ON_Viewport::SetProjection( ON::view_projection projection )
01644 {
01645   // Debugging projection changes is easier if we
01646   // do this initial check.
01647   if ( projection == m_projection )
01648     return true;
01649 
01650   bool rc = false;
01651   if ( projection == ON::perspective_view ) 
01652   {
01653     rc = true;
01654     m_projection = ON::perspective_view;
01655   }
01656   else 
01657   {
01658     rc = (projection == ON::parallel_view);
01659     m_projection = ON::parallel_view;
01660   }
01661 
01662   return rc;
01663 }
01664 
01665 ON::view_projection ON_Viewport::Projection() const
01666 {
01667   return m_projection;
01668 }
01669 
01670 bool ON_Viewport::IsParallelProjection() const
01671 {
01672   return ( ON::parallel_view == m_projection );
01673 }
01674 
01675 bool ON_Viewport::IsPerspectiveProjection() const
01676 {
01677   return ( ON::perspective_view == m_projection );
01678 }
01679 
01680 bool ON_Viewport::IsTwoPointPerspectiveProjection() const
01681 {
01682   bool rc =    IsPerspectiveProjection() 
01683             && CameraUpIsLocked() 
01684             && FrustumIsLeftRightSymmetric() 
01685             && !FrustumIsTopBottomSymmetric();
01686   return rc;
01687 }
01688 
01689 bool ON_Viewport::SetFrustum(
01690       double frus_left,
01691       double frus_right,
01692       double frus_bottom,
01693       double frus_top,
01694       double frus_near,
01695       double frus_far
01696       )
01697 {
01698   bool rc = false;
01699   if (  
01700           ON_IsValid(frus_left)
01701        && ON_IsValid(frus_right)
01702        && ON_IsValid(frus_top)
01703        && ON_IsValid(frus_bottom)
01704        && ON_IsValid(frus_near)
01705        && ON_IsValid(frus_far)
01706        && frus_left < frus_right 
01707        && frus_bottom < frus_top 
01708        && 0.0 < frus_near 
01709        && frus_near < frus_far 
01710      ) 
01711   {
01712     if ( IsPerspectiveProjection() 
01713          && (frus_near <= 1.0e-8 || frus_far > 1.0001e8*frus_near) 
01714        )
01715     {
01716       ON_ERROR("ON_Viewport::SetFrustum - Beyond float precision perspective frus_near/frus_far values - will crash MS OpenGL");
01717     }
01718 
01719     if ( FrustumIsLeftRightSymmetric() && frus_left != -frus_right )
01720     {
01721       double d = 0.5*(frus_right-frus_left);
01722       frus_right = d;
01723       frus_left = -d;
01724     }
01725 
01726     if ( FrustumIsTopBottomSymmetric() && frus_bottom != -frus_top )
01727     {
01728       double d = 0.5*(frus_top-frus_bottom);
01729       frus_top = d;
01730       frus_bottom = -d;
01731     }
01732 
01733     m_frus_left   = frus_left;
01734     m_frus_right  = frus_right;
01735     m_frus_bottom = frus_bottom;
01736     m_frus_top    = frus_top;
01737     m_frus_near   = frus_near;
01738     m_frus_far    = frus_far;
01739     m_bValidFrustum = true;
01740     rc = true;
01741   }
01742   else
01743   {
01744     // 17 March 2008 Dale Lear
01745     //   I added this to trap the bug that is creating
01746     //   invalid viewports.  Developers: If you ever
01747     //   get this error, immediately investigate it.
01748     ON_ERROR("ON_Viewport::SetFrustum - invalid input");
01749   }
01750   return rc;
01751 }
01752 
01753 
01754 bool ON_Viewport::GetFrustum(
01755       double* frus_left,
01756       double* frus_right,
01757       double* frus_bottom,
01758       double* frus_top,
01759       double* frus_near,   // = NULL
01760       double* frus_far     // = NULL
01761       ) const
01762 {
01763   if ( frus_left )
01764     *frus_left = m_frus_left;
01765   if ( frus_right )
01766     *frus_right = m_frus_right;
01767   if ( frus_bottom )
01768     *frus_bottom = m_frus_bottom;
01769   if ( frus_top )
01770     *frus_top = m_frus_top;
01771   if ( frus_near )
01772     *frus_near = m_frus_near;
01773   if ( frus_far )
01774     *frus_far = m_frus_far;
01775   return m_bValidFrustum;
01776 }
01777 
01778 double ON_Viewport::FrustumLeft()   const { return m_frus_left; }
01779 double ON_Viewport::FrustumRight()  const { return m_frus_right; }
01780 double ON_Viewport::FrustumBottom() const { return m_frus_bottom; }
01781 double ON_Viewport::FrustumTop()    const { return m_frus_top; }
01782 double ON_Viewport::FrustumNear()   const { return m_frus_near; }
01783 double ON_Viewport::FrustumFar()    const { return m_frus_far;  }
01784 double ON_Viewport::FrustumWidth()  const { return m_frus_right-m_frus_left; }
01785 double ON_Viewport::FrustumHeight() const { return m_frus_top-m_frus_bottom; }
01786 
01787 double ON_Viewport::FrustumMinimumDiameter() const 
01788 { 
01789   double w = fabs(m_frus_right-m_frus_left); 
01790   double h = fabs(m_frus_top-m_frus_bottom);
01791   return (w<=h)?w:h;
01792 }
01793 
01794 double ON_Viewport::FrustumMaximumDiameter() const
01795 { 
01796   double w = fabs(m_frus_right-m_frus_left); 
01797   double h = fabs(m_frus_top-m_frus_bottom);
01798   return (w<=h)?w:h;
01799 }
01800 
01801 
01802 bool ON_Viewport::SetFrustumAspect( double frustum_aspect )
01803 {
01804   // maintains camera angle
01805   bool rc = false;
01806   double w, h, d, left, right, bot, top, near_dist, far_dist;
01807   if ( frustum_aspect > 0.0 && GetFrustum( &left, &right, &bot, &top, &near_dist, &far_dist ) ) {
01808     w = right - left;
01809     h = top - bot;
01810     if ( fabs(h) > fabs(w) ) {
01811       d = (h>=0.0) ? fabs(w) : -fabs(w);
01812       d *= 0.5;
01813       h = 0.5*(top+bot);
01814       bot = h-d;
01815       top = h+d;
01816       h = top - bot;
01817     }
01818     else {
01819       d = (w>=0.0) ? fabs(h) : -fabs(h);
01820       d *= 0.5;
01821       w = 0.5*(left+right);
01822       left  = w-d;
01823       right = w+d;
01824       w = right - left;
01825     }
01826     if ( frustum_aspect > 1.0 ) {
01827       // increase width
01828       d = 0.5*w*frustum_aspect;
01829       w = 0.5*(left+right);
01830       left = w-d;
01831       right = w+d;
01832       w = right - left;
01833     }
01834     else if ( frustum_aspect < 1.0 ) {
01835       // increase height
01836       d = 0.5*h/frustum_aspect;
01837       h = 0.5*(bot+top);
01838       bot = h-d;
01839       top = h+d;
01840       h = top - bot;
01841     }
01842     rc = SetFrustum( left, right, bot, top, near_dist, far_dist );
01843   }
01844   return rc;
01845 }
01846 
01847 
01848 
01849 bool ON_Viewport::GetFrustumAspect( double& frustum_aspect ) const
01850 {
01851   // frustum_aspect = frustum width / frustum height
01852   double w, h, left, right, bot, top;
01853   bool rc = m_bValidFrustum;
01854   frustum_aspect = 0.0;
01855 
01856   if ( GetFrustum( &left, &right, &bot, &top ) ) {
01857     w = right - left;
01858     h = top - bot;
01859     if ( h == 0.0 )
01860       rc = false;
01861     else
01862       frustum_aspect = w/h;
01863   }
01864   return rc;
01865 }
01866 
01867 bool ON_Viewport::GetFrustumCenter( double* frus_center ) const
01868 {
01869   double camZ[3], frus_near, frus_far, d;
01870   if ( !frus_center )
01871     return false;
01872   if ( !GetCameraFrame( frus_center, NULL, NULL, camZ ) )
01873     return false;
01874   if ( !GetFrustum( NULL, NULL, NULL, NULL, &frus_near, &frus_far ) )
01875     return false;
01876   d = -0.5*(frus_near+frus_far);
01877   frus_center[0] += d*camZ[0];
01878   frus_center[1] += d*camZ[1];
01879   frus_center[2] += d*camZ[2];
01880   return true;
01881 }
01882 
01883 bool ON_Viewport::SetScreenPort( 
01884       int port_left, 
01885       int port_right,
01886       int port_bottom, 
01887       int port_top,
01888       int port_near, // = 0
01889       int port_far   // = 0
01890       )
01891 {
01892   if ( port_left == port_right )
01893     return false;
01894   if ( port_bottom == port_top )
01895     return false;
01896   m_port_left   = port_left;
01897   m_port_right  = port_right;
01898   m_port_bottom = port_bottom;
01899   m_port_top    = port_top;
01900   if ( port_near || port_near != port_far ) 
01901   {
01902     m_port_near   = port_near;
01903     m_port_far    = port_far;
01904   }
01905   m_bValidPort = true;
01906   return m_bValidPort;
01907 }
01908 
01909 bool ON_Viewport::GetScreenPort( 
01910       int* port_left,
01911       int* port_right,
01912       int* port_bottom,
01913       int* port_top,
01914       int* port_near, // = NULL
01915       int* port_far   // = NULL
01916       ) const
01917 {
01918   if ( port_left )
01919     *port_left = m_port_left;
01920   if ( port_right )
01921     *port_right = m_port_right;
01922   if ( port_bottom )
01923     *port_bottom = m_port_bottom;
01924   if ( port_top )
01925     *port_top = m_port_top;
01926   if ( port_near )
01927     *port_near = m_port_near;
01928   if ( port_far )
01929     *port_far = m_port_far;
01930   return m_bValidPort;
01931 }
01932 
01933 int ON_Viewport::ScreenPortWidth() const
01934 {
01935   int width = m_port_right - m_port_left;
01936   return width >= 0 ? width : -width;
01937 }
01938 
01939 int ON_Viewport::ScreenPortHeight() const
01940 {
01941   int height = m_port_top - m_port_bottom;
01942   return height >= 0 ? height : -height;
01943 }
01944 
01945 bool ON_Viewport::GetScreenPortAspect(double& aspect) const
01946 {
01947   const double width = m_port_right - m_port_left;
01948   const double height = m_port_top - m_port_bottom;
01949   aspect = ( m_bValidPort && ON_IsValid(height) && ON_IsValid(width) && height != 0.0 )
01950          ? fabs(width/height) 
01951          : 0.0;
01952   return (m_bValidPort && aspect != 0.0);
01953 }
01954 
01955 bool ON_ViewportFromRhinoView(
01956         ON::view_projection projection,
01957         const ON_3dPoint& rhvp_target, // 3d point
01958         double rhvp_angle1, double rhvp_angle2, double rhvp_angle3, // radians
01959         double rhvp_viewsize,     // > 0
01960         double rhvp_cameradist,   // > 0
01961         int screen_width, int screen_height,
01962         ON_Viewport& vp
01963         )
01964 /*****************************************************************************
01965 Compute canonical view projection information from Rhino viewport settings
01966 INPUT:
01967   projection
01968   rhvp_target
01969     Rhino viewport target point (3d point that is center of view rotations)
01970   rhvp_angle1, rhvp_angle2, rhvp_angle3
01971     Rhino viewport angle settings
01972   rhvp_viewsize 
01973     In perspective, rhvp_viewsize = tangent(half lens angle).
01974     In parallel, rhvp_viewsize = 1/2 * minimum(frustum width,frustum height)
01975   rhvp_cameradistance ( > 0 )
01976     Distance from camera location to Rhino's "target" point
01977   screen_width, screen_height (0,0) if not known
01978 *****************************************************************************/
01979 {
01980   vp.SetProjection( projection );
01981   /*
01982   width, height
01983     width and height of viewport  
01984     ( = RhinoViewport->width, RhinoViewport->height )
01985   z_buffer_depth
01986     depth for the z buffer.  0xFFFF is currently used for Rhino
01987     quick rendering.
01988   */
01989 
01990   // In the situation where there is no physical display device, assume a
01991   // 1000 x 1000 "screen" and set the parameters accordingly.  Toolkit users
01992   // that are using this class to actually draw a picture, can make a subsequent
01993   // call to SetScreenPort().
01994 
01995   const double height = (screen_width < 1 || screen_height < 1) 
01996                       ? 1000.0 : (double)screen_height;
01997   const double width  = (screen_width < 1 || screen_height < 1) 
01998                       ? 1000.0 : (double)screen_width;
01999   //const int z_buffer_depth = 0xFFFF; // value Rhino "Shade" command uses
02000 
02001   // Use this function to obtain standard view information from a Rhino VIEWPORT
02002   // view. The Rhino viewport has many entries.  As of 17 October, 1997 all Rhino
02003   // world to clipping transformation information is derived from the VIEWPORT 
02004   // fields:
02005   //
02006   //   target, angle1, angle2, angle3, viewsize, and cameradist.
02007   //
02008   // The width, height and zbuffer_depth arguments are used to determing the
02009   // clipping to screen transformation.
02010 
02011   ON_Xform R1, R2, R3, RhinoRot;
02012   double frustum_left, frustum_right, frustum_bottom, frustum_top;
02013   double near_clipping_distance, far_clipping_distance;
02014 
02015   // Initialize default view in case input is garbage.
02016   if (height < 1)
02017     return false;
02018   if ( width < 1 )
02019     return false;
02020   if ( rhvp_viewsize <= 0.0 )
02021     return false;
02022   if ( rhvp_cameradist <= 0.0 )
02023     return false;
02024 
02025   // A Rhino 1.0 VIEWPORT structure describes the camera's location, direction,
02026   // and  orientation by specifying a rotation transformation that is
02027   // applied to an initial frame.  The rotation transformation is defined
02028   // as a sequence of 3 rotations abount fixed axes.  The initial frame
02029   // has the camera located at (0,0,cameradist), pointed in the direction
02030   // (0,0,-1), and oriented so that up is (0,1,0).
02031 
02032   R1.Rotation( rhvp_angle1, ON_zaxis, ON_origin ); // so called "twist"
02033   R2.Rotation( rhvp_angle2, ON_xaxis, ON_origin ); // so called "elevation"
02034   R3.Rotation( rhvp_angle3, ON_zaxis, ON_origin ); // so called "fudge factor"
02035   RhinoRot = R3 * R2 * R1;
02036 
02037   vp.SetCameraUp( RhinoRot*ON_yaxis );
02038   vp.SetCameraDirection( -(RhinoRot*ON_zaxis) );
02039   vp.SetCameraLocation( rhvp_target - rhvp_cameradist*vp.CameraDirection() );
02040   vp.SetTargetPoint( rhvp_target );
02041   //vp.SetTargetDistance( rhvp_cameradist );
02042 
02043   // Camera coordinates "X" = CameraRight = CameraDirection x CameraUp
02044   // Camera coordinates "Y" = CameraUp
02045   // Camera coordinates "Z" = -CameraDirection
02046 
02047   // Rhino 1.0 did not support skew projections.  In other words, the
02048   // view frustum is symmetric and ray that begins at CameraLocation and 
02049   // goes along CameraDirection runs along the frustum's central axis.
02050   // The aspect ratio of the view frustum equals 
02051   // (screen port width)/(screen port height)
02052   // This means frus_left = -frus_right, frus_bottom = -frus_top, and
02053   // frus_top/frus_right = height/width
02054 
02055   // Set near and far clipping planes to some reasonable values.  If
02056   // the depth of the pixel is important, then the near and far clipping
02057   // plane will need to be adjusted later.
02058   // Rhino 1.0 didn't have a far clipping plane in wire frame (which explains
02059   // why you can get perspective views reversed through the origin by using 
02060   // the SetCameraTarget() command.  It's near clipping plane is set to 
02061   // a miniscule value.  For mesh rendering, it must come up with some
02062   // sort of reasonable near and far clipping planes because the zbuffer
02063   // is used correctly.  When time permits, I'll dig through the rendering
02064   // code and determine what values are being used.
02065   //
02066   near_clipping_distance = rhvp_cameradist/64.0;
02067   if ( near_clipping_distance > 1.0 )
02068     near_clipping_distance = 1.0;
02069   far_clipping_distance = 4.0*rhvp_cameradist;
02070 
02071 
02072   if ( width <= height )
02073   {
02074     frustum_right = rhvp_viewsize;
02075     frustum_top = frustum_right*height/width;
02076   }
02077   else
02078   {
02079     frustum_top = rhvp_viewsize;
02080     frustum_right = frustum_top*width/height;
02081   }
02082   if ( vp.IsPerspectiveProjection() )
02083   {
02084     frustum_right *= near_clipping_distance;
02085     frustum_top   *= near_clipping_distance;
02086   }
02087   frustum_left   = -frustum_right;
02088   frustum_bottom = -frustum_top;
02089 
02090 
02091   vp.SetFrustum( 
02092          frustum_left,   frustum_right, 
02093          frustum_bottom, frustum_top, 
02094          near_clipping_distance, far_clipping_distance );
02095 
02096   // Windows specific stuff that requires knowing size of client area in pixels
02097   vp.SetScreenPort( 0, (int)width, // windows has screen X increasing accross
02098                     (int)height,  0, // windows has screen Y increasing downwards
02099                     0, 0xFFFF );
02100 
02101   return (vp.IsValid()?true:false);
02102 }
02103 
02104 bool ON_Viewport::GetCameraAngle( 
02105        double* angle,
02106        double* angle_h, 
02107        double* angle_w
02108        ) const
02109 {
02110   bool rc = false;
02111   if ( angle )
02112     *angle = 0.0;
02113   if ( angle_h )
02114     *angle_h = 0.0;
02115   if ( angle_w )
02116     *angle_w = 0.0;
02117   double half_w, half_h, left, right, bot, top, near_dist;
02118   if ( GetFrustum( &left, &right, &bot, &top, &near_dist, NULL ) ) 
02119   {
02120     half_w = ( right > -left ) ? right : -left;
02121     half_h = ( top   > -bot  ) ? top   : -bot;
02122     if ( near_dist > 0.0 && ON_IsValid(near_dist) )
02123     {
02124       if ( angle )
02125         *angle = atan( sqrt(half_w*half_w + half_h*half_h)/near_dist );
02126       if ( angle_h )
02127         *angle_h = atan( half_h/near_dist );
02128       if ( angle_w )
02129         *angle_w = atan( half_w/near_dist );
02130     }
02131     rc = true;
02132   }
02133   return rc;
02134 }
02135 
02136 bool ON_Viewport::GetCameraAngle( 
02137        double* angle
02138        ) const
02139 {
02140   double angle_h = 0.0;
02141   double angle_w = 0.0;
02142   bool rc = GetCameraAngle( NULL, &angle_h, &angle_w );
02143   if ( angle && rc ) {
02144     *angle = (angle_h < angle_w) ? angle_h : angle_w;
02145   }
02146   return rc;
02147 }
02148 
02149 bool ON_Viewport::SetCameraAngle( double angle )
02150 {
02151   bool rc = false;
02152   double r, d, aspect, half_w, half_h, near_dist, far_dist;
02153   if ( angle > 0.0  && angle < 0.5*ON_PI*(1.0-ON_SQRT_EPSILON) ) {
02154     if ( GetFrustum( NULL, NULL, NULL, NULL, &near_dist, &far_dist ) && GetFrustumAspect( aspect) ) {
02155       r = near_dist*tan(angle);
02156       // d = r/sqrt(1.0+aspect*aspect); // if angle is 1/2 diagonal angle
02157       d = r; // angle is 1/2 smallest angle
02158       if ( aspect >= 1.0 ) {
02159         // width >= height
02160         half_w = d*aspect;
02161         half_h = d;
02162       }
02163       else {
02164         // height > width
02165         half_w = d;
02166         half_h = d/aspect;
02167       }
02168       rc = SetFrustum( -half_w, half_w, -half_h, half_h, near_dist, far_dist );
02169     }
02170   }
02171   return rc;
02172 }
02173 
02174 // This version of the function has "lens" misspelled.
02175 bool ON_Viewport::GetCamera35mmLenseLength( double* lens_length ) const
02176 {
02177   return GetCamera35mmLensLength( lens_length );
02178 }
02179 
02180 bool ON_Viewport::GetCamera35mmLensLength( double* lens_length ) const
02181 {
02182   // 35 mm film has a height of 24 mm and a width of 36 mm
02183   double film_r, view_r, half_w, half_h;
02184   double frus_left, frus_right, frus_bottom, frus_top, frus_near, frus_far;
02185   if ( !lens_length )
02186     return false;
02187   *lens_length = 0.0;
02188   if ( !GetFrustum( &frus_left, &frus_right, &frus_bottom, &frus_top, 
02189                      &frus_near, &frus_far ) )
02190     return false;
02191   if ( frus_near <= 0.0 )
02192     return false;
02193   half_w = ( frus_right > -frus_left ) ? frus_right : -frus_left;
02194   half_h = ( frus_top   > -frus_bottom ) ? frus_top : -frus_bottom;
02195 
02196   // 2009 May 8 Dale Lear - always use width in two point perspective
02197   view_r = (half_w <= half_h || IsTwoPointPerspectiveProjection()) ? half_w : half_h;
02198   film_r = 12.0;
02199   if ( view_r <= 0.0 )
02200     return false;
02201 
02202   *lens_length = frus_near*film_r/view_r;
02203   return true;
02204 }
02205 
02206 // This version of the function has "lens" misspelled.
02207 bool ON_Viewport::SetCamera35mmLenseLength( double lens_length )
02208 {
02209   return SetCamera35mmLensLength( lens_length );
02210 }
02211 
02212 bool ON_Viewport::SetCamera35mmLensLength( double lens_length )
02213 {
02214   // 35 mm film has a height of 24 mm and a width of 36 mm
02215   double film_r, view_r, half_w, half_h, s;
02216   double frus_left, frus_right, frus_bottom, frus_top, frus_near, frus_far;
02217   if ( !ON_IsValid(lens_length) || lens_length <= 0.0 )
02218     return false;
02219   if ( !GetFrustum( &frus_left, &frus_right, &frus_bottom, &frus_top, 
02220                      &frus_near, &frus_far ) )
02221     return false;
02222   if ( frus_near <= 0.0 )
02223     return false;
02224   half_w = ( frus_right > -frus_left ) ? frus_right : -frus_left;
02225   half_h = ( frus_top   > -frus_bottom  ) ? frus_top   : -frus_bottom;
02226 
02227   // 2009 May 8 Dale Lear - always use width in two point perspective
02228   view_r = (half_w <= half_h || IsTwoPointPerspectiveProjection()) ? half_w : half_h;
02229   film_r = 12.0;
02230   if ( view_r <= 0.0 )
02231     return false;
02232 
02233   s = (film_r/view_r)*(frus_near/lens_length);
02234   if ( fabs(s-1.0) < 1.0e-6 )
02235     return true;
02236 
02237   frus_left *= s;
02238   frus_right *= s;
02239   frus_bottom *= s;
02240   frus_top *= s;
02241   return SetFrustum( frus_left, frus_right, frus_bottom, frus_top, frus_near, frus_far );
02242 }
02243 
02244 bool ON_Viewport::GetXform( 
02245        ON::coordinate_system srcCS,
02246        ON::coordinate_system destCS,
02247        ON_Xform& xform
02248        ) const
02249 {
02250   bool rc = false;
02251   ON_Xform x0, x1;
02252 
02253   xform.Identity();
02254 
02255   switch( srcCS ) 
02256   {
02257   case ON::world_cs:
02258   case ON::camera_cs:
02259   case ON::clip_cs:
02260   case ON::screen_cs:
02261     break;
02262   default:
02263     return false;
02264   }
02265   switch( destCS ) 
02266   {
02267   case ON::world_cs:
02268   case ON::camera_cs:
02269   case ON::clip_cs:
02270   case ON::screen_cs:
02271     break;
02272   default:
02273     return false;
02274   }
02275 
02276   if (srcCS == destCS)
02277     return true;
02278 
02279 
02280   switch ( srcCS ) 
02281   {
02282 
02283   case ON::world_cs:
02284     if ( !m_bValidCamera )
02285       break;
02286 
02287     switch ( destCS ) 
02288     {
02289     case ON::camera_cs:
02290       xform.WorldToCamera( m_CamLoc, m_CamX, m_CamY, m_CamZ );
02291       rc = true;
02292       break;
02293 
02294     case ON::clip_cs:
02295       rc = GetXform( ON::world_cs,  ON::camera_cs, x0 );
02296       if (rc)
02297         rc = GetXform( ON::camera_cs, ON::clip_cs,   x1 );
02298       if (rc)
02299         xform = x1*x0;
02300       break;
02301 
02302     case ON::screen_cs:
02303       rc = GetXform( ON::world_cs,  ON::clip_cs,   x0 );
02304       if (rc)
02305         rc = GetXform( ON::clip_cs,   ON::screen_cs, x1 );
02306       if (rc)
02307         xform = x1*x0;
02308       break;
02309 
02310     case ON::world_cs:
02311       // Never happens.  This is here to quiet g++ warnings.
02312       break;
02313     }
02314     break;
02315 
02316   case ON::camera_cs:
02317     if ( !m_bValidCamera )
02318       break;
02319 
02320     switch ( destCS ) 
02321     {
02322     case ON::world_cs:
02323       xform.CameraToWorld( m_CamLoc, m_CamX, m_CamY, m_CamZ );
02324       rc = true;
02325       break;
02326 
02327     case ON::clip_cs:
02328       if ( m_bValidFrustum ) 
02329       {
02330         ON_Xform cam2clip;
02331         cam2clip.CameraToClip( 
02332           IsPerspectiveProjection(),
02333           m_frus_left, m_frus_right,
02334           m_frus_bottom, m_frus_top,
02335           m_frus_near, m_frus_far );
02336         xform = m_clip_mods*cam2clip;
02337         rc = true;
02338       }
02339       break;
02340 
02341     case ON::screen_cs:
02342       rc = GetXform( ON::camera_cs,  ON::clip_cs,  x0 );
02343       if (rc)
02344         rc = GetXform( ON::clip_cs,   ON::screen_cs, x1 );
02345       if (rc)
02346         xform = x1*x0;
02347       break;
02348 
02349     case ON::camera_cs:
02350       // Never happens.  This is here to quiet g++ warnings.
02351       break;
02352     }
02353     break;
02354 
02355   case ON::clip_cs:
02356     switch ( destCS ) 
02357     {
02358     case ON::world_cs:
02359       rc = GetXform( ON::clip_cs,   ON::camera_cs, x0 );
02360       if (rc)
02361         rc = GetXform( ON::camera_cs,  ON::world_cs, x1 );
02362       if (rc)
02363         xform = x1*x0;
02364       break;
02365 
02366     case ON::camera_cs:
02367       if ( m_bValidFrustum ) 
02368       {
02369         ON_Xform clip2cam;
02370         clip2cam.ClipToCamera(
02371           IsPerspectiveProjection(),
02372           m_frus_left, m_frus_right,
02373           m_frus_bottom, m_frus_top,
02374           m_frus_near, m_frus_far );
02375         xform = clip2cam*m_clip_mods_inverse;
02376         rc = true;
02377       }
02378       break;
02379 
02380     case ON::screen_cs:
02381       if ( m_bValidPort ) 
02382       {
02383         xform.ClipToScreen( 
02384           m_port_left, m_port_right, 
02385           m_port_bottom, m_port_top,
02386           m_port_near, m_port_far );
02387         rc = true;
02388       }
02389       break;
02390 
02391     case ON::clip_cs:
02392       // Never happens.  This is here to quiet g++ warnings.
02393       break;
02394     }
02395     break;
02396 
02397   case ON::screen_cs:
02398     switch ( destCS ) 
02399     {
02400     case ON::world_cs:
02401       rc = GetXform( ON::screen_cs, ON::camera_cs, x0 );
02402       if (rc)
02403         rc = GetXform( ON::camera_cs, ON::world_cs,  x1 );
02404       if (rc)
02405         xform = x1*x0;
02406       break;
02407     case ON::camera_cs:
02408       rc = GetXform( ON::screen_cs, ON::clip_cs,   x0 );
02409       if (rc)
02410         rc = GetXform( ON::clip_cs,   ON::camera_cs, x1 );
02411       if (rc)
02412         xform = x1*x0;
02413       break;
02414     case ON::clip_cs:
02415       if ( m_bValidPort ) {
02416         xform.ScreenToClip(
02417           m_port_left, m_port_right, 
02418           m_port_bottom, m_port_top,
02419           m_port_near, m_port_far );
02420         rc = true;
02421       }
02422       break;
02423     case ON::screen_cs:
02424       // Never happens.  This is here to quiet g++ warnings.
02425       break;
02426     }
02427     break;
02428 
02429   }
02430 
02431   return rc;
02432 }
02433 
02434 bool ON_Viewport::GetFrustumLine( double screenx, double screeny, ON_Line& world_line ) const
02435 {
02436   ON_Xform s2c, c2w;
02437   ON_3dPoint c;
02438   ON_Line line;
02439   bool rc;
02440 
02441   rc = GetXform( ON::screen_cs, ON::clip_cs, s2c );
02442   if ( rc )
02443     rc = GetXform( ON::clip_cs, ON::world_cs, c2w );
02444   if (rc )
02445   {
02446     // c = mouse point on near clipping plane
02447     c.x = s2c.m_xform[0][0]*screenx + s2c.m_xform[0][1]*screeny + s2c.m_xform[0][3];
02448     c.y = s2c.m_xform[1][0]*screenx + s2c.m_xform[1][1]*screeny + s2c.m_xform[1][3];
02449     c.z = 1.0;
02450     line.to = c2w*c;   // line.to = near plane mouse point in world coords
02451     c.z = -1.0;
02452     line.from = c2w*c; // line.from = far plane mouse point in world coords
02453 
02454     world_line = line;
02455   }
02456   return rc;
02457 }
02458 
02459 static double clipDist( const double* camLoc, const double* camZ, const double* P )
02460 {
02461   return (camLoc[0]-P[0])*camZ[0]+(camLoc[1]-P[1])*camZ[1]+(camLoc[2]-P[2])*camZ[2];
02462 }
02463 
02464 
02465 bool ON_Viewport::SetFrustumNearFar( 
02466        const double* box_min,
02467        const double* box_max
02468        )
02469 {
02470   bool rc = false;
02471   const double* box[2];
02472   int i,j,k;
02473   double n, f, d;
02474   double camLoc[3], camZ[3], P[3];
02475 
02476   if ( !box_min )
02477     box_min = box_max;
02478   if ( !box_max )
02479     box_max = box_min;
02480   if ( !box_min )
02481     return false;
02482 
02483   // 31 May 2007 Dale Lear RR 25980
02484   //    Add validation of box_min and box_max.
02485   if ( !ON_IsValid(box_min[0]) || !ON_IsValid(box_min[1]) || !ON_IsValid(box_min[2]) )
02486     return false;
02487   if ( !ON_IsValid(box_max[0]) || !ON_IsValid(box_max[1]) || !ON_IsValid(box_max[2]) )
02488     return false;
02489   if (    box_min[0] > box_max[0]
02490        || box_min[1] > box_max[1]
02491        || box_min[2] > box_max[2]
02492      )
02493   {
02494     return false;
02495   }
02496   box[0] = box_min;
02497   box[1] = box_max;
02498 
02499   if ( GetCameraFrame( camLoc, NULL, NULL, camZ ) ) {
02500     n = f = -1.0;
02501     for(i=0;i<2;i++)for(j=0;j<2;j++)for(k=0;k<2;k++) {
02502       P[0] = box[i][0];
02503       P[1] = box[j][1];
02504       P[2] = box[k][2];
02505       d = clipDist(camLoc,camZ,P);
02506       if (!i&&!j&&!k)
02507         n=f=d;
02508       else if ( d < n )
02509         n = d;
02510       else if ( d > f )
02511         f = d;
02512     }
02513     if ( !ON_IsValid(f) || !ON_IsValid(n) )
02514       return false;
02515     if ( f <= 0.0 )
02516       return false; // box is behind camera
02517     n *= 0.9375;
02518     f *= 1.0625;
02519     if ( n <= 0.0 )
02520       n = m__MIN_NEAR_OVER_FAR*f;
02521     if ( IsPerspectiveProjection() )
02522       rc = SetFrustumNearFar( n, f, m__MIN_NEAR_DIST, m__MIN_NEAR_OVER_FAR, 0.5*(n+f) );
02523     else
02524       rc = SetFrustumNearFar( n, f );
02525   }
02526   return rc;
02527 }
02528 
02529 bool ON_Viewport::SetFrustumNearFar( 
02530        const double* center,
02531        double        radius
02532        )
02533 {
02534   bool rc = false;
02535   double n, f, d;
02536   double camLoc[3], camZ[3], P[3];
02537 
02538   if ( !center 
02539        || !ON_IsValid(center[0]) 
02540        || !ON_IsValid(center[1]) 
02541        || !ON_IsValid(center[2])
02542        || !ON_IsValid(radius)
02543      )
02544   {
02545     return false;
02546   }
02547 
02548   if ( GetCameraFrame( camLoc, NULL, NULL, camZ ) ) 
02549   {
02550     d = fabs(radius);
02551     P[0] = center[0] + d*camZ[0];
02552     P[1] = center[1] + d*camZ[0];
02553     P[2] = center[2] + d*camZ[0];
02554     n = clipDist(camLoc,camZ,P);
02555     P[0] = center[0] - d*camZ[0];
02556     P[1] = center[1] - d*camZ[0];
02557     P[2] = center[2] - d*camZ[0];
02558     f = clipDist(camLoc,camZ,P);
02559     if ( !ON_IsValid(f) || !ON_IsValid(n) )
02560       return false;
02561     if ( f <= 0.0 )
02562       return false; // sphere is behind camera
02563     n *= 0.9375;
02564     f *= 1.0625;
02565     if ( n <= 0.0 )
02566       n = m__MIN_NEAR_OVER_FAR*f;
02567     if ( IsPerspectiveProjection() )
02568       rc = SetFrustumNearFar( n, f, m__MIN_NEAR_DIST, m__MIN_NEAR_OVER_FAR, 0.5*(n+f) );
02569     else
02570       rc = SetFrustumNearFar( n, f );
02571   }
02572   return rc;
02573 }
02574 
02575 bool ON_Viewport::SetFrustumNearFar( double n, double f )
02576 {
02577   // This is a bare bones setter.  Except for the perspective 0 < n < f
02578   // requirement, do not add checking here.
02579   //
02580   // Use the ON_Viewport::SetFrustumNearFar( near_dist, 
02581   //                                         far_dist, 
02582   //                                         min_near_dist, 
02583   //                                         min_near_over_far,
02584   //                                         target_dist );
02585   //
02586   // version if you need lots of validation and automatic fixing.
02587 
02588   double d, frus_left, frus_right, frus_bottom, frus_top, frus_near, frus_far;
02589   bool rc = false;
02590   if ( ON_IsValid(n) && ON_IsValid(f) && n > 0.0 && f > n ) 
02591   {
02592     if ( GetFrustum( &frus_left,   &frus_right, 
02593                       &frus_bottom, &frus_top, 
02594                       &frus_near,   &frus_far ) ) 
02595     {
02596       // preserve valid frustum
02597       if ( IsPerspectiveProjection() ) 
02598       {
02599         d = n/frus_near;
02600         frus_left *= d;
02601         frus_right *= d;
02602         frus_bottom *= d;
02603         frus_top *= d;
02604       }
02605       frus_near = n;
02606       frus_far = f;
02607       rc = SetFrustum( frus_left,   frus_right, 
02608                        frus_bottom, frus_top, 
02609                        frus_near,   frus_far );
02610     }
02611     else 
02612     {
02613       if ( IsPerspectiveProjection() && (n <= 1.0e-8 || f > 1.0001e8*n) )
02614       {
02615         ON_ERROR("ON_Viewport::SetFrustum - bogus perspective m_frus_near/far values - will crash MS OpenGL");
02616       }
02617       m_frus_near = n;
02618       m_frus_far = f;
02619       rc = true;
02620     }
02621   }
02622   return rc;
02623 }
02624 
02625 
02626 bool ON_Viewport::ChangeToSymmetricFrustum( 
02627     bool bLeftRightSymmetric, 
02628     bool bTopBottomSymmetric,
02629     double target_distance
02630     )
02631 {
02632   if ( bLeftRightSymmetric && m_frus_left == -m_frus_right )
02633     bLeftRightSymmetric = false; // no left/right chnages required.
02634 
02635   if ( bTopBottomSymmetric && m_frus_bottom == -m_frus_top )
02636     bTopBottomSymmetric = false; // no top/bottom chagnes required.
02637 
02638   if ( !bLeftRightSymmetric && !bTopBottomSymmetric )
02639     return true; // no changes required
02640 
02641   if ( !m_bValidFrustum )
02642     return false;
02643 
02644   const double half_w = 0.5*(m_frus_right-m_frus_left);
02645   const double half_h = 0.5*(m_frus_top-m_frus_bottom);
02646   double dx = bLeftRightSymmetric ? (m_frus_right - half_w) : 0.0;
02647   double dy = bTopBottomSymmetric ? (m_frus_top   - half_h) : 0.0;
02648   if ( bLeftRightSymmetric )
02649   {
02650     m_frus_right = half_w;
02651     m_frus_left = -m_frus_right;
02652   }
02653   if ( bTopBottomSymmetric )
02654   {
02655     m_frus_top = half_h;
02656     m_frus_bottom = -m_frus_top;
02657   }
02658 
02659   // if possible, dolly the camera so the original
02660   // target plane is still visible.
02661   if ( m_bValidCamera && (dx != 0.0 || dy != 0.0 ) )
02662   {
02663     if ( ON::perspective_view == m_projection )
02664     {
02665       if ( m_frus_near > 0.0 )
02666       {
02667         if ( ON_UNSET_VALUE == target_distance )
02668           target_distance = TargetDistance(true);
02669         if ( ON_IsValid(target_distance) && target_distance > 0.0 )
02670         {
02671           double s = target_distance/m_frus_near;
02672           dx *= s;
02673           dy *= s;
02674         }
02675       }
02676       else
02677       {
02678         dx=dy = 0.0;
02679       }
02680     }
02681     if ( dx != 0.0 || dy != 0.0 )
02682     {
02683       ON_3dPoint cam_loc = m_CamLoc + dx*m_CamX + dy*m_CamY;
02684       SetCameraLocation(cam_loc);
02685     }
02686   } 
02687 
02688   return true;
02689 }
02690 
02691 
02692 bool ON_Viewport::GetWorldToScreenScale( const ON_3dPoint& P, double* scale ) const
02693 {
02694   if ( scale ) {
02695     ON_Xform w2s;
02696     ON_3dVector X;
02697     ON_3dPoint Q, ScrC, ScrQ;
02698     if (!GetCameraFrame( NULL, X, NULL, NULL )) 
02699       return false;
02700     if (!GetXform( ON::world_cs, ON::screen_cs, w2s )) 
02701       return false;
02702     Q = P+X;
02703     ScrC = w2s*P;
02704     ScrQ = w2s*Q;
02705     *scale = fabs(ScrC.x - ScrQ.x);
02706   }
02707   return true;
02708 }
02709 
02710 bool ON_Viewport::GetCoordinateSprite( 
02711                      int size, 
02712                      int scrx, int scry,
02713                      int indx[3], // axis order by depth
02714                      double scr_coord[3][2] ) const
02715 {
02716   // size = length of axes in pixels
02717 
02718   indx[0] = 0; indx[1] = 1; indx[2] = 2;
02719   scr_coord[0][0] = scr_coord[1][0] = scr_coord[2][0] = scrx;
02720   scr_coord[0][1] = scr_coord[1][1] = scr_coord[2][1] = scry;
02721 
02722   ON_3dPoint C, XP, YP, ZP, ScrC, ScrXP;
02723   ON_3dVector X, Z, Scr[3];
02724   ON_Xform w2s;
02725   if (!GetFrustumCenter( C ) )
02726     return false;
02727   if (!GetCameraFrame( NULL, X, NULL, Z )) 
02728     return false;
02729   if (!GetXform( ON::world_cs, ON::screen_cs, w2s )) 
02730     return false;
02731 
02732   // indx[] determines order that axes are drawn
02733   // sorted from back to front
02734   int i,j,k;
02735   for (i = 0; i < 2; i++) for (j = i+1; j <= 2; j++) {
02736     if (Z[indx[i]] > Z[indx[j]])
02737       {k = indx[i]; indx[i] = indx[j]; indx[j] = k;}
02738   }
02739 
02740   // determine world length that corresponds to size pixels
02741   XP = C+X;
02742   ScrC = w2s*C;
02743   ScrXP = w2s*XP;
02744   if (ScrC.x == ScrXP.x)
02745     return false;
02746   double s = size/fabs( ScrC.x - ScrXP.x );
02747 
02748   // transform world coord axes to screen
02749   XP = C;
02750   XP.x += s;
02751   YP = C;
02752   YP.y += s;
02753   ZP = C;
02754   ZP.z += s;
02755   Scr[0] = w2s*XP;
02756   Scr[1] = w2s*YP;
02757   Scr[2] = w2s*ZP;
02758   
02759   double dx = scrx - ScrC.x;
02760   double dy = scry - ScrC.y;
02761   for (i=0;i<3;i++) {
02762     scr_coord[i][0] = dx + Scr[i].x; 
02763     scr_coord[i][1] = dy + Scr[i].y;
02764   }
02765 
02766   return true;
02767 }
02768 
02769 static ON_BOOL32 GetRelativeScreenCoordinates(
02770           int port_left, int port_right,
02771           int port_bottom, int port_top,
02772           ON_BOOL32 bSortPoints,
02773           int& x0, int& y0, int& x1, int& y1,
02774           double& s0, double& t0, double& s1, double& t1
02775           )
02776 {
02777   // convert screen rectangle into relative rectangle
02778   if ( bSortPoints ) {
02779     int i;
02780     if ( x0 > x1 ) {
02781       i = x0; x0 = x1; x1 = i;
02782     }
02783     if ( port_left > port_right ) {
02784       i = x0; x0 = x1; x1 = i;
02785     }
02786     if ( y0 > y1 ) {
02787       i = y0; y0 = y1; y1 = i;
02788     }
02789     if ( port_bottom > port_top ) {
02790       i = y0; y0 = y1; y1 = i;
02791     }
02792   }
02793 
02794   s0 = ((double)(x0 - port_left))/((double)(port_right - port_left));
02795   s1 = ((double)(x1 - port_left))/((double)(port_right - port_left));
02796   t0 = ((double)(y0 - port_bottom))/((double)(port_top - port_bottom));
02797   t1 = ((double)(y1 - port_bottom))/((double)(port_top - port_bottom));
02798   
02799   double tol = 0.001;
02800   if ( fabs(s0) <= tol ) s0 = 0.0; else if (fabs(s0-1.0) <= tol ) s0 = 1.0;
02801   if ( fabs(s1) <= tol ) s1 = 0.0; else if (fabs(s1-1.0) <= tol ) s1 = 1.0;
02802   if ( fabs(t0) <= tol ) t0 = 0.0; else if (fabs(t0-1.0) <= tol ) t0 = 1.0;
02803   if ( fabs(t1) <= tol ) t1 = 0.0; else if (fabs(t1-1.0) <= tol ) t1 = 1.0;
02804   if ( fabs(s0-s1) <= tol )
02805     return false;
02806   if ( fabs(t0-t1) <= tol )
02807     return false;
02808   return true;
02809 }
02810 
02811 bool ON_Viewport::ZoomToScreenRect( int x0, int y0, int x1, int y1 )
02812 {
02813   int port_left, port_right, port_bottom, port_top, port_near, port_far;
02814   if ( !GetScreenPort( &port_left, &port_right, 
02815                        &port_bottom, &port_top, 
02816                        &port_near, &port_far ) )
02817     return false;
02818 
02819   // dolly camera sideways so it's looking at center of rectangle
02820   int dx = (x0+x1)/2;
02821   int dy = (y0+y1)/2;
02822   int cx = (port_left+port_right)/2;
02823   int cy = (port_bottom+port_top)/2;
02824 
02825   ON_3dVector dolly_vector;
02826   if ( !GetDollyCameraVector( dx, dy, cx, cy, 0.5*(FrustumNear()+FrustumFar()), dolly_vector ) )
02827     return false;
02828   if ( !DollyCamera( dolly_vector ) )
02829     return false;
02830 
02831   // adjust frustum
02832   dx = cx - dx;
02833   dy = cy - dy;
02834   x0 += dx;
02835   x1 += dx;
02836   y0 += dy;
02837   y1 += dy;
02838   double frus_left, frus_right, frus_bottom, frus_top, frus_near, frus_far;
02839   if ( !GetFrustum( &frus_left,   &frus_right, 
02840                      &frus_bottom, &frus_top, 
02841                      &frus_near,   &frus_far ) )
02842     return false;
02843   double s0,t0,s1,t1;
02844   if ( !GetRelativeScreenCoordinates(port_left, port_right, port_bottom, port_top,
02845                               true,
02846                               x0,y0,x1,y1,
02847                               s0,t0,s1,t1) )
02848     return false;
02849   double w = frus_right - frus_left;
02850   double h = frus_top - frus_bottom;
02851   double a0 = (1.0-s0)*frus_left   + s0*frus_right;
02852   double a1 = (1.0-s1)*frus_left   + s1*frus_right;
02853   double b0 = (1.0-t0)*frus_bottom + t0*frus_top;
02854   double b1 = (1.0-t1)*frus_bottom + t1*frus_top;
02855   if ( -a0 > a1 ) a1 = -a0; else a0 = -a1;
02856   if ( -b0 > b1 ) b1 = -b0; else b0 = -b1;
02857   double d;
02858   if ( (b1-b0)*w < (a1-a0)*h ) {
02859     d = (a1-a0)*h/w;
02860     d = 0.5*(d - (b1-b0));
02861     b0 -= d;
02862     b1 += d;
02863   }
02864   else {
02865     d = (b1-b0)*w/h;
02866     d = 0.5*(d - (a1-a0));
02867     a0 -= d;
02868     a1 += d;
02869   }
02870 
02871   return SetFrustum( a0, a1, b0, b1, frus_near, frus_far );
02872 }
02873 
02874 /*
02875 ON_BOOL32 ON_Viewport::DollyToScreenRect( double view_plane_distance,
02876                                         int x0, int y0, int x1, int y1 )
02877 {
02878   // Only makes sense in a perspective projection. In a parallel projection,
02879   // I resort to ZoomToScreenRect(0 and the visual result is the same.
02880   if ( !IsPerspectiveProjection() )
02881     return ZoomToScreenRect( x0, y0, x1, y1 );
02882 
02883   int port_left, port_right, port_bottom, port_top;
02884   if ( !GetScreenPort( &port_left, &port_right, &port_bottom, &port_top, NULL, NULL ) )
02885     return false;
02886   int dx = (x0+x1)/2;
02887   int dy = (y0+y1)/2;
02888   int cx = (port_left+port_right)/2;
02889   int cy = (port_bottom+port_top)/2;
02890   if ( !DollyAlongScreenChord( dx, dy, cx, cy ) )
02891     return false;
02892   dx = cx - dx;
02893   dy = cy - dy;
02894   x0 += dx;
02895   x1 += dx;
02896   y0 += dy;
02897   y1 += dy;
02898 
02899   double frus_left, frus_right, frus_bottom, frus_top, frus_near, frus_far;
02900   if ( !GetFrustum( &frus_left,   &frus_right, 
02901                      &frus_bottom, &frus_top, 
02902                      &frus_near,   &frus_far ) )
02903     return false;
02904 
02905   double s0, t0, s1, t1;
02906   if ( !GetRelativeScreenCoordinates(port_left, port_right, port_bottom, port_top,
02907                               true,
02908                               x0,y0,x1,y1,
02909                               s0,t0,s1,t1) )
02910     return false;
02911 
02912   double w = frus_right - frus_left;
02913   double h = frus_top - frus_bottom;
02914   double a0 = (1.0-s0)*frus_left   + s0*frus_right;
02915   double a1 = (1.0-s1)*frus_left   + s1*frus_right;
02916   double b0 = (1.0-t0)*frus_bottom + t0*frus_top;
02917   double b1 = (1.0-t1)*frus_bottom + t1*frus_top;
02918   if ( -a0 > a1 ) a1 = -a0; else a0 = -a1;
02919   if ( -b0 > b1 ) b1 = -b0; else b0 = -b1;
02920   double d;
02921   if ( (b1-b0)*w < (a1-a0)*h ) {
02922     d = (a1-a0)*h/w;
02923     d = 0.5*(d - h);
02924     b0 -= d;
02925     b1 += d;
02926   }
02927   else {
02928     d = (b1-b0)*w/h;
02929     d = 0.5*(d - w);
02930     a0 -= d;
02931     a1 += d;
02932   }
02933 
02934   d = 0.5*((a1-a0)/w + (b1-b0)/h)*view_plane_distance;
02935   double delta = d - view_plane_distance;
02936 
02937   frus_near += delta;
02938   frus_far  += delta;
02939   if ( frus_near <= 0.0 ) {
02940     if ( frus_far <= 0.0 )
02941       frus_far = 100.0;
02942     frus_near = 0.001*frus_far;
02943   }
02944   if ( !SetFrustumNearFar( frus_near, frus_far ) )
02945     return false;
02946 
02947   double camLoc[3], camY[3], camZ[3];
02948   if ( !GetCameraFrame( camLoc, NULL, camY, camZ ) )
02949     return false;
02950   camLoc[0] += delta*camZ[0];
02951   camLoc[1] += delta*camZ[1];
02952   camLoc[2] += delta*camZ[2];
02953   camZ[0] = -camZ[0];
02954   camZ[1] = -camZ[1];
02955   camZ[2] = -camZ[2];
02956   if ( !SetCamera( camLoc, camZ, camY ) )
02957     return false;
02958 
02959   return true;
02960 }
02961 */
02962 
02963 bool ON_Viewport::Extents( double angle, const ON_BoundingBox& bbox )
02964 {
02965   double radius;
02966   double x, y, xmin, xmax, ymin, ymax;
02967   int i,j,k;
02968 
02969   if ( !bbox.IsValid() || !IsValid() )
02970     return false;
02971   ON_3dVector camX = CameraX();
02972   ON_3dVector camY = CameraY();
02973   ON_3dPoint center = bbox.Center();
02974   xmin=xmax=ymin=ymax=0.0;
02975   for (i=0;i<2;i++) for (j=0;j<2;j++) for (k=0;k<2;k++) {
02976     ON_3dVector box_corner = bbox.Corner(i,j,k);
02977     x = camX*box_corner;
02978     y = camY*box_corner;
02979     if ( i==0&&j==0&&k==0) {
02980       xmin=xmax=x;
02981       ymin=ymax=y;
02982     }
02983     else {
02984       if ( x > xmax) xmax=x; else if (x < xmin) xmin = x;
02985       if ( y > ymax) ymax=y; else if (y < ymin) ymin = y;
02986     }
02987   }
02988   radius = xmax-xmin;
02989   if ( ymax-ymin > radius )
02990     radius = ymax-ymin;
02991   if ( radius <= ON_SQRT_EPSILON ) {
02992     radius = bbox.Diagonal().MaximumCoordinate();
02993   }
02994   radius *= 0.5;
02995   if ( radius <= ON_SQRT_EPSILON )
02996     radius = 1.0;
02997   return Extents( angle, center, radius );
02998 }
02999 
03000 bool ON_Viewport::Extents( double angle, const ON_3dPoint& center, double radius )
03001 {
03002   if ( !IsValid() )
03003     return false;
03004 
03005   double target_dist, near_dist, far_dist;
03006 
03007   if ( radius <= 0.0 || 
03008        angle  <= 0.0 || 
03009        angle  >= 0.5*ON_PI*(1.0-ON_SQRT_EPSILON) )
03010     return false;
03011   
03012   target_dist = radius/sin(angle);
03013   if ( !IsPerspectiveProjection() )
03014   {
03015     target_dist += 1.0625*radius;
03016   }
03017   near_dist = target_dist - 1.0625*radius;
03018   if ( near_dist < 0.0625*radius )
03019     near_dist = 0.0625*radius;
03020   if ( near_dist < m__MIN_NEAR_DIST )
03021     near_dist = m__MIN_NEAR_DIST;
03022   far_dist = target_dist +  1.0625*radius;
03023 
03024   SetCameraLocation( center + target_dist*CameraZ() );
03025   if ( !SetFrustumNearFar( near_dist, far_dist ) )
03026     return false;
03027   if ( !SetCameraAngle( angle ) )
03028     return false;
03029 
03030   return IsValid()?true:false;
03031 }
03032 
03033 void ON_Viewport::Dump( ON_TextLog& dump ) const
03034 {
03035   dump.Print("ON_Viewport\n");
03036   dump.PushIndent();
03037 
03038   dump.Print("Projection: ");
03039   switch(m_projection)
03040   {
03041   case ON::parallel_view:
03042     dump.Print("parallel\n");
03043     break;
03044   case ON::perspective_view:
03045     dump.Print("perspective\n");
03046     break;
03047   default:
03048     dump.Print("invalid\n");
03049     break;
03050   }
03051   dump.Print("Camera: (m_bValidCamera = %s)\n",(m_bValidCamera?"true":"false"));
03052   dump.PushIndent();
03053   dump.Print("Location: "); if ( CameraLocationIsLocked() ) dump.Print("(locked) "); dump.Print(m_CamLoc); dump.Print("\n");
03054   dump.Print("Direction: "); if ( CameraDirectionIsLocked() ) dump.Print("(locked) "); dump.Print(m_CamDir); dump.Print("\n");
03055   dump.Print("Up: "); if ( CameraUpIsLocked() ) dump.Print("(locked) "); dump.Print(m_CamUp); dump.Print("\n");
03056   dump.Print("X: "); dump.Print(m_CamX); dump.Print("\n");
03057   dump.Print("Y: "); dump.Print(m_CamY); dump.Print("\n");
03058   dump.Print("Z: "); dump.Print(m_CamZ); dump.Print("\n");
03059   dump.PopIndent();
03060   dump.Print("Target Point: "); dump.Print(m_target_point); dump.Print("\n");
03061   dump.Print("target distance %g\n",TargetDistance(true));
03062 
03063   double frus_aspect=0.0;
03064   GetFrustumAspect(frus_aspect);
03065   dump.Print("Frustum: (m_bValidFrustum = %s)\n",(m_bValidFrustum?"true":"false"));
03066   dump.PushIndent();
03067   dump.Print("left/right symmetry locked = %s\n",FrustumIsLeftRightSymmetric()?"true":"false");
03068   dump.Print("top/bottom symmetry locked = %s\n",FrustumIsTopBottomSymmetric()?"true":"false");
03069   dump.Print("left: "); dump.Print(m_frus_left); dump.Print("\n");
03070   dump.Print("right: "); dump.Print(m_frus_right); dump.Print("\n");
03071   dump.Print("bottom: "); dump.Print(m_frus_bottom); dump.Print("\n");
03072   dump.Print("top: "); dump.Print(m_frus_top); dump.Print("\n");
03073   dump.Print("near: "); dump.Print(m_frus_near); dump.Print("\n");
03074   dump.Print("far: "); dump.Print(m_frus_far); dump.Print("\n");
03075   dump.Print("aspect (width/height): "); dump.Print(frus_aspect); dump.Print("\n");
03076   if ( ON::perspective_view == m_projection )
03077   {
03078     dump.PushIndent();
03079     dump.Print("near/far: %g\n",m_frus_near/m_frus_far);
03080     dump.Print("suggested minimum near: = %g\n",m__MIN_NEAR_DIST);
03081     dump.Print("suggested minimum near/far: = %g\n",m__MIN_NEAR_OVER_FAR);
03082     dump.PopIndent();
03083   }
03084   dump.PopIndent();
03085 
03086   double port_aspect=0.0;
03087   GetScreenPortAspect(port_aspect);
03088   dump.Print("Port: (m_bValidPort = %s\n",(m_bValidPort?"true":"false"));
03089   dump.PushIndent();
03090   dump.Print("left: %d\n",m_port_left);
03091   dump.Print("right: %d\n",m_port_right);
03092   dump.Print("bottom: %d\n",m_port_bottom);
03093   dump.Print("top: %d\n",m_port_top);
03094   dump.Print("near: %d\n",m_port_near);
03095   dump.Print("far: %d\n",m_port_far);
03096   dump.Print("aspect (width/height): "); dump.Print(port_aspect); dump.Print("\n");
03097   dump.PopIndent();
03098 
03099   dump.PopIndent();
03100 }
03101 
03102 bool ON_Viewport::GetPointDepth(       
03103        ON_3dPoint point,
03104        double* near_dist,
03105        double* far_dist,
03106        bool bGrowNearFar
03107        ) const
03108 {
03109   bool rc = false;
03110   if ( point.x != ON_UNSET_VALUE )
03111   {
03112     double depth = (m_CamLoc - point)*m_CamZ;
03113     if ( 0 != near_dist && (*near_dist == ON_UNSET_VALUE || !bGrowNearFar || *near_dist > depth) )
03114       *near_dist = depth;
03115     if ( 0 != far_dist && (*far_dist == ON_UNSET_VALUE || !bGrowNearFar || *far_dist < depth) )
03116       *far_dist = depth;
03117     rc = true;
03118   }
03119   return rc;
03120 }
03121 
03122 bool ON_Viewport::GetPointDepth(       
03123        ON_3dPoint point,
03124        double* view_plane_depth
03125        ) const
03126 {
03127   bool rc = false;
03128   if ( point.x != ON_UNSET_VALUE )
03129   {
03130     double depth = (m_CamLoc - point)*m_CamZ;
03131     if ( 0 != view_plane_depth )
03132       *view_plane_depth = depth;
03133     rc = true;
03134   }
03135   return rc;
03136 }
03137 
03138 bool ON_Viewport::GetBoundingBoxDepth(       
03139        ON_BoundingBox bbox,
03140        double* near_dist,
03141        double* far_dist,
03142        bool bGrowNearFar
03143        ) const
03144 {
03145   // The Xbuffer[] stuff is to skip wasting time in unneeded constructors.
03146   // The buffers are double arrays to insure alignments are correct.
03147   ON_3dPoint* C;
03148   ON_3dPoint* P;
03149   ON_PlaneEquation* S;
03150   ON_Line* L;
03151   ON_3dPoint Q;
03152   double Pbuffer[(8+8+8+48)*(sizeof(P[0])/sizeof(double))];
03153   double Sbuffer[5*(sizeof(S[0])/sizeof(double))];
03154   double Lbuffer[4*(sizeof(L[0])/sizeof(double))];
03155   double d, t[2], v[4][8], v0, v1;
03156   const double tol = ON_SQRT_EPSILON*(1.0 + m_CamLoc.MaximumCoordinate());
03157   C = (ON_3dPoint*)Pbuffer;
03158   P = C+8;
03159   S = (ON_PlaneEquation*)Sbuffer;
03160   L = (ON_Line*)Lbuffer;
03161   unsigned int i, j, k, Pin, Pout, Pcount;
03162   bool rc;
03163   const bool bPerspectiveProjection = (ON::perspective_view == m_projection);
03164 
03165   for (;;)
03166   {
03167     rc = bbox.GetCorners(C);
03168     if (!rc)
03169       break;
03170     rc = GetFrustumLeftPlaneEquation(S[0]);
03171     if (!rc)
03172       break;
03173     rc = GetFrustumRightPlaneEquation(S[1]);
03174     if (!rc)
03175       break;
03176     rc = GetFrustumBottomPlaneEquation(S[2]);
03177     if (!rc)
03178       break;
03179     rc = GetFrustumTopPlaneEquation(S[3]);
03180     if (!rc)
03181       break;
03182 
03183     S[4].ON_3dVector::operator=(-m_CamZ);
03184     S[4].d = -S[4].ON_3dVector::operator*(m_CamLoc);
03185     
03186     Pcount = 0;
03187     Pin = 0;
03188     Pout = 0;
03189 
03190     for ( i = 0; i < 8; i++ )
03191     {
03192       k = 0;
03193       if ( (v[0][i] = S[0].ValueAt(C[i])) >= -tol )
03194         k |= 1;      
03195       else
03196         Pout |= 1;
03197       if ( (v[1][i] = S[1].ValueAt(C[i])) >= -tol )
03198         k |= 2;
03199       else
03200         Pout |= 2;
03201       if ( (v[2][i] = S[2].ValueAt(C[i])) >= -tol )
03202         k |= 4;
03203       else
03204         Pout |= 4;
03205       if ( (v[3][i] = S[3].ValueAt(C[i])) >= -tol )
03206         k |= 8;
03207       else
03208         Pout |= 8;
03209 
03210       if ( !bPerspectiveProjection || S[4].ValueAt(C[i]) > 0.0 )
03211         k |= 16;
03212 
03213       Pin |= k;
03214       if ( (1|2|4|8|16) == k )
03215       {
03216         // C[i] is inside the infinte frustum
03217         P[Pcount++] = C[i];
03218       }
03219     }
03220 
03221     if ( Pcount < 8 )
03222     {
03223       // some portion of bbox is outside the infinte frustum
03224       if ( (1|2|4|8|16) != Pin )
03225       {
03226         // bbox does not intersect the infinite frustum.
03227         rc = false;
03228         break;
03229       }
03230 
03231       j = 0;
03232       if ( bPerspectiveProjection )
03233       {
03234         if ( bbox.MinimumDistanceTo(m_CamLoc) <= 0.0 )
03235         {
03236           // camera location is in the bounding box
03237           P[Pcount++] = m_CamLoc;
03238           j = 1; // j = 1 indicates m_CamLoc has been added to P[].
03239         }
03240         L[0].from = m_CamLoc;
03241         L[1].from = m_CamLoc;
03242         L[2].from = m_CamLoc;
03243         L[3].from = m_CamLoc;
03244       }
03245       else
03246       {
03247         rc = GetNearRect(L[0].from,L[1].from,L[2].from,L[3].from);
03248         if (!rc)
03249           break;
03250       }
03251 
03252       rc = GetFarRect(L[0].to,L[1].to,L[2].to,L[3].to);
03253       if (!rc)
03254         break;
03255 
03256       const unsigned int Linout[4] = {
03257         1|4, // intersection of left and bottom frustum sides
03258         2|4, // intersection of right and bottom frustum sides
03259         1|8, // intersection of left and top frustum sides
03260         2|8  // intersection of right and top frustum sides
03261         };
03262 
03263       k = Pin & Pout;
03264       for ( i = 0; i < 4; i++ )
03265       {
03266         // The Linout[i] == ... test is true if bbox is on both sides
03267         // of both planes whose intersection defines the line L[i].
03268         // The fast integer test helps cull unnecessary calls to
03269         // the expensive ON_Intersect() function.
03270         if (    Linout[i] == (k & Linout[i]) 
03271              && ON_Intersect(bbox,L[i],tol,(ON_Interval*)t) 
03272            )
03273         {
03274           if ( bPerspectiveProjection )
03275           {
03276             if ( t[1] < 0.0 )
03277               continue;
03278             if ( t[0] < 0.0 )
03279             {
03280               if ( 0 == j )
03281               {
03282                 P[Pcount++] = m_CamLoc;
03283                 j = 1; // j = 1 indicates m_CamLoc has been added to P[].
03284               }
03285               t[0] = t[1];
03286             }
03287           }
03288           P[Pcount++] = L[i].PointAt(t[0]);
03289           if ( t[1] > t[0] )
03290             P[Pcount++] = L[i].PointAt(t[1]);
03291         }
03292       }
03293 
03294       // intersect box edges with frustum sides
03295       // The 12 bbox edges have endpoints
03296       // C[e[*][0]] and C[E[*][1]]
03297       const unsigned int e[12][2] = {
03298         {0,1},{2,3},{4,5},{6,7},
03299         {0,2},{1,3},{4,6},{5,7},
03300         {0,4},{1,5},{2,6},{3,7}};
03301 
03302       for ( i = 0; i < 4; i++ )
03303       {
03304         for ( j = 0; j < 12; j++ )
03305         {
03306           v0 = v[i][e[j][0]];
03307           v1 = v[i][e[j][1]];
03308           if ( v0*v1 < 0.0 )
03309           {
03310             // this box edge crosses the frustum side plane
03311             d = v0/(v0-v1);
03312             P[Pcount++] = Q = (1.0-d)*C[e[j][0]] + d*C[e[j][1]];
03313             // verify that Q is in the frustum
03314             for ( k = 0; k < 4; k++ )
03315             {
03316               if ( i != k && S[k].ValueAt(Q) <= -tol )
03317               {
03318                 // Q is not in the view frustum
03319                 Pcount--;
03320                 break;
03321               }
03322             }
03323           }
03324         }
03325       }
03326       if ( 0 == Pcount )
03327       {
03328         rc = false;
03329         break;
03330       }
03331     }
03332 
03333     t[0] = t[1] = (m_CamLoc - P[0])*m_CamZ;
03334     for ( i = 1; i < Pcount; i++ )
03335     {
03336       d = (m_CamLoc - P[i])*m_CamZ;
03337       if ( d < t[0] )
03338         t[0] = d;
03339       else if ( d > t[1] )
03340         t[1] = d;
03341     }
03342 
03343     if ( bPerspectiveProjection )
03344     {
03345       if ( t[1] < 0.0 )
03346       {
03347         rc = false;
03348         break;
03349       }
03350       if ( t[0] < 0.0 )
03351         t[0] = 0.0;
03352     }
03353 
03354     if ( 0 != near_dist && (!bGrowNearFar || !ON_IsValid(*near_dist) || t[0] < *near_dist) )
03355       *near_dist = t[0];
03356     if ( 0 != far_dist && (!bGrowNearFar || !ON_IsValid(*far_dist) || t[1] > *far_dist) )
03357       *far_dist = t[1];
03358 
03359     rc = true;
03360     break;
03361   }
03362 
03363   return rc;
03364 }
03365 
03366 bool ON_Viewport::GetSphereDepth( 
03367        ON_Sphere sphere,
03368        double* near_dist,
03369        double* far_dist,
03370        bool bGrowNearFar
03371        ) const
03372 {
03373   bool rc = GetPointDepth( sphere.Center(), near_dist, far_dist, bGrowNearFar );
03374   if ( rc && sphere.Radius() > 0.0 )
03375   {
03376     if ( 0 != near_dist )
03377       *near_dist -= sphere.Radius();
03378     if ( 0 != far_dist )
03379       *far_dist += sphere.Radius();
03380   }
03381   return rc;
03382 }
03383 
03384 bool ON_Viewport::SetFrustumNearFar( 
03385        double near_dist,
03386        double far_dist,
03387        double min_near_dist,
03388        double min_near_over_far,
03389        double target_dist
03390        )
03391 {
03392   double relative_depth_bias = 0.0;
03393   return SetFrustumNearFar( 
03394             near_dist,
03395             far_dist,
03396             min_near_dist,
03397             min_near_over_far,
03398             target_dist,
03399             relative_depth_bias
03400             );
03401 }
03402 
03403 bool ON_Viewport::SetFrustumNearFar( 
03404        double near_dist,
03405        double far_dist,
03406        double min_near_dist,
03407        double min_near_over_far,
03408        double target_dist,
03409        double relative_depth_bias
03410        )
03411 {
03412   if (    !ON_IsValid(near_dist)
03413        || !ON_IsValid(far_dist)
03414        || near_dist > far_dist )
03415   {
03416     return false;
03417   }
03418 
03419   // min_near_over_far needs to be < 1 and should be in the
03420   // range 1e-6 to 1e-2.  By setting negative min's to zero,
03421   // the code below is simplified but still ignores a negative
03422   // input.
03423   const double tiny = ON_ZERO_TOLERANCE;
03424   const double MIN_NEAR_DIST = ( ON_IsValid(m__MIN_NEAR_DIST) &&  m__MIN_NEAR_DIST <= tiny )
03425                             ? m__MIN_NEAR_DIST
03426                             : ON_Viewport::DefaultMinNearDist;
03427   const double MIN_NEAR_OVER_FAR = (    ON_IsValid(m__MIN_NEAR_OVER_FAR)
03428                                      && m__MIN_NEAR_OVER_FAR > tiny 
03429                                      && m__MIN_NEAR_OVER_FAR < 1.0-tiny )
03430                                  ? m__MIN_NEAR_OVER_FAR
03431                                  : ON_Viewport::DefaultMinNearOverFar;
03432 
03433   // 30 May Dale Lear
03434   //    Add checks for validity of min_near_dist and min_near_over_far
03435   if ( !ON_IsValid(min_near_dist) || min_near_dist <= tiny )
03436   {
03437     min_near_dist = MIN_NEAR_DIST;
03438   }
03439 
03440   if (    !ON_IsValid(min_near_over_far) 
03441        || min_near_over_far <= tiny 
03442        || min_near_over_far >= 1.0-tiny )
03443   {
03444     min_near_over_far = MIN_NEAR_OVER_FAR;
03445   }
03446 
03447   if ( IsPerspectiveProjection() )
03448   {
03449     // make sure 0 < near_dist < far_dist
03450     if ( near_dist < min_near_dist )
03451       near_dist = min_near_dist;
03452 
03453     if ( far_dist <= near_dist+tiny )
03454     {
03455       far_dist =  100.0*near_dist;
03456       if ( target_dist > near_dist+min_near_dist && far_dist <= target_dist+min_near_dist )
03457       {
03458         far_dist =  2.0*target_dist - near_dist;
03459       }
03460       if ( near_dist < min_near_over_far*far_dist ) 
03461         far_dist = near_dist/min_near_over_far;
03462     }
03463     // The 1.0001 fudge factor is to ensure successive calls to this function
03464     // give identical results.
03465     while ( near_dist < 1.0001*min_near_over_far*far_dist )
03466     {
03467       // need to move near and far closer together
03468       if ( ON_IsValid(target_dist) && near_dist < target_dist && target_dist < far_dist )
03469       {
03470         // STEP 1
03471         // If near and far are a long ways from the target
03472         // point, move them towards the target so the
03473         // fine tuning in step 2 makes sense.
03474         if ( target_dist/far_dist < min_near_over_far )
03475         {
03476           if ( near_dist/target_dist >= sqrt(min_near_over_far) )
03477           {
03478             // assume near_dist is good and just pull back far_dist
03479             far_dist = near_dist/min_near_over_far;
03480             break;
03481           }
03482           else
03483           {
03484             // move far_dist to within striking distance of the target
03485             // and let STEP 2 fine tune things.
03486             far_dist = target_dist/min_near_over_far;
03487           }
03488         }
03489 
03490         if ( near_dist/target_dist < min_near_over_far )
03491         {
03492           if ( target_dist/far_dist <= sqrt(min_near_over_far) 
03493                && far_dist <= 4.0*target_dist )
03494           {
03495             // assume far_dist is good and just move up near_dist
03496             near_dist = far_dist*min_near_over_far;
03497             break;
03498           }
03499           else
03500           {
03501             // move near_dist to within striking distance of the target
03502             // and let STEP 2 fine tune things.
03503             near_dist = target_dist*min_near_over_far;
03504           }
03505         }
03506 
03507         // STEP 2
03508         // Move near and far towards target by
03509         // an amount proportional to current
03510         // distances from the target.
03511 
03512         double b = (far_dist - target_dist)*min_near_over_far + (target_dist - near_dist);
03513         if ( b > 0.0)
03514         {
03515           double s = target_dist*(1.0 - min_near_over_far)/b;
03516           if ( s > 1.0 || s <= ON_ZERO_TOLERANCE || !ON_IsValid(s) )
03517           {
03518             if ( s > 1.00001 || s <= ON_ZERO_TOLERANCE )
03519             {
03520               // should never happen
03521               ON_ERROR("ON_Viewport::SetFrustumNearFar arithmetic problem 1.");
03522             }
03523             s = 1.0; 
03524           }
03525 
03526           // 19 Jan 2010, Mikko:
03527           // Reordered the operations to guarantee n==near_dist and f==far_dist
03528           // when s==1.0. The old system generated bogus problem reports when the dist
03529           // difference was big.
03530           double n = s*near_dist + target_dist*(1.0-s);
03531           double f = s*far_dist + target_dist*(1.0-s);
03532           //double n = target_dist + s*(near_dist-target_dist);
03533           //double f = target_dist + s*(far_dist-target_dist);
03534 
03535 #if defined(ON_DEBUG)
03536           double m = ((f != 0.0) ? n/f : 0.0)/min_near_over_far;
03537           if ( m < 0.95 || m > 1.05 )
03538           {
03539             ON_ERROR("ON_Viewport::SetFrustumNearFar arithmetic problem 2.");
03540           }
03541 #endif
03542 
03543           if ( n < near_dist || n >= target_dist)
03544           {
03545             ON_ERROR("ON_Viewport::SetFrustumNearFar arithmetic problem 3.");
03546             if ( target_dist < f && f < far_dist )
03547               n = min_near_over_far*f;
03548             else
03549               n = near_dist;
03550           }
03551           if ( f > far_dist || f <= target_dist )
03552           {
03553             ON_ERROR("ON_Viewport::SetFrustumNearFar arithmetic problem 4.");
03554             if ( near_dist < n && n < target_dist )
03555               f = n/min_near_over_far;
03556             else
03557               f = far_dist;
03558           }
03559 
03560           if ( n < min_near_over_far*f )
03561             n = min_near_over_far*f;
03562           else 
03563             f = n/min_near_over_far;
03564 
03565           near_dist = n;
03566           far_dist = f;
03567         }
03568         else
03569         {
03570           near_dist = min_near_over_far*far_dist;
03571         }
03572       }
03573       else if ( ON_IsValid(target_dist) && fabs(far_dist-target_dist) > fabs(near_dist-target_dist) )
03574       {
03575         far_dist = near_dist/min_near_over_far;
03576       }
03577       else
03578       {
03579         near_dist = min_near_over_far*far_dist;
03580       }
03581       break;
03582     }
03583   }
03584   else
03585   {
03586     // parallel projection
03587     if ( far_dist <= near_dist+tiny)
03588     {
03589       double d = fabs(near_dist)*0.125;
03590       if ( d <= MIN_NEAR_DIST || d < tiny || d < min_near_dist )
03591         d = 1.0;
03592       near_dist -= d;
03593       far_dist += d;
03594     }
03595 
03596     if ( near_dist < min_near_dist || near_dist < MIN_NEAR_DIST )
03597     {
03598       if ( !m_bValidCamera )
03599         return false;
03600       // move camera back in parallel projection so everything shows
03601       double h = fabs(m_frus_top - m_frus_bottom);
03602       double w = fabs(m_frus_right - m_frus_left);
03603       double r = 0.5*((h > w) ? h : w);
03604       double n = 3.0*r;
03605       if (n < 2.0*min_near_dist )
03606         n = 2.0*min_near_dist;
03607       if ( n < 2.0*MIN_NEAR_DIST )
03608         n = 2.0*MIN_NEAR_DIST;
03609       double d = n-near_dist;
03610       ON_3dPoint new_loc = CameraLocation() + d*CameraZ();
03611       SetCameraLocation(new_loc);
03612       if ( m_bValidFrustum && fabs(m_frus_near) >= d*ON_SQRT_EPSILON )
03613       {
03614         m_frus_near += d;
03615         m_frus_far += d;
03616       }
03617       near_dist = n;
03618       far_dist += d;
03619       target_dist += d;
03620       if ( far_dist < near_dist )
03621       {
03622         // could happen if d is < ON_EPSILON*far_dist
03623         far_dist = 1.125*near_dist;
03624       }
03625     }
03626   }
03627 
03628   // call bare bones setter
03629   bool rc = SetFrustumNearFar( near_dist, far_dist );
03630 
03631   // if depth bias will be applied, then make an attempt
03632   // to adust the frustum's near plane to prevent
03633   // clipping biased objects.  This post-adjustment
03634   // fixes display bugs like # 87514.
03635   if ( rc 
03636        && relative_depth_bias > 0.0 && relative_depth_bias <= 0.5 
03637        && m_frus_near > min_near_dist
03638        && m_frus_far > m_frus_near
03639        && m_frus_near > MIN_NEAR_DIST
03640        )
03641   {
03642     const double near0 = m_frus_near;
03643     const double far0 = m_frus_far;
03644     double bias_3d = 1.001*relative_depth_bias*(m_frus_far - m_frus_near);
03645     double near1 = m_frus_near - bias_3d;
03646     if ( IsPerspectiveProjection() )
03647     {
03648       if ( near1 < min_near_over_far*far0 || near1 < MIN_NEAR_OVER_FAR*far0 )
03649       {
03650         if (near0 - near1 > 0.01*near0)
03651           near1 = 0.99*near0;
03652       }
03653     }
03654 
03655     // It is important that this test be applied in perspective
03656     // and parallel views.  Otherwise the camera location in
03657     // parallel view will creep back when SetFrustumNearFar()
03658     // is called multiple times.
03659     if ( !(near1 >= min_near_dist && near1 >= MIN_NEAR_DIST) )
03660     {
03661       near1 = (min_near_dist >= MIN_NEAR_DIST)
03662             ? min_near_dist
03663             : MIN_NEAR_DIST;
03664     }
03665 
03666     if ( near1 < near0 )
03667     {
03668 #if defined(ON_DEBUG)
03669       const ON_3dPoint debug_camloc0(m_CamLoc);
03670 #endif
03671       if ( IsPerspectiveProjection() )
03672       {
03673         rc = SetFrustumNearFar( near1, far0 );
03674         if (!rc)
03675           rc = SetFrustumNearFar( near0, far0 );
03676       }
03677       else
03678       {
03679         // call this function again with relative_depth_bias = 0.0
03680         // to get cameral location positioned correctly when near1 
03681         // is too small or negative.
03682         rc = SetFrustumNearFar( 
03683           near1, far0,
03684           min_near_dist, min_near_over_far,
03685           target_dist,
03686           0.0
03687           );
03688         if (!rc)
03689           rc = SetFrustumNearFar( 
03690             near0, far0,
03691             min_near_dist, min_near_over_far,
03692             target_dist,
03693             0.0
03694             );
03695       }
03696 #if defined(ON_DEBUG)
03697       if ( debug_camloc0 != m_CamLoc )
03698       {
03699         ON_WARNING("Relative depth bias changed camera location.");
03700       }
03701 #endif
03702     }
03703   }
03704 
03705   return rc;
03706 }
03707 
03708 
03709 bool ON_Viewport::GetFrustumLeftPlane( 
03710   ON_Plane& left_plane 
03711   ) const
03712 {
03713   bool rc = m_bValidCamera && m_bValidFrustum;
03714   if (rc)
03715   {
03716     if ( IsPerspectiveProjection() )
03717     {
03718       ON_2dVector v(m_frus_near,m_frus_left);
03719       rc = v.Unitize();
03720       left_plane.origin = m_CamLoc;
03721       left_plane.xaxis =  v.y*m_CamX - v.x*m_CamZ;
03722       left_plane.yaxis =  m_CamY;
03723       left_plane.zaxis =  v.x*m_CamX + v.y*m_CamZ;
03724     }
03725     else
03726     {
03727       left_plane.origin = m_CamLoc + m_frus_left*m_CamX;
03728       left_plane.xaxis = -m_CamZ;
03729       left_plane.yaxis =  m_CamY;
03730       left_plane.zaxis =  m_CamX;
03731     }
03732     left_plane.UpdateEquation();
03733   }
03734   return rc;
03735 }
03736 
03737 bool ON_Viewport::GetFrustumLeftPlaneEquation( 
03738   ON_PlaneEquation& left_plane_equation
03739   ) const
03740 {
03741   bool rc = m_bValidCamera && m_bValidFrustum;
03742   if (rc)
03743   {
03744 
03745     if ( IsPerspectiveProjection() )
03746     {
03747       ON_2dVector v(m_frus_near,m_frus_left);
03748       if ( 0 != (rc = v.Unitize()) )
03749       {
03750         left_plane_equation.ON_3dVector::operator=(v.x*m_CamX + v.y*m_CamZ);
03751         left_plane_equation.d = -left_plane_equation.ON_3dVector::operator*(m_CamLoc);
03752       }
03753     }
03754     else
03755     {
03756       left_plane_equation.ON_3dVector::operator=(m_CamX);
03757       left_plane_equation.d = -left_plane_equation.ON_3dVector::operator*(m_CamLoc + m_frus_left*m_CamX);
03758     }
03759   }
03760   return rc;
03761 }
03762 
03763 
03764 bool ON_Viewport::GetFrustumRightPlane( 
03765   ON_Plane& right_plane 
03766   ) const
03767 {
03768   bool rc = m_bValidCamera && m_bValidFrustum;
03769   if (rc)
03770   {
03771     if ( IsPerspectiveProjection() )
03772     {
03773       ON_2dVector v(m_frus_near,-m_frus_right);
03774       rc = v.Unitize();
03775       right_plane.origin = m_CamLoc;
03776       right_plane.xaxis =  v.y*m_CamX + v.x*m_CamZ;
03777       right_plane.yaxis =  m_CamY;
03778       right_plane.zaxis = -v.x*m_CamX + v.y*m_CamZ;
03779     }
03780     else
03781     {
03782       right_plane.origin = m_CamLoc + m_frus_right*m_CamX;
03783       right_plane.xaxis =  m_CamZ;
03784       right_plane.yaxis =  m_CamY;
03785       right_plane.zaxis = -m_CamX;
03786     }
03787     right_plane.UpdateEquation();
03788   }
03789   return rc;
03790 }
03791 
03792 bool ON_Viewport::GetFrustumRightPlaneEquation( 
03793   ON_PlaneEquation& right_plane_equation
03794   ) const
03795 {
03796   bool rc = m_bValidCamera && m_bValidFrustum;
03797   if (rc)
03798   {
03799 
03800     if ( IsPerspectiveProjection() )
03801     {
03802       ON_2dVector v(m_frus_near,-m_frus_right);
03803       if ( 0 != (rc = v.Unitize()) )
03804       {
03805         right_plane_equation.ON_3dVector::operator=(-v.x*m_CamX + v.y*m_CamZ);
03806         right_plane_equation.d = -right_plane_equation.ON_3dVector::operator*(m_CamLoc);
03807       }
03808     }
03809     else
03810     {
03811       right_plane_equation.ON_3dVector::operator=(-m_CamX);
03812       right_plane_equation.d = -right_plane_equation.ON_3dVector::operator*(m_CamLoc + m_frus_right*m_CamX);
03813     }
03814   }
03815   return rc;
03816 }
03817 
03818 
03819 bool ON_Viewport::GetFrustumBottomPlane( 
03820   ON_Plane& bottom_plane 
03821   ) const
03822 {
03823   bool rc = m_bValidCamera && m_bValidFrustum;
03824   if (rc)
03825   {
03826     if ( IsPerspectiveProjection() )
03827     {
03828       ON_2dVector v(m_frus_near,m_frus_bottom);
03829       rc = v.Unitize();
03830       bottom_plane.origin = m_CamLoc;
03831       bottom_plane.xaxis = -v.y*m_CamY + v.x*m_CamZ;
03832       bottom_plane.yaxis =  m_CamX;
03833       bottom_plane.zaxis =  v.x*m_CamY + v.y*m_CamZ;
03834     }
03835     else
03836     {
03837       bottom_plane.origin = m_CamLoc + m_frus_bottom*m_CamY;
03838       bottom_plane.xaxis =  m_CamZ;
03839       bottom_plane.yaxis =  m_CamX;
03840       bottom_plane.zaxis =  m_CamY;
03841     }
03842     bottom_plane.UpdateEquation();
03843   }
03844   return rc;
03845 }
03846 
03847 
03848 bool ON_Viewport::GetFrustumBottomPlaneEquation( 
03849   ON_PlaneEquation& bottom_plane_equation
03850   ) const
03851 {
03852   bool rc = m_bValidCamera && m_bValidFrustum;
03853   if (rc)
03854   {
03855 
03856     if ( IsPerspectiveProjection() )
03857     {
03858       ON_2dVector v(m_frus_near,m_frus_bottom);
03859       if ( 0 != (rc = v.Unitize()) )
03860       {
03861         bottom_plane_equation.ON_3dVector::operator=(v.x*m_CamY + v.y*m_CamZ);
03862         bottom_plane_equation.d = -bottom_plane_equation.ON_3dVector::operator*(m_CamLoc);
03863       }
03864     }
03865     else
03866     {
03867       bottom_plane_equation.ON_3dVector::operator=(m_CamY);
03868       bottom_plane_equation.d = -bottom_plane_equation.ON_3dVector::operator*(m_CamLoc + m_frus_bottom*m_CamY);
03869     }
03870   }
03871   return rc;
03872 }
03873 
03874 
03875 bool ON_Viewport::GetFrustumTopPlane( 
03876   ON_Plane& top_plane 
03877   ) const
03878 {
03879   bool rc = m_bValidCamera && m_bValidFrustum;
03880   if (rc)
03881   {
03882     if ( IsPerspectiveProjection() )
03883     {
03884       ON_2dVector v(m_frus_near,-m_frus_top);
03885       rc = v.Unitize();
03886       top_plane.origin = m_CamLoc;
03887       top_plane.xaxis = -v.y*m_CamY - v.x*m_CamZ;
03888       top_plane.yaxis =  m_CamX;
03889       top_plane.zaxis = -v.x*m_CamY + v.y*m_CamZ;
03890     }
03891     else
03892     {
03893       top_plane.origin = m_CamLoc + m_frus_top*m_CamY;
03894       top_plane.xaxis = -m_CamZ;
03895       top_plane.yaxis =  m_CamX;
03896       top_plane.zaxis = -m_CamY;
03897     }
03898     top_plane.UpdateEquation();
03899   }
03900   return rc;
03901 }
03902 
03903 bool ON_Viewport::GetFrustumTopPlaneEquation( 
03904   ON_PlaneEquation& top_plane_equation
03905   ) const
03906 {
03907   bool rc = m_bValidCamera && m_bValidFrustum;
03908   if (rc)
03909   {
03910 
03911     if ( IsPerspectiveProjection() )
03912     {
03913       ON_2dVector v(m_frus_near,-m_frus_top);
03914       if ( 0 != (rc = v.Unitize()) )
03915       {
03916         top_plane_equation.ON_3dVector::operator=(-v.x*m_CamY + v.y*m_CamZ);
03917         top_plane_equation.d = -top_plane_equation.ON_3dVector::operator*(m_CamLoc);
03918       }
03919     }
03920     else
03921     {
03922       top_plane_equation.ON_3dVector::operator=(-m_CamY);
03923       top_plane_equation.d = -top_plane_equation.ON_3dVector::operator*(m_CamLoc + m_frus_top*m_CamY);
03924     }
03925   }
03926   return rc;
03927 }
03928 
03929 void ON_Viewport::GetViewScale( double* x, double* y ) const
03930 {
03931   if ( x ) *x = 1.0;
03932   if ( y ) *y = 1.0;
03933   if ( !m_clip_mods.IsIdentity()
03934        && 0.0 == m_clip_mods.m_xform[3][0]
03935        && 0.0 == m_clip_mods.m_xform[3][1]
03936        && 0.0 == m_clip_mods.m_xform[3][2]
03937        && 1.0 == m_clip_mods.m_xform[3][3]
03938      )
03939   {
03940     // 04 November 2011 S. Baer (RR93636)
03941     //   See comments in SetViewScale about why we are ignoring the test for 1
03942     //   on either sx or sy
03943     double sx = m_clip_mods.m_xform[0][0];
03944     double sy = m_clip_mods.m_xform[1][1];
03945     if (    sx > ON_ZERO_TOLERANCE
03946          && sy > ON_ZERO_TOLERANCE
03947          && 0.0 == m_clip_mods.m_xform[0][1]
03948          && 0.0 == m_clip_mods.m_xform[0][2]
03949          && 0.0 == m_clip_mods.m_xform[1][0]
03950          && 0.0 == m_clip_mods.m_xform[1][2]
03951          // && (1.0 == sx || 1.0 == sy )
03952         )
03953     {
03954       if ( x ) *x = sx;
03955       if ( y ) *y = sy;
03956     }
03957   }
03958 }
03959 
03960 //bool ON_Viewport::ScaleView( double x, double y, double z )
03961 //{
03962 //  // z ignored on purpose - it was a mistake to include z
03963 //  return (!IsPerspectiveProjection()) ? SetViewScale(x,y) : false;
03964 //}
03965 
03966 bool ON_Viewport::SetViewScale( double x, double y )
03967 {
03968   // 22 May Dale Lear
03969   //   View scaling should have been done by adjusting the 
03970   //   frustum left/right top/bottom but I was stupid and added a clipmodxform 
03971   //   that is more trouble than it is worth.
03972   //   Someday I will fix this.  In the mean time, I want all scaling requests
03973   //   to flow through SetViewScale/GetViewScale so I can easly find and fix
03974   //   things when I have time to do it right.
03975   // 04 November 2011 S. Baer (RR93636)
03976   //   This function is used for printer calibration and it is commonly possible
03977   //   to need to apply a scale in both x and y.  The reason for the need of x
03978   //   or y to be one is because the view scale is encoded in the clip mod xform
03979   //   and it is hard to be sure that we could accurately extract these values
03980   //   when calling GetViewScale.  Removing the requirement to have one of the
03981   //   values == 1
03982   bool rc = false;
03983   if (    !IsPerspectiveProjection() 
03984        && x > ON_ZERO_TOLERANCE && ON_IsValid(x) 
03985        && y > ON_ZERO_TOLERANCE && ON_IsValid(y) 
03986        // && (1.0 == x || 1.0 == y)
03987        )
03988   {
03989     ON_Xform xform(1.0);
03990     xform.m_xform[0][0] = x;
03991     xform.m_xform[1][1] = y;
03992     rc = SetClipModXform(xform);
03993   }
03994   return rc;
03995 }
03996 
03997 double ON_Viewport::ClipCoordDepthBias( double relative_depth_bias, double clip_z, double clip_w ) const
03998 {
03999   double d;
04000   if ( m_frus_far > m_frus_near 
04001        && 0.0 != relative_depth_bias 
04002        && 0.0 != clip_w
04003      )
04004   {
04005     if ( ON::perspective_view == m_projection )
04006     {
04007       // To get the formula for the code in this claus:
04008       //
04009       // Set M = [Camera2Clip]*[translation by (0,0,relative_depth_bias*(f-n)]*[Clip2Camera]
04010       // Note that M maps clipping coordinates to clipping coordinates.
04011       //
04012       // Calculate M([x,y,z,w]) = [p,q,r,s]
04013       //
04014       // This function returns (r/s - z/w)*w
04015       //
04016       // If you are actually doing this calculation and trying to 
04017       // get the formula used in the code below, it helps to notice
04018       // that (f+n)/(f-n) = a/b.
04019       //
04020       // Note that there "should" be a small adjustment to the
04021       // x and y coordinates that is not performed by tweaking
04022       // the z clipping coordiante
04023       //    z += vp->ClipCoordDepthBias( rel_bias, z, w );
04024       // but the effect is actually better when the goal is to
04025       // make wires that are on shaded surfaces appear because
04026       // their horizons are not altered.
04027       // 
04028       // This method is more complicated that adding a constant
04029       // depth buffer bias but is required for high quality images
04030       // when values of far/near get to be around 1e4 or larger.
04031       //
04032       double a = m_frus_far + m_frus_near;
04033       double b = m_frus_far - m_frus_near;
04034       double c = 0.5*relative_depth_bias/(m_frus_far*m_frus_near);
04035       double t = a + b*clip_z/clip_w;
04036       d = c*t*t*clip_w/(1.0 - c*b*t);
04037     }
04038     else
04039     {
04040       // The "2.0*" is here because clipping coordinates run from
04041       // -1 to +1, a distance of 2 units.
04042       d = 2.0*relative_depth_bias*clip_w;
04043     }
04044   }
04045   else
04046   {
04047     d = 0.0;
04048   }
04049   return d;
04050 }
04051 
04052 bool ON_Viewport::GetClipCoordDepthBiasXform( 
04053     double relative_depth_bias,
04054     ON_Xform& clipbias 
04055     ) const
04056 {
04057   bool rc = false;
04058 
04059   while ( 0.0 != relative_depth_bias
04060        && m_frus_far > m_frus_near
04061        )
04062   {
04063     if ( ON::perspective_view == m_projection )
04064     {
04065       ON_Xform clip2cam, cam_delta(1.0), cam2clip;
04066       if ( !cam2clip.CameraToClip(true,m_frus_left,m_frus_right,m_frus_bottom,m_frus_top,m_frus_near,m_frus_far) )
04067         break;
04068       if ( !clip2cam.ClipToCamera(true,m_frus_left,m_frus_right,m_frus_bottom,m_frus_top,m_frus_near,m_frus_far) )
04069         break;
04070       cam_delta.m_xform[2][3] = relative_depth_bias*(m_frus_far-m_frus_near);
04071       clipbias = cam2clip*cam_delta*clip2cam;
04072     }
04073     else
04074     {
04075       clipbias.Identity();
04076       clipbias.m_xform[2][3] = 2.0*relative_depth_bias;
04077     }
04078     rc = true;
04079     break;
04080   }
04081 
04082   if (!rc)
04083     clipbias.Identity();
04084 
04085   return rc;
04086 }
04087 
04088 bool ON_Viewport::SetClipModXform( ON_Xform clip_mod_xform )
04089 {
04090   bool rc = false;
04091   ON_Xform clip_mod_inverse_xform = clip_mod_xform;
04092   rc = clip_mod_inverse_xform.Invert();
04093   if ( rc )
04094   {
04095     ON_Xform id = clip_mod_inverse_xform*clip_mod_xform;
04096     double e;
04097     int i, j;
04098     for ( i = 0; i < 4 && rc; i++ ) for ( j = 0; j < 4 && rc; j++ )
04099     {
04100       e = ( i == j ) ? 1.0 : 0.0;
04101       if ( fabs(id.m_xform[i][j] - e) > ON_SQRT_EPSILON )
04102       {
04103         rc = false;
04104       }
04105     }
04106     if (rc)
04107     {
04108       m_clip_mods = clip_mod_xform;
04109       m_clip_mods_inverse = clip_mod_inverse_xform;
04110     }
04111   }
04112   return rc;
04113 }
04114 
04115 bool ON_Viewport::ClipModXformIsIdentity() const
04116 {
04117   return m_clip_mods.IsIdentity();
04118 }
04119 
04120 ON_Xform ON_Viewport::ClipModXform() const
04121 {
04122   return m_clip_mods;
04123 }
04124 
04125 ON_Xform ON_Viewport::ClipModInverseXform() const
04126 {
04127   return m_clip_mods_inverse;
04128 }
04129 
04130 bool ON_Viewport::SetTargetPoint( ON_3dPoint target_point )
04131 {
04132   bool rc = (target_point.IsValid() || (ON_UNSET_POINT == target_point));
04133   if (rc)
04134     m_target_point = target_point;
04135   return rc;
04136 }
04137 
04138 ON_3dPoint ON_Viewport::FrustumCenterPoint( double target_distance ) const
04139 {
04140   double s,dx,dy,dz;
04141   ON_3dPoint target_point = ON_3dPoint::UnsetPoint;
04142 
04143   if (!m_bValidCamera || !m_bValidFrustum)
04144     return target_point;
04145 
04146   if ( ON_UNSET_VALUE == target_distance && m_bValidFrustum 
04147        && m_frus_near > 0.0 && m_frus_far >= m_frus_near
04148      )
04149   {
04150     target_distance = 0.5*(m_frus_near+m_frus_far);
04151     if ( target_distance < m_frus_near )
04152       target_distance = m_frus_near;
04153     else if ( target_distance > m_frus_far )
04154       target_distance = m_frus_far;
04155   }
04156 
04157   if ( !ON_IsValid(target_distance) || target_distance <= 0.0 )
04158     return target_point;
04159 
04160   if ( m_bValidFrustum )
04161   {
04162     s  = (ON::perspective_view == m_projection && m_frus_near > 0.0)
04163        ? 0.5*target_distance/m_frus_near
04164        : 0.5;
04165     dx = FrustumIsLeftRightSymmetric() 
04166        ?  0.0
04167        : s*(m_frus_right+m_frus_left);
04168     dy = FrustumIsTopBottomSymmetric() 
04169        ?  0.0
04170        : s*(m_frus_top+m_frus_bottom);
04171   }
04172   else
04173   {
04174     dx = dy = 0.0;
04175   }
04176   dz = -target_distance;
04177 
04178   // Done this way instead of using ON_3dPoint/ON_3dVector arithmetic so the
04179   // optimizer can generate maximum precision when using 64 bit mantissas.
04180   target_point.x = (m_CamLoc.x + dx*m_CamX.x + dy*m_CamY.x + dz*m_CamZ.x);
04181   target_point.y = (m_CamLoc.y + dx*m_CamX.y + dy*m_CamY.y + dz*m_CamZ.y);
04182   target_point.z = (m_CamLoc.z + dx*m_CamX.z + dy*m_CamY.z + dz*m_CamZ.z);
04183 
04184   return target_point;
04185 }
04186 
04187 ON_3dPoint ON_Viewport::TargetPoint() const
04188 {
04189   return m_target_point;
04190 }
04191 
04192 
04193 double ON_Viewport::TargetDistance( bool bUseFrustumCenterFallback ) const
04194 {
04195   double d = ON_UNSET_VALUE;
04196   if ( m_bValidCamera )
04197   {
04198     if ( bUseFrustumCenterFallback && !m_bValidFrustum )
04199       bUseFrustumCenterFallback = false;
04200     if ( m_target_point.IsValid() )
04201     {
04202       d = (m_CamLoc - m_target_point)*m_CamZ;
04203       if ( bUseFrustumCenterFallback && (!ON_IsValid(d) || d <= 0.0) )
04204         d = ON_UNSET_VALUE;
04205     }
04206     if ( bUseFrustumCenterFallback 
04207         && ON_UNSET_VALUE == d 
04208         && m_frus_far >= m_frus_near
04209         )
04210     {
04211       d = 0.5*(m_frus_near+m_frus_far);
04212       if ( d < m_frus_near ) d = m_frus_near; else if (d > m_frus_far) d = m_frus_far;
04213       if ( d <= 0.0 )
04214         d = ON_UNSET_VALUE;
04215     }
04216   }
04217   return d;
04218 }
04219 
04220 bool ON_Viewport::SetViewportId( const ON_UUID& id)
04221 {
04222   // Please discuss any code changes with Dale Lear.
04223   // You should NEVER change the viewport id once
04224   // it is set.
04225   bool rc = (0 == memcmp(&m_viewport_id,&id,sizeof(m_viewport_id)));
04226   if ( !rc && m_viewport_id == ON_nil_uuid )
04227   {  
04228     m_viewport_id = id;
04229     rc = true;
04230   }
04231   return rc;
04232 }
04233 
04234 void ON_Viewport::ChangeViewportId(const ON_UUID& viewport_id)
04235 {
04236   m_viewport_id = viewport_id; // <- good place for a breakpoint
04237 }
04238 
04239 
04240 ON_UUID  ON_Viewport::ViewportId(void) const
04241 {
04242   return m_viewport_id;
04243 }
04244 
04245 
04246 class ON_PgonPt
04247 {
04248 public:
04249   ON_3dPoint m_P;
04250   ON_2dVector m_Q;
04251   double m_negcotangle;
04252 };
04253 
04254 static 
04255 int comparePptAngle( const void* pa, const void* pb )
04256 {
04257   double a = ((const ON_PgonPt*)pa)->m_negcotangle;
04258   double b = ((const ON_PgonPt*)pb)->m_negcotangle;
04259   if ( a == b )
04260   {
04261     a = ((const ON_PgonPt*)pa)->m_Q.LengthSquared();
04262     b = ((const ON_PgonPt*)pb)->m_Q.LengthSquared();
04263   }
04264   return ((a>b) ? 1 : ((a==b) ? 0 : -1));
04265 }
04266 
04267 bool ON_IntersectViewFrustumPlane( 
04268     const ON_Viewport& vp,
04269     const ON_PlaneEquation& plane_equation, 
04270     ON_SimpleArray<ON_3dPoint>& points 
04271     )
04272 {
04273 
04274   double left, right, bottom, top, near_dist, far_dist;
04275   double v[8], v0, v1, s;
04276   ON_PgonPt ppt, ppt_list[24];
04277   ON_3dPoint F[8], P0, P1, P;
04278   ON_2dVector D;
04279   const ON_3dPoint  C = vp.CameraLocation();
04280   const ON_3dVector X = vp.CameraX();
04281   const ON_3dVector Y = vp.CameraY();
04282   const ON_3dVector Z = -vp.CameraZ();
04283   int e[12][2] = {{0,1},{1,2},{2,3},{3,0},
04284                   {4,5},{5,6},{6,7},{7,4},
04285                   {0,4},{1,5},{2,6},{3,7}};
04286   int i, i0, i1;
04287   int ppt_count = 0;
04288 
04289   if ( !vp.IsValidCamera() || !vp.GetFrustum(&left,&right,&bottom,&top,&near_dist,&far_dist) )
04290     return false;
04291 
04292   const ON_Plane plane(plane_equation);
04293   if ( !plane.IsValid() )
04294     return false;
04295 
04296   s = ON::perspective_view == vp.Projection() 
04297     ? far_dist/near_dist
04298     : 1.0;
04299   F[0] = C + left*X  + bottom*Y + near_dist*Z;
04300   F[1] = C + right*X + bottom*Y + near_dist*Z;
04301   F[2] = C + right*X + top*Y    + near_dist*Z;
04302   F[3] = C + left*X  + top*Y    + near_dist*Z;
04303 
04304   F[4] = C + s*left*X  + s*bottom*Y + far_dist*Z;
04305   F[5] = C + s*right*X + s*bottom*Y + far_dist*Z;
04306   F[6] = C + s*right*X + s*top*Y    + far_dist*Z;
04307   F[7] = C + s*left*X  + s*top*Y    + far_dist*Z;
04308 
04309   for ( i = 0; i < 8; i++ )
04310   {
04311     v[i] = plane_equation.ValueAt(F[i]);
04312   }
04313 
04314   for ( i = 0; i < 12; i++ )
04315   {
04316     v0 = v[e[i][0]];
04317     v1 = v[e[i][1]];
04318     P0 = F[e[i][0]];
04319     P1 = F[e[i][1]];
04320     if ( (v0 <= 0.0 && v1 >= 0.0) || (v0 >= 0.0 && v1 <= 0.0) )
04321     {
04322       if ( v0 == v1 )
04323       {
04324         ppt_list[ppt_count++].m_P = P0;
04325         ppt_list[ppt_count++].m_P = P1;
04326       }
04327       else
04328       {
04329         s = v1/(v1-v0);
04330         P = s*P0 + (1.0-s)*P1;
04331         ppt_list[ppt_count++].m_P = P;
04332       }
04333     }
04334   }
04335 
04336   if ( ppt_count <= 0 )
04337     return true; // plane misses frustum
04338 
04339   i0 = 0;
04340   for ( i = 0; i < ppt_count; i++ )
04341   {
04342     plane.ClosestPointTo( ppt_list[i].m_P, &ppt_list[i].m_Q.x, &ppt_list[i].m_Q.y );
04343     if (     ppt_list[i].m_Q.y < ppt_list[i0].m_Q.y 
04344          || (ppt_list[i].m_Q.y == ppt_list[i0].m_Q.y && ppt_list[i].m_Q.x < ppt_list[i0].m_Q.x) )
04345       i0 = i;
04346   }
04347 
04348   // Use Gram scan to get the convex hull and save it in points[].
04349   // See http://en.wikipedia.org/wiki/Graham_scan for details.
04350 
04351   // put point with smallest m_Q.y coordinate in ppt_list[0].
04352   ppt = ppt_list[i0];
04353   if ( i0 )
04354   {
04355     ppt_list[i0] = ppt_list[0];
04356     ppt_list[0] = ppt;
04357     i0 = 0;
04358   }
04359 
04360   // sort points by the angle (ppt_list[i].m_Q = ppt_list[0].m_Q) makes
04361   // with the positve x axis.  This is the same as sorting them by
04362   // -cot(angle) = -deltax/deltay.
04363   ppt_list[0].m_negcotangle = -ON_DBL_MAX; // -cot(0) = - infinity
04364   for ( i = 1; i < ppt_count; i++ )
04365   {
04366     ppt_list[i].m_Q.x -= ppt_list[0].m_Q.x;
04367     ppt_list[i].m_Q.y -= ppt_list[0].m_Q.y;
04368     ppt_list[i].m_negcotangle = (0.0 >= ppt_list[i].m_Q.y) ? -ON_DBL_MAX : -ppt_list[i].m_Q.x/ppt_list[i].m_Q.y;
04369   }
04370   ppt_list[0].m_Q.x = 0.0;
04371   ppt_list[0].m_Q.y = 0.0;
04372   ON_qsort(ppt_list+1,ppt_count-1,sizeof(ppt_list[0]),comparePptAngle);
04373 
04374   points.Append(ppt_list[0].m_P);
04375   i0 = 0;
04376   i1 = 1;
04377   D = ppt_list[i1].m_Q - ppt_list[i0].m_Q;
04378 
04379   for ( i = 2; i < ppt_count; i++ )
04380   {
04381     if ( (ppt_list[i].m_Q.y - ppt_list[i0].m_Q.y)*D.x <= (ppt_list[i].m_Q.x - ppt_list[i0].m_Q.x)*D.y )
04382     {
04383       // ppt_list[i0], ppt_list[i1], ppt_list[i] is a "right" turn or colinear.
04384       // Drop ppt_list[i1].
04385       i1 = i;
04386     }
04387     else
04388     {
04389       // ppt_list[i0], ppt_list[i1], ppt_list[i] is a "left" turn.
04390       points.Append(ppt_list[i1].m_P);
04391       i0 = i1;
04392       i1 = i;
04393     }
04394     D = ppt_list[i1].m_Q - ppt_list[i0].m_Q;
04395   }
04396 
04397   if ( i1 > i0 )
04398     points.Append(ppt_list[i1].m_P);
04399 
04400   return true;
04401 }
04402 
04403 void ON_Viewport::GetPerspectiveClippingPlaneConstraints( 
04404   ON_3dPoint camera_location,
04405   unsigned int depth_buffer_bit_depth,
04406   double* min_near_dist,
04407   double* min_near_over_far
04408   )
04409 {
04410   double nof, n, d;
04411 
04412   if ( camera_location.IsValid() )
04413   {
04414     /*
04415 
04416     // This code was used prior to 14 July 2011.
04417     //
04418     d = camera_location.DistanceTo(ON_3dPoint::Origin);
04419     if ( d >= 1.0e5 )
04420     {
04421       if ( depth_buffer_bit_depth >= 32 )
04422         depth_buffer_bit_depth -= 24;
04423       else
04424         depth_buffer_bit_depth = 8;
04425     }
04426     else if ( d >= 1.0e4 )
04427     {
04428       if ( depth_buffer_bit_depth >= 24 )
04429         depth_buffer_bit_depth -= 16;
04430       else
04431         depth_buffer_bit_depth = 8;
04432     }
04433     else if ( d >= 1.0e3 )
04434     {
04435       if ( depth_buffer_bit_depth >= 16 )
04436         depth_buffer_bit_depth -= 8;
04437       else
04438         depth_buffer_bit_depth = 8;
04439     }
04440     */
04441 
04442     // 14 July 2011 - Dale Lear
04443     //   The reductions above were too harsh and were
04444     //   generating clipping artifacts in the perspective
04445     //   view in bug report 88216.  Changing to
04446     //   to the code below gets rid of those
04447     //   artifacts at the risk of having a meaninless
04448     //   view to clip transform if the transformation is
04449     //   calculated with single precision numbers.
04450     //   If these values require further tuning, please
04451     //   discuss changes with me and attach example files
04452     //   to bug report 88216.
04453     d = camera_location.MaximumCoordinate();
04454     if ( d > 1.0e6 && depth_buffer_bit_depth >= 16 )
04455       depth_buffer_bit_depth -= 8;
04456   }
04457 
04458   if ( depth_buffer_bit_depth >= 32 )
04459   {
04460     nof = 0.0001;
04461     n = 0.001;
04462   }
04463   else if ( depth_buffer_bit_depth >= 24 )
04464   {
04465     nof = 0.0005;
04466     n = 0.005;
04467   }
04468   else if ( depth_buffer_bit_depth >= 16 )
04469   {
04470     nof = 0.005;
04471     n = 0.005;
04472   }
04473   else
04474   {
04475     nof = 0.01;
04476     n = 0.01;
04477   }
04478 
04479   if ( min_near_dist )
04480     *min_near_dist = n;
04481   if ( min_near_over_far )
04482     *min_near_over_far = nof;
04483 }


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