00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00015
00016
00017 #include "pcl/surface/3rdparty/opennurbs/opennurbs.h"
00018
00019 ON_Sphere::ON_Sphere() : radius(0.0)
00020 {}
00021
00022 ON_Sphere::ON_Sphere( const ON_3dPoint& center, double r)
00023 {
00024 Create(center,r);
00025 }
00026
00027 ON_Sphere::~ON_Sphere()
00028 {}
00029
00030 bool ON_Sphere::IsValid() const
00031 {
00032 return ( ON_IsValid(radius) && radius > 0.0 && plane.IsValid() ) ? true : false;
00033 }
00034
00035 bool ON_Sphere::Create( const ON_3dPoint& center, double r )
00036 {
00037 plane = ON_xy_plane;
00038 plane.origin = center;
00039 plane.UpdateEquation();
00040 radius = r;
00041 return (r > 0.0) ? true : false;
00042 }
00043
00044 ON_3dPoint ON_Sphere::PointAt(double longitude, double latitude) const
00045 {
00046 return radius*NormalAt(longitude,latitude) + plane.origin;
00047 }
00048
00049 ON_3dVector ON_Sphere::NormalAt(double longitude, double latitude) const
00050 {
00051 return cos(latitude)*(cos(longitude)*plane.xaxis + sin(longitude)*plane.yaxis) + sin(latitude)*plane.zaxis;
00052 }
00053
00054 ON_Circle ON_Sphere::LatitudeRadians(double a) const
00055 {
00056 return ON_Circle(PointAt(0.0,a),PointAt(0.5*ON_PI,a),PointAt(ON_PI,a));
00057 }
00058
00059 ON_Circle ON_Sphere::LatitudeDegrees(double a) const
00060 {
00061 return LatitudeRadians(a*ON_PI/180.0);
00062 }
00063
00064 ON_Circle ON_Sphere::LongitudeRadians(double a) const
00065 {
00066 return ON_Circle(PointAt(a,0.0),NorthPole(),PointAt(a+ON_PI,0.0));
00067 }
00068
00069 ON_Circle ON_Sphere::LongitudeDegrees(double a) const
00070 {
00071 return LongitudeRadians(a*ON_PI/180.0);
00072 }
00073
00074 ON_3dPoint ON_Sphere::Center() const
00075 {
00076 return plane.origin;
00077 }
00078
00079 ON_3dPoint ON_Sphere::NorthPole() const
00080 {
00081 return PointAt(0.0, 0.5*ON_PI);
00082 }
00083
00084 ON_3dPoint ON_Sphere::SouthPole() const
00085 {
00086 return PointAt(0.0, -0.5*ON_PI);
00087 }
00088
00089 double ON_Sphere::Radius() const
00090 {
00091 return radius;
00092 }
00093
00094 double ON_Sphere::Diameter() const
00095 {
00096 return 2.0*radius;
00097 }
00098
00099 bool ON_Sphere::ClosestPointTo(
00100 ON_3dPoint point,
00101 double* longitude,
00102 double* latitude
00103 ) const
00104 {
00105 bool rc = true;
00106 ON_3dVector v = point - plane.origin;
00107 double h = v*plane.zaxis;
00108 double x = v*plane.xaxis;
00109 double y = v*plane.yaxis;
00110 double r = 1.0;
00111 if ( x == 0.0 && y == 0.0 ) {
00112 if ( longitude )
00113 *longitude = 0.0;
00114 if ( latitude )
00115 *latitude = (h>=0.0) ? 0.5*ON_PI : -0.5*ON_PI;
00116 if ( h == 0.0 )
00117 rc = false;
00118 }
00119 else {
00120 if ( fabs(x) >= fabs(y) ) {
00121 r = y/x;
00122 r = fabs(x)*sqrt(1.0+r*r);
00123 }
00124 else {
00125 r = x/y;
00126 r = fabs(y)*sqrt(1.0+r*r);
00127 }
00128 if ( longitude ) {
00129 *longitude = atan2(y,x);
00130 if ( *longitude < 0.0 )
00131 *longitude += 2.0*ON_PI;
00132 if ( *longitude < 0.0 || *longitude >= 2.0*ON_PI)
00133 *longitude = 0.0;
00134 }
00135 if ( latitude )
00136 *latitude = atan(h/r);
00137 }
00138 return rc;
00139 }
00140
00141 ON_BoundingBox ON_Sphere::BoundingBox() const
00142 {
00143 ON_BoundingBox bbox;
00144 double r = Radius();
00145 bbox.m_min = Center();
00146 bbox.m_max = bbox.m_min;
00147 bbox.m_min.x -= r;
00148 bbox.m_min.y -= r;
00149 bbox.m_min.z -= r;
00150 bbox.m_max.x += r;
00151 bbox.m_max.y += r;
00152 bbox.m_max.z += r;
00153 return bbox;
00154 }
00155
00156
00157 ON_3dPoint ON_Sphere::ClosestPointTo( ON_3dPoint point ) const
00158 {
00159 ON_3dVector v = point - plane.origin;
00160 v.Unitize();
00161 return plane.origin + radius*v;
00162 }
00163
00164
00165
00166 bool ON_Sphere::Rotate(
00167 double sin_angle,
00168 double cos_angle,
00169 const ON_3dVector& axis
00170 )
00171 {
00172 return Rotate(sin_angle, cos_angle, axis, plane.origin );
00173 }
00174
00175 bool ON_Sphere::Rotate(
00176 double angle,
00177 const ON_3dVector& axis
00178 )
00179 {
00180 return Rotate(sin(angle), cos(angle), axis, plane.origin );
00181 }
00182
00183
00184 bool ON_Sphere::Rotate(
00185 double sin_angle,
00186 double cos_angle,
00187 const ON_3dVector& axis,
00188 const ON_3dPoint& point
00189 )
00190 {
00191 return plane.Rotate( sin_angle, cos_angle, axis, point );
00192 }
00193
00194 bool ON_Sphere::Rotate(
00195 double angle,
00196 const ON_3dVector& axis,
00197 const ON_3dPoint& point
00198 )
00199 {
00200 return Rotate(sin(angle),cos(angle),axis,point);
00201 }
00202
00203 bool ON_Sphere::Translate(
00204 const ON_3dVector& delta
00205 )
00206 {
00207 return plane.Translate(delta);
00208 }
00209
00210
00211 bool ON_Sphere::Transform( const ON_Xform& xform )
00212 {
00213 ON_Circle xc(plane,radius);
00214 bool rc = xc.Transform(xform);
00215 if (rc)
00216 {
00217 plane = xc.plane;
00218 radius = xc.radius;
00219 }
00220 return rc;
00221 }
00222
00223 int ON_Sphere::GetNurbForm( ON_NurbsSurface& s ) const
00224 {
00225 int rc = 0;
00226 if ( IsValid() ) {
00227 s.Create(3,true,3,3,9,5);
00228 s.m_knot[0][0] = s.m_knot[0][1] = 0.0;
00229 s.m_knot[0][2] = s.m_knot[0][3] = 0.5*ON_PI;
00230 s.m_knot[0][4] = s.m_knot[0][5] = ON_PI;
00231 s.m_knot[0][6] = s.m_knot[0][7] = 1.5*ON_PI;
00232 s.m_knot[0][8] = s.m_knot[0][9] = 2.0*ON_PI;
00233
00234 s.m_knot[1][0] = s.m_knot[1][1] = -0.5*ON_PI;
00235 s.m_knot[1][2] = s.m_knot[1][3] = 0.0;
00236 s.m_knot[1][4] = s.m_knot[1][5] = 0.5*ON_PI;
00237
00238 ON_4dPoint* CV = (ON_4dPoint*)s.m_cv;
00239 const ON_3dVector x = radius*plane.xaxis;
00240 const ON_3dVector y = radius*plane.yaxis;
00241 const ON_3dVector z = radius*plane.zaxis;
00242
00243 ON_3dPoint p[9] = {plane.origin+x,
00244 plane.origin+x+y,
00245 plane.origin+y,
00246 plane.origin-x+y,
00247 plane.origin-x,
00248 plane.origin-x-y,
00249 plane.origin-y,
00250 plane.origin+x-y,
00251 plane.origin+x};
00252
00253 const double w = 1.0/sqrt(2.0);
00254 double w13;
00255 int i;
00256 ON_4dPoint southpole = plane.origin - z;
00257 ON_4dPoint northpole = plane.origin + z;
00258 for ( i = 0; i < 8; i++ ) {
00259 CV[5*i ] = southpole;
00260 CV[5*i+1] = p[i] - z;
00261 CV[5*i+2] = p[i];
00262 CV[5*i+3] = p[i] + z;
00263 CV[5*i+4] = northpole;
00264
00265 if ( i%2) {
00266 CV[5*i ].x *= w;
00267 CV[5*i ].y *= w;
00268 CV[5*i ].z *= w;
00269 CV[5*i ].w = w;
00270 CV[5*i+2].x *= w;
00271 CV[5*i+2].y *= w;
00272 CV[5*i+2].z *= w;
00273 CV[5*i+2].w = w;
00274 CV[5*i+4].x *= w;
00275 CV[5*i+4].y *= w;
00276 CV[5*i+4].z *= w;
00277 CV[5*i+4].w = w;
00278 w13 = 0.5;
00279 }
00280 else {
00281 w13 = w;
00282 }
00283 CV[5*i+1].x *= w13;
00284 CV[5*i+1].y *= w13;
00285 CV[5*i+1].z *= w13;
00286 CV[5*i+1].w = w13;
00287
00288 CV[5*i+3].x *= w13;
00289 CV[5*i+3].y *= w13;
00290 CV[5*i+3].z *= w13;
00291 CV[5*i+3].w = w13;
00292 }
00293 CV[40] = CV[0];
00294 CV[41] = CV[1];
00295 CV[42] = CV[2];
00296 CV[43] = CV[3];
00297 CV[44] = CV[4];
00298 rc = 2;
00299 }
00300 return rc;
00301 }
00302
00303 ON_RevSurface* ON_Sphere::RevSurfaceForm( ON_RevSurface* srf ) const
00304 {
00305 return RevSurfaceForm(false,srf);
00306 }
00307
00308 ON_RevSurface* ON_Sphere::RevSurfaceForm(
00309 bool bArcLengthParameterization,
00310 ON_RevSurface* srf
00311 ) const
00312 {
00313 if ( srf )
00314 srf->Destroy();
00315 ON_RevSurface* pRevSurface = NULL;
00316 if ( IsValid() )
00317 {
00318 ON_Arc arc;
00319 arc.plane.origin = plane.origin;
00320 arc.plane.xaxis = -plane.zaxis;
00321 arc.plane.yaxis = plane.xaxis;
00322 arc.plane.zaxis = -plane.yaxis;
00323 arc.plane.UpdateEquation();
00324 arc.radius = radius;
00325 arc.SetAngleRadians(ON_PI);
00326 ON_ArcCurve* arc_curve = new ON_ArcCurve( arc, -0.5*ON_PI, 0.5*ON_PI );
00327 if ( srf )
00328 pRevSurface = srf;
00329 else
00330 pRevSurface = new ON_RevSurface();
00331 pRevSurface->m_angle.Set(0.0,2.0*ON_PI);
00332 pRevSurface->m_t = pRevSurface->m_angle;
00333 pRevSurface->m_curve = arc_curve;
00334 pRevSurface->m_axis.from = plane.origin;
00335 pRevSurface->m_axis.to = plane.origin + plane.zaxis;
00336 pRevSurface->m_bTransposed = false;
00337 pRevSurface->m_bbox.m_min = plane.origin;
00338 pRevSurface->m_bbox.m_min.x -= radius;
00339 pRevSurface->m_bbox.m_min.y -= radius;
00340 pRevSurface->m_bbox.m_min.z -= radius;
00341 pRevSurface->m_bbox.m_max = plane.origin;
00342 pRevSurface->m_bbox.m_max.x += radius;
00343 pRevSurface->m_bbox.m_max.y += radius;
00344 pRevSurface->m_bbox.m_max.z += radius;
00345 if ( bArcLengthParameterization )
00346 {
00347 double r = fabs(radius);
00348 if ( !(r > ON_SQRT_EPSILON) )
00349 r = 1.0;
00350 r *= ON_PI;
00351 pRevSurface->SetDomain(0,0.0,2.0*r);
00352 pRevSurface->SetDomain(1,-0.5*r,0.5*r);
00353 }
00354 }
00355 return pRevSurface;
00356 }
00357
00358