sparse_matrix.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without modification,
00006 are permitted provided that the following conditions are met:
00007 
00008 Redistributions of source code must retain the above copyright notice, this list of
00009 conditions and the following disclaimer. Redistributions in binary form must reproduce
00010 the above copyright notice, this list of conditions and the following disclaimer
00011 in the documentation and/or other materials provided with the distribution. 
00012 
00013 Neither the name of the Johns Hopkins University nor the names of its contributors
00014 may be used to endorse or promote products derived from this software without specific
00015 prior written permission. 
00016 
00017 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY
00018 EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES 
00019 OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT
00020 SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00021 INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
00022 TO, PROCUREMENT OF SUBSTITUTE  GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
00023 BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00024 CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00025 ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
00026 DAMAGE.
00027 */
00028 
00029 #ifndef __SPARSEMATRIX_HPP
00030 #define __SPARSEMATRIX_HPP
00031 
00032 #if defined __GNUC__
00033 #  pragma GCC system_header
00034 #endif
00035 
00036 #include "vector.h"
00037 #include "allocator.h"
00038 
00039 namespace pcl
00040 {
00041   namespace poisson
00042   {
00043 
00044     template <class T>
00045     struct MatrixEntry
00046     {
00047         MatrixEntry( void )             { N =-1; Value = 0; }
00048         MatrixEntry( int i )    { N = i; Value = 0; }
00049         int N;
00050         T Value;
00051     };
00052 
00053     template<class T> class SparseMatrix
00054     {
00055       private:
00056         bool _contiguous;
00057         int _maxEntriesPerRow;
00058         static int UseAlloc;
00059       public:
00060         static Allocator<MatrixEntry<T> > internalAllocator;
00061         static int UseAllocator(void);
00062         static void SetAllocator( int blockSize );
00063 
00064         int rows;
00065         int* rowSizes;
00066         MatrixEntry<T>** m_ppElements;
00067         MatrixEntry< T >* operator[] ( int idx ) { return m_ppElements[idx]; }
00068         const MatrixEntry< T >* operator[] ( int idx ) const { return m_ppElements[idx]; }
00069 
00070         SparseMatrix( void );
00071         SparseMatrix( int rows );
00072         SparseMatrix( int rows , int maxEntriesPerRow );
00073         void Resize( int rows );
00074         void Resize( int rows , int maxEntriesPerRow );
00075         void SetRowSize( int row , int count );
00076         int Entries( void ) const;
00077 
00078         SparseMatrix( const SparseMatrix& M );
00079         ~SparseMatrix();
00080 
00081         void SetZero();
00082         void SetIdentity();
00083 
00084         SparseMatrix<T>& operator = (const SparseMatrix<T>& M);
00085 
00086         SparseMatrix<T> operator * (const T& V) const;
00087         SparseMatrix<T>& operator *= (const T& V);
00088 
00089 
00090         SparseMatrix<T> operator * (const SparseMatrix<T>& M) const;
00091         SparseMatrix<T> Multiply( const SparseMatrix<T>& M ) const;
00092         SparseMatrix<T> MultiplyTranspose( const SparseMatrix<T>& Mt ) const;
00093 
00094         template<class T2>
00095         Vector<T2> operator * (const Vector<T2>& V) const;
00096         template<class T2>
00097         Vector<T2> Multiply( const Vector<T2>& V ) const;
00098         template<class T2>
00099         void Multiply( const Vector<T2>& In , Vector<T2>& Out , int threads=1 ) const;
00100 
00101 
00102         SparseMatrix<T> Transpose() const;
00103 
00104         static int Solve                        (const SparseMatrix<T>& M,const Vector<T>& b, int iters,Vector<T>& solution,const T eps=1e-8);
00105 
00106         template<class T2>
00107         static int SolveSymmetric( const SparseMatrix<T>& M , const Vector<T2>& b , int iters , Vector<T2>& solution , const T2 eps=1e-8 , int reset=1 , int threads=1 );
00108 
00109         bool write( FILE* fp ) const;
00110         bool write( const char* fileName ) const;
00111         bool read( FILE* fp );
00112         bool read( const char* fileName );
00113     };
00114 
00115     template< class T2 >
00116     struct MapReduceVector
00117     {
00118       private:
00119         int _dim;
00120       public:
00121         std::vector< T2* > out;
00122         MapReduceVector( void ) { _dim = 0; }
00123         ~MapReduceVector( void )
00124         {
00125           if( _dim ) for( int t=0 ; t<int(out.size()) ; t++ ) delete[] out[t];
00126           out.resize( 0 );
00127         }
00128         T2* operator[]( int t ) { return out[t]; }
00129         const T2* operator[]( int t ) const { return out[t]; }
00130         int threads( void ) const { return int( out.size() ); }
00131         void resize( int threads , int dim )
00132         {
00133           if( threads!=out.size() || _dim<dim )
00134           {
00135             for( int t=0 ; t<int(out.size()) ; t++ ) delete[] out[t];
00136             out.resize( threads );
00137             for( int t=0 ; t<int(out.size()) ; t++ ) out[t] = new T2[dim];
00138             _dim = dim;
00139           }
00140         }
00141 
00142     };
00143 
00144     template< class T >
00145     class SparseSymmetricMatrix : public SparseMatrix< T >
00146     {
00147       public:
00148 
00149         template< class T2 >
00150         Vector< T2 > operator * ( const Vector<T2>& V ) const;
00151 
00152         template< class T2 >
00153         Vector< T2 > Multiply( const Vector<T2>& V ) const;
00154 
00155         template< class T2 >
00156         void Multiply( const Vector<T2>& In, Vector<T2>& Out , bool addDCTerm=false ) const;
00157 
00158         template< class T2 >
00159         void Multiply( const Vector<T2>& In, Vector<T2>& Out , MapReduceVector< T2 >& OutScratch , bool addDCTerm=false ) const;
00160 
00161         template< class T2 >
00162         void Multiply( const Vector<T2>& In, Vector<T2>& Out , std::vector< T2* >& OutScratch , const std::vector< int >& bounds ) const;
00163 
00164         template< class T2 >
00165         static int Solve( const SparseSymmetricMatrix<T>& M , const Vector<T2>& b , int iters , Vector<T2>& solution , T2 eps=1e-8 , int reset=1 , int threads=0  , bool addDCTerm=false , bool solveNormal=false );
00166 
00167         template< class T2 >
00168         static int Solve( const SparseSymmetricMatrix<T>& M , const Vector<T2>& b , int iters , Vector<T2>& solution , MapReduceVector<T2>& scratch , T2 eps=1e-8 , int reset=1 , bool addDCTerm=false , bool solveNormal=false );
00169 #if defined _WIN32 && !defined __MINGW32__
00170         template< class T2 >
00171         static int SolveAtomic( const SparseSymmetricMatrix<T>& M , const Vector<T2>& b , int iters , Vector<T2>& solution , T2 eps=1e-8 , int reset=1 , int threads=0  , bool solveNormal=false );
00172 #endif // _WIN32 || __MINGW32__
00173         template<class T2>
00174         static int Solve( const SparseSymmetricMatrix<T>& M , const Vector<T2>& diagonal , const Vector<T2>& b , int iters , Vector<T2>& solution , int reset=1 );
00175 
00176         template< class T2 >
00177         void getDiagonal( Vector< T2 >& diagonal ) const;
00178     };
00179 
00180 
00181   }
00182 }
00183 
00184 
00185 #include "sparse_matrix.hpp"
00186 
00187 #endif
00188 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:33:37