vector.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: vector.h 5531 2012-04-08 09:14:33Z aichim $
00039  *
00040  */
00041 
00042 #ifndef PCL_POISSON__VECTOR_H_
00043 #define PCL_POISSON__VECTOR_H_
00044 
00045 #define Assert assert
00046 #include <assert.h>
00047 
00048 namespace pcl {
00049   namespace poisson {
00050 
00051     template<class T>
00052     class Vector
00053     {
00054     public:
00055       Vector ();
00056       Vector (const Vector<T>& V);
00057       Vector (size_t N);
00058       Vector (size_t N, T* pV);
00059       ~Vector();
00060 
00061       const T& operator () (size_t i) const;
00062       T& operator () (size_t i);
00063       const T& operator [] (size_t i) const;
00064       T& operator [] (size_t i);
00065 
00066       void SetZero();
00067 
00068       size_t Dimensions() const;
00069       void Resize( size_t N );
00070 
00071       Vector operator * (const T& A) const;
00072       Vector operator / (const T& A) const;
00073       Vector operator - (const Vector& V) const;
00074       Vector operator + (const Vector& V) const;
00075 
00076       Vector& operator *= (const T& A);
00077       Vector& operator /= (const T& A);
00078       Vector& operator += (const Vector& V);
00079       Vector& operator -= (const Vector& V);
00080 
00081       Vector& AddScaled (const Vector& V,const T& scale);
00082       Vector& SubtractScaled (const Vector& V,const T& scale);
00083       static void Add (const Vector& V1,const T& scale1,const Vector& V2,const T& scale2,Vector& Out);
00084       static void Add (const Vector& V1,const T& scale1,const Vector& V2,Vector& Out);
00085 
00086       Vector operator - () const;
00087 
00088       Vector& operator = (const Vector& V);
00089 
00090       T Dot (const Vector& V) const;
00091 
00092       T Length() const;
00093 
00094       T Norm (size_t Ln) const;
00095       void Normalize();
00096 
00097       T* m_pV;
00098     protected:
00099       size_t m_N;
00100 
00101     };
00102 
00103     template<class T,int Dim>
00104     class NVector
00105     {
00106     public:
00107       NVector ();
00108       NVector (const NVector& V);
00109       NVector (size_t N);
00110       NVector (size_t N, T* pV);
00111       ~NVector ();
00112 
00113       const T* operator () (size_t i) const;
00114       T* operator () (size_t i);
00115       const T* operator [] (size_t i) const;
00116       T* operator [] (size_t i);
00117 
00118       void SetZero();
00119 
00120       size_t Dimensions() const;
00121       void Resize( size_t N );
00122 
00123       NVector operator * (const T& A) const;
00124       NVector operator / (const T& A) const;
00125       NVector operator - (const NVector& V) const;
00126       NVector operator + (const NVector& V) const;
00127 
00128       NVector& operator *= (const T& A);
00129       NVector& operator /= (const T& A);
00130       NVector& operator += (const NVector& V);
00131       NVector& operator -= (const NVector& V);
00132 
00133       NVector& AddScaled (const NVector& V,const T& scale);
00134       NVector& SubtractScaled (const NVector& V,const T& scale);
00135       static void Add (const NVector& V1,const T& scale1,const NVector& V2,const T& scale2,NVector& Out);
00136       static void Add (const NVector& V1,const T& scale1,const NVector& V2, NVector& Out);
00137 
00138       NVector operator - () const;
00139 
00140       NVector& operator = (const NVector& V);
00141 
00142       T Dot (const NVector& V) const;
00143 
00144       T Length () const;
00145 
00146       T Norm (size_t Ln) const;
00147       void Normalize ();
00148 
00149       T* m_pV;
00150     protected:
00151       size_t m_N;
00152 
00153     };
00154 
00155   }
00156 }
00157 
00158 
00159 #include <pcl/surface/impl/poisson/vector.hpp>
00160 
00161 
00162 
00163 #endif /* PCL_POISSON__VECTOR_H_ */


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:18:55