opennurbs_torus.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_Torus::ON_Torus() : major_radius(0.0), minor_radius(0.0)
00020 {}
00021 
00022 ON_Torus::ON_Torus( const ON_Plane& major_plane, double major__radius, double minor__radius )
00023 {
00024   Create(major_plane,major__radius,minor__radius);
00025 }
00026 
00027 ON_Torus::ON_Torus( const ON_Circle& major__circle, double minor__radius )
00028 {
00029   Create(major__circle,minor__radius);
00030 }
00031 
00032 ON_Torus::~ON_Torus()
00033 {}
00034 
00035 ON_BOOL32 ON_Torus::IsValid( ON_TextLog* text_log ) const
00036 {
00037   bool rc=false;
00038   if ( minor_radius <= 0.0 )
00039   {
00040     if ( text_log )
00041       text_log->Print("ON_Torus.minor_radius = %g (should be > 0)\n",minor_radius);
00042   }
00043   else if ( major_radius <= minor_radius)
00044   {
00045     if ( text_log )
00046       text_log->Print("ON_Torus.major_radius = %g (should be > minor_radius=%g)\n",major_radius,minor_radius);
00047   }
00048   else if ( !plane.IsValid() )
00049   {
00050     if ( text_log )
00051       text_log->Print("ON_Torus.plane is not valid.\n");
00052   }
00053   else
00054     rc = true;
00055   return rc;
00056 }
00057 
00058 ON_BOOL32 ON_Torus::Create( const ON_Plane& major_plane, double major__radius, double minor__radius )
00059 {
00060   plane = major_plane;
00061   major_radius = major__radius;
00062   minor_radius = minor__radius;
00063   return IsValid();
00064 }
00065 
00066 ON_BOOL32 ON_Torus::Create( const ON_Circle& major__circle, double minor__radius )
00067 {
00068   return Create( major__circle.plane, major__circle.radius, minor__radius );
00069 }
00070 
00071 #define EVAL_SETUP_MINOR \
00072   const double sin_ma = sin(minor_angle_radians);\
00073   const double cos_ma = cos(minor_angle_radians)
00074 
00075 #define EVAL_SETUP_MAJOR \
00076   const double sin_MA = sin(major_angle_radians);\
00077   const double cos_MA = cos(major_angle_radians);\
00078   const ON_3dVector raxis = cos_MA*plane.xaxis + sin_MA*plane.yaxis
00079 
00080 ON_3dPoint ON_Torus::PointAt(double major_angle_radians, double minor_angle_radians) const
00081 {
00082   EVAL_SETUP_MINOR;
00083   EVAL_SETUP_MAJOR;
00084   return ((major_radius + cos_ma*minor_radius)*raxis + sin_ma*minor_radius*plane.zaxis + plane.origin);
00085 }
00086 
00087 ON_3dVector ON_Torus::NormalAt(double major_angle_radians, double minor_angle_radians) const
00088 {
00089   EVAL_SETUP_MINOR;
00090   EVAL_SETUP_MAJOR;
00091   return (cos_ma*raxis + sin_ma*plane.zaxis);
00092 }
00093 
00094 ON_Circle ON_Torus::MajorCircleRadians(double minor_angle_radians ) const
00095 {
00096   EVAL_SETUP_MINOR;
00097   ON_Circle c(plane,major_radius);
00098   c.radius = major_radius + cos_ma*minor_radius;
00099   c.plane.origin += sin_ma*minor_radius*plane.zaxis;
00100   c.plane.UpdateEquation();
00101   return c;
00102 }
00103 
00104 ON_Circle ON_Torus::MajorCircleDegrees(double minor_angle_degrees ) const
00105 {
00106   return MajorCircleRadians(minor_angle_degrees*ON_PI/180.0);
00107 }
00108 
00109 ON_Circle ON_Torus::MinorCircleRadians(double major_angle_radians ) const
00110 {
00111   EVAL_SETUP_MAJOR;
00112   ON_Circle c;
00113   c.plane.xaxis = raxis;
00114   c.plane.yaxis = plane.zaxis;
00115   c.plane.zaxis = ON_CrossProduct( c.plane.xaxis, c.plane.yaxis );
00116   c.plane.origin = plane.origin + major_radius*raxis;
00117   c.plane.UpdateEquation();
00118   c.radius = minor_radius;
00119   return c;
00120 }
00121 
00122 ON_Circle ON_Torus::MinorCircleDegrees(double minor_angle_degrees ) const
00123 {
00124   return MinorCircleRadians(minor_angle_degrees*ON_PI/180.0);
00125 }
00126 
00127 ON_3dPoint ON_Torus::Center() const
00128 {
00129   return plane.origin;
00130 }
00131 
00132 ON_3dVector ON_Torus::Axis() const
00133 {
00134   return plane.zaxis;
00135 }
00136 
00137 double ON_Torus::MajorRadius() const
00138 {
00139   return major_radius;
00140 }
00141 
00142 double ON_Torus::MinorRadius() const
00143 {
00144   return minor_radius;
00145 }
00146 
00147 ON_BOOL32 ON_Torus::ClosestPointTo( 
00148          ON_3dPoint test_point, 
00149          double* major__angle_radians, 
00150          double* minor__angle_radians
00151        ) const
00152 {
00153   double major_angle_radians, minor_angle_radians;
00154   const ON_Circle major_circle(plane,major_radius);
00155   ON_BOOL32 rc = major_circle.ClosestPointTo( test_point, &major_angle_radians );
00156   if ( rc && minor__angle_radians )
00157   {
00158     EVAL_SETUP_MAJOR;
00159     ON_3dVector v = test_point - major_radius*raxis;
00160     rc = v.Unitize();
00161     if ( rc )
00162     {
00163       double sma = v*plane.zaxis;
00164       double cma = v*raxis;
00165       minor_angle_radians = atan2(sma,cma);
00166       if ( minor_angle_radians < 0.0 )
00167         minor_angle_radians += 2.0*ON_PI;
00168     }
00169     else
00170       minor_angle_radians = 0.0;
00171     *minor__angle_radians = minor_angle_radians;
00172   }
00173   if ( major__angle_radians )
00174     *major__angle_radians = major_angle_radians;
00175   return rc;
00176 }
00177 
00178 ON_3dPoint ON_Torus::ClosestPointTo( ON_3dPoint test_point ) const
00179 {
00180   const ON_Circle major_circle(plane,major_radius);
00181   ON_3dPoint C = major_circle.ClosestPointTo( test_point );
00182   ON_3dVector v = test_point - C;
00183   if ( !v.Unitize() )
00184   {
00185     v = C - plane.origin;
00186     v.Unitize();
00187   }
00188   return C + minor_radius*v;
00189 }
00190 
00191 
00192 // rotate cylinder about its origin
00193 ON_BOOL32 ON_Torus::Rotate(
00194       double sin_angle,
00195       double cos_angle,
00196       const ON_3dVector& axis // axis of rotation
00197       )
00198 {
00199   return Rotate(sin_angle, cos_angle, axis, plane.origin );
00200 }
00201 
00202 ON_BOOL32 ON_Torus::Rotate(
00203       double angle,            // angle in radians
00204       const ON_3dVector& axis // axis of rotation
00205       )
00206 {
00207   return Rotate(sin(angle), cos(angle), axis, plane.origin );
00208 }
00209 
00210 ON_BOOL32 ON_Torus::Rotate(
00211       double sin_angle,
00212       double cos_angle,
00213       const ON_3dVector& axis, // axis of rotation
00214       const ON_3dPoint&  point // center of rotation
00215       )
00216 {
00217   return plane.Rotate( sin_angle, cos_angle, axis, point );
00218 }
00219 
00220 ON_BOOL32 ON_Torus::Rotate(
00221       double angle,             // angle in radians
00222       const ON_3dVector& axis,  // axis of rotation
00223       const ON_3dPoint&  point  // center of rotation
00224       )
00225 {
00226   return Rotate(sin(angle),cos(angle),axis,point);
00227 }
00228 
00229 ON_BOOL32 ON_Torus::Translate( const ON_3dVector& delta )
00230 {
00231   return plane.Translate(delta);
00232 }
00233 
00234 ON_BOOL32 ON_Torus::Transform( const ON_Xform& xform )
00235 {
00236   ON_Circle major_c(plane,major_radius);
00237   ON_BOOL32 rc = major_c.Transform(xform);
00238   if (rc)
00239   {
00240     double s = (0.0==major_radius) ? 1.0 : major_c.radius/major_radius;
00241     plane = major_c.plane;
00242     major_radius = major_c.radius;
00243     minor_radius *= s;
00244   }
00245   return rc;
00246 }
00247 
00248 
00249 int ON_Torus::GetNurbForm( ON_NurbsSurface& s ) const
00250 {
00251   int rc = 0;
00252   ON_RevSurface revsrf;
00253   if ( RevSurfaceForm(&revsrf) )
00254   {
00255     rc = revsrf.GetNurbForm(s);
00256   }
00257   else
00258     s.Destroy();
00259   return rc;
00260 }
00261 
00262 ON_RevSurface* ON_Torus::RevSurfaceForm( ON_RevSurface* srf ) const
00263 {
00264   if ( srf )
00265     srf->Destroy();
00266   ON_RevSurface* pRevSurface = NULL;
00267   if ( IsValid() )
00268   {
00269     ON_Circle circle = MinorCircleRadians(0.0);
00270     ON_ArcCurve* circle_crv = new ON_ArcCurve(circle);
00271     if ( srf )
00272       pRevSurface = srf;
00273     else
00274       pRevSurface = new ON_RevSurface();
00275     pRevSurface->m_angle.Set(0.0,2.0*ON_PI);
00276     pRevSurface->m_t = pRevSurface->m_angle;
00277     pRevSurface->m_curve = circle_crv;
00278     pRevSurface->m_axis.from = plane.origin;
00279     pRevSurface->m_axis.to = plane.origin + plane.zaxis;
00280     pRevSurface->m_bTransposed = false;
00281     double r[2], h[2];
00282     h[0] = fabs(minor_radius);
00283     h[1] = -h[0];
00284     r[0] = fabs(major_radius) + h[0];
00285     r[1] = -r[0];
00286     int i, j, k, n=0;
00287     ON_3dPoint pt[8];
00288     for (i=0;i<2;i++)
00289     {
00290       for (j=0;j<2;j++)
00291       {
00292         for (k=0;k<2;k++)
00293         {
00294           pt[n++] = plane.PointAt( r[i], r[j], h[k] );
00295         }
00296       }
00297     }
00298     pRevSurface->m_bbox.Set( 3, 0, 8, 3, &pt[0].x );
00299   }
00300   return pRevSurface;
00301 }


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