geometry.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2009-2012, Willow Garage, Inc.
00006  *  Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho,
00007  *                      Johns Hopkins University
00008  *
00009  *  All rights reserved.
00010  *
00011  *  Redistribution and use in source and binary forms, with or without
00012  *  modification, are permitted provided that the following conditions
00013  *  are met:
00014  *
00015  *   * Redistributions of source code must retain the above copyright
00016  *     notice, this list of conditions and the following disclaimer.
00017  *   * Redistributions in binary form must reproduce the above
00018  *     copyright notice, this list of conditions and the following
00019  *     disclaimer in the documentation and/or other materials provided
00020  *     with the distribution.
00021  *   * Neither the name of Willow Garage, Inc. nor the names of its
00022  *     contributors may be used to endorse or promote products derived
00023  *     from this software without specific prior written permission.
00024  *
00025  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00026  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00027  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00028  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00029  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00030  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00031  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00032  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00033  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00034  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00035  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00036  *  POSSIBILITY OF SUCH DAMAGE.
00037  *
00038  * $Id: geometry.cpp 5036 2012-03-12 08:54:15Z rusu $
00039  *
00040  */
00041 
00042 #include <pcl/surface/poisson/geometry.h>
00043 
00044 
00045 namespace pcl {
00046   namespace poisson {
00047 
00049     // CoredMeshData //
00051 
00052     TriangulationEdge::TriangulationEdge(void){pIndex[0]=pIndex[1]=tIndex[0]=tIndex[1]=-1;}
00053     TriangulationTriangle::TriangulationTriangle(void){eIndex[0]=eIndex[1]=eIndex[2]=-1;}
00054 
00056     // CoredVectorMeshData //
00058     CoredVectorMeshData::CoredVectorMeshData (void) : oocPoints (), polygons (), polygonIndex (0), oocPointIndex (0) {}
00059 
00060     void CoredVectorMeshData::resetIterator ( void ) { oocPointIndex = polygonIndex = 0; }
00061     int CoredVectorMeshData::addOutOfCorePoint(const Point3D<float>& p){
00062       oocPoints.push_back(p);
00063       return int(oocPoints.size())-1;
00064     }
00065     int CoredVectorMeshData::addPolygon( const std::vector< CoredVertexIndex >& vertices )
00066     {
00067       std::vector< int > polygon( vertices.size() );
00068       for( unsigned i=0 ; i<vertices.size() ; i++ )
00069         if( vertices[i].inCore ) polygon[i] =  vertices[i].idx;
00070         else                     polygon[i] = -vertices[i].idx-1;
00071       polygons.push_back( polygon );
00072       return int( polygons.size() )-1;
00073     }
00074     int CoredVectorMeshData::nextOutOfCorePoint(Point3D<float>& p){
00075       if(oocPointIndex<int(oocPoints.size())){
00076         p=oocPoints[oocPointIndex++];
00077         return 1;
00078       }
00079       else{return 0;}
00080     }
00081     int CoredVectorMeshData::nextPolygon( std::vector< CoredVertexIndex >& vertices )
00082     {
00083       if( polygonIndex<int( polygons.size() ) )
00084       {
00085         std::vector< int >& polygon = polygons[ polygonIndex++ ];
00086         vertices.resize( polygon.size() );
00087         for( unsigned i=0 ; i<polygon.size() ; i++ )
00088           if( polygon[i]<0 ) vertices[i].idx = -polygon[i]-1 , vertices[i].inCore = false;
00089           else               vertices[i].idx =  polygon[i]   , vertices[i].inCore = true;
00090         return 1;
00091       }
00092       else return 0;
00093     }
00094     int CoredVectorMeshData::outOfCorePointCount(void){return int(oocPoints.size());}
00095     int CoredVectorMeshData::polygonCount( void ) { return int( polygons.size() ); }
00096 
00097 
00098   }
00099 }
00100 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:13