binary_node.h
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: binary_node.h 5922 2012-06-13 19:46:55Z nburrus $
00039  *
00040  */
00041 
00042 #ifndef PCL_POISSON_BINARY_NODE_H_
00043 #define PCL_POISSON_BINARY_NODE_H_
00044 
00045 namespace pcl {
00046   namespace poisson {
00047 
00048     template<class Real>
00049     class BinaryNode
00050     {
00051     public:
00052       static inline int CenterCount (int depth){return 1<<depth;}
00053       static inline int CumulativeCenterCount (int maxDepth){return  (1<< (maxDepth+1))-1;}
00054       static inline int Index (int depth,  int offSet){return  (1<<depth)+offSet-1;}
00055       static inline int CornerIndex (int maxDepth, int depth, int offSet, int forwardCorner)
00056       {return  (offSet+forwardCorner)<< (maxDepth-depth);}
00057       static inline Real CornerIndexPosition (int index, int maxDepth)
00058       {return Real (index)/ (1<<maxDepth);}
00059       static inline Real Width (int depth)
00060       {return Real (1.0/ (1<<depth));}      
00061 
00062       // Fix for Bug #717 with Visual Studio that generates wrong code for this function
00063       // when global optimization is enabled (release mode).
00064 #ifdef _MSC_VER
00065       static __declspec(noinline) void CenterAndWidth (int depth, int offset, Real& center, Real& width)
00066 #else
00067       static inline void CenterAndWidth (int depth, int offset, Real& center, Real& width)
00068 #endif
00069       {
00070         width=Real (1.0/ (1<<depth));
00071         center=Real ( (0.5+offset)*width);
00072       }
00073 
00074 #ifdef _MSC_VER
00075       static __declspec(noinline) void CenterAndWidth (int idx, Real& center, Real& width)
00076 #else
00077       static inline void CenterAndWidth (int idx, Real& center, Real& width)
00078 #endif
00079       {
00080         int depth, offset;
00081         DepthAndOffset (idx, depth, offset);
00082         CenterAndWidth (depth, offset, center, width);
00083       }
00084       static inline void DepthAndOffset (int idx,  int& depth, int& offset)
00085       {
00086         int i = idx+1;
00087         depth = -1;
00088         while (i)
00089         {
00090           i>>=1;
00091           depth++;
00092         }
00093         offset= (idx+1)- (1<<depth);
00094       }
00095     };
00096 
00097 
00098   }
00099 }
00100 
00101 #endif /* PCL_POISSON_BINARY_NODE_H_ */


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:14:40