opennurbs_pointcloud.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_PointCloud, ON_Geometry, "2488F347-F8FA-11d3-BFEC-0010830122F0");
00020 
00021 
00022 ON_3dPoint& ON_PointCloud::operator[](int i)
00023 {
00024   return m_P[i];
00025 }
00026 
00027 const ON_3dPoint& ON_PointCloud::operator[](int i) const
00028 {
00029   return m_P[i];
00030 }
00031 
00032 ON_3dPoint ON_PointCloud::Point( ON_COMPONENT_INDEX ci ) const
00033 {
00034   return (ON_COMPONENT_INDEX::pointcloud_point == ci.m_type && ci.m_index >= 0 && ci.m_index < m_P.Count() )
00035     ? m_P[ci.m_index]
00036     : ON_UNSET_POINT;
00037 }
00038 
00039 ON_PointCloud::ON_PointCloud() : m_flags(0)
00040 {
00041   m_hidden_count=0;
00042 }
00043 
00044 ON_PointCloud::ON_PointCloud( int capacity ) : m_P(capacity), m_flags(0)
00045 {
00046   m_hidden_count=0;
00047 }
00048 
00049 ON_PointCloud::ON_PointCloud( const ON_PointCloud& src )
00050 {
00051   *this = src;
00052 }
00053 
00054 ON_PointCloud& ON_PointCloud::operator=( const ON_PointCloud& src )
00055 {
00056   if ( this != &src ) {
00057     Destroy();
00058     ON_Geometry::operator=(src);
00059     m_P = src.m_P;
00060     m_H = src.m_H;
00061     m_C = src.m_C;
00062     m_N = src.m_N;
00063     m_hidden_count = src.m_hidden_count;
00064 
00065     m_plane = src.m_plane;
00066     m_bbox = src.m_bbox;
00067     m_flags = src.m_flags;
00068   }
00069   return *this;
00070 }
00071 
00072 ON_PointCloud::~ON_PointCloud()
00073 {
00074   Destroy();
00075 }
00076 
00077 void ON_PointCloud::Destroy()
00078 {
00079   m_H.Destroy();
00080   m_C.Destroy();
00081   m_N.Destroy();
00082   m_P.Destroy();
00083   m_hidden_count=0;
00084   m_flags = 0;
00085   m_bbox.Destroy();
00086 }
00087 
00088 void ON_PointCloud::EmergencyDestroy()
00089 {
00090   m_P.EmergencyDestroy();
00091   m_C.EmergencyDestroy();
00092   m_H.EmergencyDestroy();
00093   m_N.EmergencyDestroy();
00094   m_hidden_count=0;
00095   m_flags = 0;
00096   m_bbox.Destroy();
00097 }
00098 
00099 ON_BOOL32 ON_PointCloud::IsValid( ON_TextLog* text_log ) const
00100 {
00101   return ( m_P.Count() > 0 ) ? true : false;
00102 }
00103 
00104 void ON_PointCloud::Dump( ON_TextLog& dump ) const
00105 {
00106   int i;
00107   const bool bHasNormals = HasPointNormals();
00108   const bool bHasHiddenPoints = (HiddenPointCount() > 0);
00109   const int point_count = m_P.Count();
00110   dump.Print("ON_PointCloud: %d points\n",point_count);
00111   dump.PushIndent();
00112   for ( i = 0; i < point_count; i++ ) {
00113     dump.Print("point[%2d]: ",i);
00114     dump.Print( m_P[i] );
00115     if ( bHasNormals )
00116     {
00117       dump.Print(", normal = ");
00118       dump.Print(m_N[i]);
00119     }
00120     if ( bHasHiddenPoints && m_H[i])
00121     {
00122       dump.Print(" (hidden)");
00123     }
00124     dump.Print("\n");
00125   }
00126   dump.PopIndent();
00127 }
00128 
00129 ON_BOOL32 ON_PointCloud::Write( ON_BinaryArchive& file ) const
00130 {
00131   bool rc = file.Write3dmChunkVersion(1,1);
00132 
00133   if (rc) rc = file.WriteArray( m_P );
00134   if (rc) rc = file.WritePlane( m_plane );
00135   if (rc) rc = file.WriteBoundingBox( m_bbox );
00136   if (rc) rc = file.WriteInt( m_flags);
00137 
00138   // added for 1.1  (7 December 2005)
00139   if (rc) rc = file.WriteArray(m_N);
00140   if (rc) rc = file.WriteArray(m_C);
00141 
00142   return rc;
00143 }
00144 
00145 ON_BOOL32 ON_PointCloud::Read( ON_BinaryArchive& file )
00146 {
00147   int major_version = 0;
00148   int minor_version = 0;
00149   bool rc = file.Read3dmChunkVersion(&major_version,&minor_version);
00150   if (rc && major_version == 1 ) 
00151   {
00152     if (rc) rc = file.ReadArray( m_P );
00153     if (rc) rc = file.ReadPlane( m_plane );
00154     if (rc) rc = file.ReadBoundingBox( m_bbox );
00155     if (rc) rc = file.ReadInt( &m_flags);
00156 
00157     if (rc && minor_version >= 1 )
00158     {
00159       if (rc) rc = file.ReadArray( m_N );
00160       if (rc) rc = file.ReadArray( m_C );
00161     }
00162   }
00163   return rc;
00164 }
00165 
00166 ON::object_type ON_PointCloud::ObjectType() const
00167 {
00168   return ON::pointset_object;
00169 }
00170 
00171 
00172 int ON_PointCloud::Dimension() const
00173 {
00174   return 3;
00175 }
00176 
00177 ON_BOOL32 ON_PointCloud::GetBBox( // returns true if successful
00178        double* boxmin,    // minimum
00179        double* boxmax,    // maximum
00180        ON_BOOL32 bGrowBox  // true means grow box
00181        ) const
00182 {
00183   if ( !m_bbox.IsValid() ) {
00184     m_P.GetBBox( (double*)&m_bbox.m_min.x, (double*)&m_bbox.m_max.x, false );
00185   }
00186   ON_BOOL32 rc = m_bbox.IsValid();
00187   if (rc) {
00188     if ( bGrowBox ) {
00189       if ( boxmin ) {
00190         if ( boxmin[0] > m_bbox.m_min.x ) boxmin[0] = m_bbox.m_min.x;
00191         if ( boxmin[1] > m_bbox.m_min.y ) boxmin[1] = m_bbox.m_min.y;
00192         if ( boxmin[2] > m_bbox.m_min.z ) boxmin[2] = m_bbox.m_min.z;
00193       }
00194       if ( boxmax ) {
00195         if ( boxmax[0] < m_bbox.m_max.x ) boxmax[0] = m_bbox.m_max.x;
00196         if ( boxmax[1] < m_bbox.m_max.y ) boxmax[1] = m_bbox.m_max.y;
00197         if ( boxmax[2] < m_bbox.m_max.z ) boxmax[2] = m_bbox.m_max.z;
00198       }
00199     }
00200     else {
00201       if ( boxmin ) {
00202         boxmin[0] = m_bbox.m_min.x;
00203         boxmin[1] = m_bbox.m_min.y;
00204         boxmin[2] = m_bbox.m_min.z;
00205       }
00206       if ( boxmax ) {
00207         boxmax[0] = m_bbox.m_max.x;
00208         boxmax[1] = m_bbox.m_max.y;
00209         boxmax[2] = m_bbox.m_max.z;
00210       }
00211     }
00212   }
00213   return rc;
00214 }
00215 
00216 ON_BOOL32 ON_PointCloud::Transform( 
00217        const ON_Xform& xform
00218        )
00219 {
00220   TransformUserData(xform);
00221   ON_BOOL32 rc = m_P.Transform(xform);
00222   if (rc && HasPlane() )
00223     rc = m_plane.Transform(xform);
00224   m_bbox.Destroy();
00225   return rc;
00226 }
00227 
00228 bool ON_PointCloud::IsDeformable() const
00229 {
00230   return true;
00231 }
00232 
00233 bool ON_PointCloud::MakeDeformable()
00234 {
00235   return true;
00236 }
00237 
00238 ON_BOOL32 ON_PointCloud::SwapCoordinates(
00239       int i, int j        // indices of coords to swap
00240       )
00241 {
00242   ON_BOOL32 rc = m_P.SwapCoordinates(i,j);
00243   if ( rc && HasPlane() ) {
00244     rc = m_plane.SwapCoordinates(i,j);
00245   }
00246   if ( rc && m_bbox.IsValid() ) {
00247     rc = m_bbox.SwapCoordinates(i,j);
00248   }
00249   return rc;
00250 }
00251 
00252 int ON_PointCloud::PointCount() const
00253 {
00254   return m_P.Count();
00255 }
00256 
00257 void ON_PointCloud::AppendPoint( const ON_3dPoint& pt )
00258 {
00259   m_P.Append(pt);
00260 }
00261 
00262 void ON_PointCloud::InvalidateBoundingBox()
00263 {
00264   m_bbox.Destroy();
00265 }
00266 
00267 void ON_PointCloud::SetOrdered(bool b)
00268 {
00269   if ( b ) {
00270     m_flags |= 1;
00271   }
00272   else {
00273     m_flags &= 0xFFFFFFFE;
00274   }
00275 }
00276 
00277 bool ON_PointCloud::IsOrdered() const
00278 {
00279   return (m_flags & 1) ? true : false;
00280 }
00281 
00282 bool ON_PointCloud::HasPlane() const
00283 {
00284   return ( m_flags&2) ? true : false;
00285 }
00286 
00287 void ON_PointCloud::SetPlane( const ON_Plane& plane )
00288 {
00289   m_plane = plane;
00290   if ( m_plane.IsValid() ) {
00291     m_flags |= 2;
00292   }
00293   else {
00294     m_flags &= 0xFFFFFFFD;
00295   }
00296 }
00297 
00298 const ON_Plane& ON_PointCloud::Plane()
00299 {
00300   return m_plane;
00301 }
00302 
00303 
00304 
00305 
00306 
00307 double ON_PointCloud::Height(int i)
00308 {
00309   return (m_P[i] - m_plane.origin)*m_plane.zaxis;
00310 }
00311 
00312 bool ON_GetClosestPointInPointList( 
00313           int point_count,
00314           const ON_3dPoint* point_list,
00315           ON_3dPoint P,
00316           int* closest_point_index
00317           )
00318 {
00319   bool rc = false;
00320   if ( point_count>0 && 0 != point_list && closest_point_index )
00321   {
00322     double d = 1.0e300;
00323     double d2 = 1.0e300;
00324     double x,e;
00325     int i;
00326     int best_i = -1;
00327     //const double* pl = &point_list[0].x;
00328     for ( i = point_count; i--; point_list++ )
00329     {
00330       e = d2;
00331       x = point_list->x - P.x;
00332       e = x*x;
00333       if ( e >= d2 ) continue;
00334       x = point_list->y - P.y;
00335       e += x*x;
00336       if ( e >= d2 ) continue;
00337       x = point_list->z - P.z;
00338       e += x*x;
00339       if ( e >= d2 ) continue;
00340       d2 = (1.0+ON_SQRT_EPSILON)*e;
00341       e = P.DistanceTo(*point_list);
00342       if ( e < d )
00343       {
00344         d = e;
00345         best_i = point_count-i-1;
00346       }
00347     }
00348     if ( best_i >= 0 )
00349     {
00350       if ( closest_point_index )
00351         *closest_point_index = best_i;
00352       rc = true;
00353     }
00354   }
00355   return rc;
00356 }
00357 
00358 bool ON_3dPointArray::GetClosestPoint( 
00359           ON_3dPoint P,
00360           int* closest_point_index,
00361           double maximum_distance
00362           ) const
00363 {
00364   int i;
00365 
00366   bool rc = ON_GetClosestPointInPointList( m_count, m_a , P, &i );
00367 
00368   if (rc)
00369   {
00370     if ( maximum_distance > 0.0 && P.DistanceTo(m_a[i]) > maximum_distance )
00371     {
00372       rc = false;
00373     }
00374     else if ( closest_point_index )
00375     {
00376       *closest_point_index = i;
00377     }
00378   }
00379 
00380   return rc;
00381 }
00382 
00383 bool ON_PointCloud::HasPointColors() const
00384 {
00385   const int point_count = m_P.Count();
00386   return (point_count > 0 && point_count == m_C.Count());
00387 }
00388 
00389 bool ON_PointCloud::HasPointNormals() const
00390 {
00391   const int point_count = m_P.Count();
00392   return (point_count > 0 && point_count == m_N.Count());
00393 }
00394 
00395 bool ON_PointCloud::GetClosestPoint(
00396                 ON_3dPoint P,
00397                 int* closest_point_index,
00398                 double maximum_distance 
00399                 ) const
00400 {
00401   if ( maximum_distance > 0.0 && m_bbox.IsValid() )
00402   {
00403     // check bounding box
00404     if ( m_bbox.MinimumDistanceTo(P) > maximum_distance )
00405       return false;
00406   }
00407   return m_P.GetClosestPoint( P, closest_point_index, maximum_distance );
00408 }
00409 
00410 int ON_PointCloud::HiddenPointCount() const
00411 {
00412   int point_count;
00413   return (    m_hidden_count > 0 
00414            && (point_count = m_P.Count()) > 0
00415            && m_hidden_count < point_count 
00416            && m_H.Count() == point_count 
00417            )
00418            ? m_hidden_count
00419            : 0;
00420 }
00421 
00422 void ON_PointCloud::DestroyHiddenPointArray()
00423 {
00424   m_hidden_count = 0;
00425   m_H.Destroy();
00426 }
00427 
00428 const bool* ON_PointCloud::HiddenPointArray() const
00429 {
00430   return (m_hidden_count > 0 && m_H.Count() == m_P.Count()) 
00431          ? m_H.Array() 
00432          : 0;
00433 }
00434 
00435 void ON_PointCloud::SetHiddenPointFlag( int point_index, bool bHidden )
00436 {
00437   const int point_count = m_P.Count();
00438   if ( point_index >= 0 && point_index < point_count )
00439   {
00440     if ( bHidden )
00441     {
00442       if ( point_count != m_H.Count() )
00443       {
00444         m_H.SetCapacity(point_count);
00445         m_H.SetCount(point_count);
00446         m_H.Zero();
00447         m_H[point_index] = true;
00448         m_hidden_count = 1;
00449       }
00450       else if ( false == m_H[point_index] )
00451       {
00452         m_H[point_index] = true;
00453         m_hidden_count++;
00454       }
00455     }
00456     else
00457     {
00458       // show this vertex
00459       if ( m_hidden_count > 0 && point_count == m_H.Count() )
00460       {
00461         if  ( m_H[point_index] )
00462         {
00463           m_H[point_index] = false;
00464           m_hidden_count--;
00465           if ( 0 == m_hidden_count )
00466           {
00467             DestroyHiddenPointArray();
00468           }
00469         }
00470       }
00471       else if ( m_hidden_count > 0 || m_H.Capacity() > 0 )
00472       {
00473         // if m_H exists, it is bogus.
00474         DestroyHiddenPointArray();
00475       }
00476     }
00477   }
00478 }
00479 
00480 bool ON_PointCloud::PointIsHidden( int point_index ) const
00481 {
00482   int point_count;
00483   return (    point_index >= 0
00484            && point_index < (point_count = m_P.Count())
00485            && m_H.Count() == point_count )
00486            ? m_H[point_index]
00487            : false;
00488 }
00489 


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