eigen3_interface.hh
Go to the documentation of this file.
1 //=====================================================
2 // Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>
3 //=====================================================
4 //
5 // This program is free software; you can redistribute it and/or
6 // modify it under the terms of the GNU General Public License
7 // as published by the Free Software Foundation; either version 2
8 // of the License, or (at your option) any later version.
9 //
10 // This program is distributed in the hope that it will be useful,
11 // but WITHOUT ANY WARRANTY; without even the implied warranty of
12 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 // GNU General Public License for more details.
14 // You should have received a copy of the GNU General Public License
15 // along with this program; if not, write to the Free Software
16 // Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
17 //
18 #ifndef EIGEN3_INTERFACE_HH
19 #define EIGEN3_INTERFACE_HH
20 
21 #include <Eigen/Eigen>
22 #include <vector>
23 #include "btl.hh"
24 
25 using namespace Eigen;
26 
27 template<class real, int SIZE=Dynamic>
29 {
30 
31 public :
32 
33  enum {IsFixedSize = (SIZE!=Dynamic)};
34 
35  typedef real real_type;
36 
37  typedef std::vector<real> stl_vector;
38  typedef std::vector<stl_vector> stl_matrix;
39 
42 
43  static inline std::string name( void )
44  {
45  return EIGEN_MAKESTRING(BTL_PREFIX);
46  }
47 
48  static void free_matrix(gene_matrix & /*A*/, int /*N*/) {}
49 
50  static void free_vector(gene_vector & /*B*/) {}
51 
53  A.resize(A_stl[0].size(), A_stl.size());
54 
55  for (unsigned int j=0; j<A_stl.size() ; j++){
56  for (unsigned int i=0; i<A_stl[j].size() ; i++){
57  A.coeffRef(i,j) = A_stl[j][i];
58  }
59  }
60  }
61 
63  B.resize(B_stl.size(),1);
64 
65  for (unsigned int i=0; i<B_stl.size() ; i++){
66  B.coeffRef(i) = B_stl[i];
67  }
68  }
69 
71  for (unsigned int i=0; i<B_stl.size() ; i++){
72  B_stl[i] = B.coeff(i);
73  }
74  }
75 
77  int N=A_stl.size();
78 
79  for (int j=0;j<N;j++){
80  A_stl[j].resize(N);
81  for (int i=0;i<N;i++){
82  A_stl[j][i] = A.coeff(i,j);
83  }
84  }
85  }
86 
87  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int /*N*/){
88  X.noalias() = A*B;
89  }
90 
91  static inline void transposed_matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int /*N*/){
92  X.noalias() = A.transpose()*B.transpose();
93  }
94 
95  static inline void ata_product(const gene_matrix & A, gene_matrix & X, int /*N*/){
96  //X.noalias() = A.transpose()*A;
97  X.template triangularView<Lower>().setZero();
98  X.template selfadjointView<Lower>().rankUpdate(A.transpose());
99  }
100 
101  static inline void aat_product(const gene_matrix & A, gene_matrix & X, int /*N*/){
102  X.template triangularView<Lower>().setZero();
103  X.template selfadjointView<Lower>().rankUpdate(A);
104  }
105 
106  static inline void matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int /*N*/){
107  X.noalias() = A*B;
108  }
109 
110  static inline void symv(const gene_matrix & A, const gene_vector & B, gene_vector & X, int /*N*/){
111  X.noalias() = (A.template selfadjointView<Lower>() * B);
112 // internal::product_selfadjoint_vector<real,0,LowerTriangularBit,false,false>(N,A.data(),N, B.data(), 1, X.data(), 1);
113  }
114 
115  template<typename Dest, typename Src> static void triassign(Dest& dst, const Src& src)
116  {
117  typedef typename Dest::Scalar Scalar;
119  const int PacketSize = sizeof(Packet)/sizeof(Scalar);
120  int size = dst.cols();
121  for(int j=0; j<size; j+=1)
122  {
123 // const int alignedEnd = alignedStart + ((innerSize-alignedStart) & ~packetAlignedMask);
124  Scalar* A0 = dst.data() + j*dst.stride();
125  int starti = j;
126  int alignedEnd = starti;
127  int alignedStart = (starti) + internal::first_aligned(&A0[starti], size-starti);
128  alignedEnd = alignedStart + ((size-alignedStart)/(2*PacketSize))*(PacketSize*2);
129 
130  // do the non-vectorizable part of the assignment
131  for (int index = starti; index<alignedStart ; ++index)
132  {
133  if(Dest::Flags&RowMajorBit)
134  dst.copyCoeff(j, index, src);
135  else
136  dst.copyCoeff(index, j, src);
137  }
138 
139  // do the vectorizable part of the assignment
140  for (int index = alignedStart; index<alignedEnd; index+=PacketSize)
141  {
142  if(Dest::Flags&RowMajorBit)
143  dst.template copyPacket<Src, Aligned, Unaligned>(j, index, src);
144  else
145  dst.template copyPacket<Src, Aligned, Unaligned>(index, j, src);
146  }
147 
148  // do the non-vectorizable part of the assignment
149  for (int index = alignedEnd; index<size; ++index)
150  {
151  if(Dest::Flags&RowMajorBit)
152  dst.copyCoeff(j, index, src);
153  else
154  dst.copyCoeff(index, j, src);
155  }
156  //dst.col(j).tail(N-j) = src.col(j).tail(N-j);
157  }
158  }
159 
161  // internal::product_selfadjoint_rank2_update<real,0,LowerTriangularBit>(N,A.data(),N, X.data(), 1, Y.data(), 1, -1);
162  for(int j=0; j<N; ++j)
163  A.col(j).tail(N-j) += X[j] * Y.tail(N-j) + Y[j] * X.tail(N-j);
164  }
165 
167  for(int j=0; j<N; ++j)
168  A.col(j) += X * Y[j];
169  }
170 
171  static EIGEN_DONT_INLINE void rot(gene_vector & A, gene_vector & B, real c, real s, int /*N*/){
173  }
174 
175  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int /*N*/){
176  X.noalias() = (A.transpose()*B);
177  }
178 
179  static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int /*N*/){
180  Y += coef * X;
181  }
182 
183  static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int /*N*/){
184  Y = a*X + b*Y;
185  }
186 
187  static EIGEN_DONT_INLINE void copy_matrix(const gene_matrix & source, gene_matrix & cible, int /*N*/){
188  cible = source;
189  }
190 
191  static EIGEN_DONT_INLINE void copy_vector(const gene_vector & source, gene_vector & cible, int /*N*/){
192  cible = source;
193  }
194 
195  static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector& X, int /*N*/){
196  X = L.template triangularView<Lower>().solve(B);
197  }
198 
199  static inline void trisolve_lower_matrix(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int /*N*/){
200  X = L.template triangularView<Upper>().solve(B);
201  }
202 
203  static inline void trmm(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int /*N*/){
204  X.noalias() = L.template triangularView<Lower>() * B;
205  }
206 
207  static inline void cholesky(const gene_matrix & X, gene_matrix & C, int /*N*/){
208  C = X;
209  internal::llt_inplace<real,Lower>::blocked(C);
210  //C = X.llt().matrixL();
211 // C = X;
212 // Cholesky<gene_matrix>::computeInPlace(C);
213 // Cholesky<gene_matrix>::computeInPlaceBlock(C);
214  }
215 
216  static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int /*N*/){
217  C = X.fullPivLu().matrixLU();
218  }
219 
220  static inline void partial_lu_decomp(const gene_matrix & X, gene_matrix & C, int N){
222  DenseIndex nb;
223  C = X;
225 // C = X.partialPivLu().matrixLU();
226  }
227 
228  static inline void tridiagonalization(const gene_matrix & X, gene_matrix & C, int N){
230  C = X;
232  }
233 
234  static inline void hessenberg(const gene_matrix & X, gene_matrix & C, int /*N*/){
236  }
237 
238 
239 
240 };
241 
242 #endif
eigen3_interface::partial_lu_decomp
static void partial_lu_decomp(const gene_matrix &X, gene_matrix &C, int N)
Definition: eigen3_interface.hh:220
eigen3_interface::atv_product
static void atv_product(gene_matrix &A, gene_vector &B, gene_vector &X, int)
Definition: eigen3_interface.hh:175
eigen3_interface::gene_matrix
Eigen::Matrix< real, SIZE, SIZE > gene_matrix
Definition: eigen3_interface.hh:40
Eigen
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
B
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
Definition: bench_gemm.cpp:49
eigen3_interface::rot
static EIGEN_DONT_INLINE void rot(gene_vector &A, gene_vector &B, real c, real s, int)
Definition: eigen3_interface.hh:171
Y
const char Y
Definition: test/EulerAngles.cpp:31
s
RealScalar s
Definition: level1_cplx_impl.h:126
btl.hh
Packet
internal::packet_traits< Scalar >::type Packet
Definition: benchmark-blocking-sizes.cpp:54
eigen3_interface::matrix_vector_product
static void matrix_vector_product(const gene_matrix &A, const gene_vector &B, gene_vector &X, int)
Definition: eigen3_interface.hh:106
eigen3_interface::copy_vector
static EIGEN_DONT_INLINE void copy_vector(const gene_vector &source, gene_vector &cible, int)
Definition: eigen3_interface.hh:191
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
b
Scalar * b
Definition: benchVecAdd.cpp:17
eigen3_interface::transposed_matrix_matrix_product
static void transposed_matrix_matrix_product(const gene_matrix &A, const gene_matrix &B, gene_matrix &X, int)
Definition: eigen3_interface.hh:91
eigen3_interface::trisolve_lower
static void trisolve_lower(const gene_matrix &L, const gene_vector &B, gene_vector &X, int)
Definition: eigen3_interface.hh:195
Eigen::RowMajorBit
const unsigned int RowMajorBit
Definition: Constants.h:66
eigen3_interface::matrix_matrix_product
static void matrix_matrix_product(const gene_matrix &A, const gene_matrix &B, gene_matrix &X, int)
Definition: eigen3_interface.hh:87
eigen3_interface::vector_from_stl
static BTL_DONT_INLINE void vector_from_stl(gene_vector &B, stl_vector &B_stl)
Definition: eigen3_interface.hh:62
Eigen::HessenbergDecomposition::packedMatrix
const MatrixType & packedMatrix() const
Returns the internal representation of the decomposition.
Definition: HessenbergDecomposition.h:214
eigen3_interface::symv
static void symv(const gene_matrix &A, const gene_vector &B, gene_vector &X, int)
Definition: eigen3_interface.hh:110
eigen3_interface::vector_to_stl
static BTL_DONT_INLINE void vector_to_stl(gene_vector &B, stl_vector &B_stl)
Definition: eigen3_interface.hh:70
eigen3_interface::tridiagonalization
static void tridiagonalization(const gene_matrix &X, gene_matrix &C, int N)
Definition: eigen3_interface.hh:228
X
#define X
Definition: icosphere.cpp:20
eigen3_interface
Definition: eigen3_interface.hh:28
eigen3_interface::cholesky
static void cholesky(const gene_matrix &X, gene_matrix &C, int)
Definition: eigen3_interface.hh:207
Eigen::JacobiRotation
Rotation given by a cosine-sine pair.
Definition: ForwardDeclarations.h:283
A0
static const double A0[]
Definition: expn.h:5
A
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Definition: bench_gemm.cpp:48
size
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
eigen3_interface::name
static std::string name(void)
Definition: eigen3_interface.hh:43
eigen3_interface::trmm
static void trmm(const gene_matrix &L, const gene_matrix &B, gene_matrix &X, int)
Definition: eigen3_interface.hh:203
eigen3_interface::axpy
static void axpy(real coef, const gene_vector &X, gene_vector &Y, int)
Definition: eigen3_interface.hh:179
eigen3_interface::aat_product
static void aat_product(const gene_matrix &A, gene_matrix &X, int)
Definition: eigen3_interface.hh:101
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
Eigen::internal::partial_lu_inplace
void partial_lu_inplace(MatrixType &lu, TranspositionType &row_transpositions, typename TranspositionType::StorageIndex &nb_transpositions)
Definition: PartialPivLU.h:505
eigen3_interface::ata_product
static void ata_product(const gene_matrix &A, gene_matrix &X, int)
Definition: eigen3_interface.hh:95
eigen3_interface::matrix_from_stl
static BTL_DONT_INLINE void matrix_from_stl(gene_matrix &A, stl_matrix &A_stl)
Definition: eigen3_interface.hh:52
Eigen::Dynamic
const int Dynamic
Definition: Constants.h:22
eigen3_interface::free_vector
static void free_vector(gene_vector &)
Definition: eigen3_interface.hh:50
eigen3_interface::stl_matrix
std::vector< stl_vector > stl_matrix
Definition: eigen3_interface.hh:38
Eigen::internal::first_aligned
static Index first_aligned(const DenseBase< Derived > &m)
Definition: DenseCoeffsBase.h:643
L
MatrixXd L
Definition: LLT_example.cpp:6
eigen3_interface::ger
static EIGEN_DONT_INLINE void ger(gene_matrix &A, gene_vector &X, gene_vector &Y, int N)
Definition: eigen3_interface.hh:166
SIZE
#define SIZE
Definition: BenchSparseUtil.h:11
eigen3_interface::real_type
real real_type
Definition: eigen3_interface.hh:35
Eigen::Triplet< double >
eigen3_interface::triassign
static void triassign(Dest &dst, const Src &src)
Definition: eigen3_interface.hh:115
Eigen::internal::tridiagonalization_inplace
EIGEN_DEVICE_FUNC void tridiagonalization_inplace(MatrixType &matA, CoeffVectorType &hCoeffs)
Definition: Tridiagonalization.h:349
eigen3_interface::lu_decomp
static void lu_decomp(const gene_matrix &X, gene_matrix &C, int)
Definition: eigen3_interface.hh:216
eigen3_interface::copy_matrix
static EIGEN_DONT_INLINE void copy_matrix(const gene_matrix &source, gene_matrix &cible, int)
Definition: eigen3_interface.hh:187
eigen3_interface::matrix_to_stl
static BTL_DONT_INLINE void matrix_to_stl(gene_matrix &A, stl_matrix &A_stl)
Definition: eigen3_interface.hh:76
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
eigen3_interface::stl_vector
std::vector< real > stl_vector
Definition: eigen3_interface.hh:37
C
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:50
EIGEN_MAKESTRING
#define EIGEN_MAKESTRING(a)
Definition: Macros.h:908
Eigen::DenseIndex
EIGEN_DEFAULT_DENSE_INDEX_TYPE DenseIndex
Definition: Meta.h:66
eigen3_interface::hessenberg
static void hessenberg(const gene_matrix &X, gene_matrix &C, int)
Definition: eigen3_interface.hh:234
eigen3_interface::syr2
static EIGEN_DONT_INLINE void syr2(gene_matrix &A, gene_vector &X, gene_vector &Y, int N)
Definition: eigen3_interface.hh:160
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
N
#define N
Definition: igam.h:9
eigen3_interface::axpby
static void axpby(real a, const gene_vector &X, real b, gene_vector &Y, int)
Definition: eigen3_interface.hh:183
triangularView< Lower >
A triangularView< Lower >().adjoint().solveInPlace(B)
Eigen::HessenbergDecomposition
Reduces a square matrix to Hessenberg form by an orthogonal similarity transformation.
Definition: HessenbergDecomposition.h:57
BTL_DONT_INLINE
#define BTL_DONT_INLINE
Definition: btl.hh:38
eigen3_interface::free_matrix
static void free_matrix(gene_matrix &, int)
Definition: eigen3_interface.hh:48
real
Definition: main.h:100
eigen3_interface::gene_vector
Eigen::Matrix< real, SIZE, 1 > gene_vector
Definition: eigen3_interface.hh:41
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Eigen::internal::apply_rotation_in_the_plane
EIGEN_DEVICE_FUNC void apply_rotation_in_the_plane(DenseBase< VectorX > &xpr_x, DenseBase< VectorY > &xpr_y, const JacobiRotation< OtherScalar > &j)
Definition: Jacobi.h:453
Scalar
SCALAR Scalar
Definition: bench_gemm.cpp:46
eigen3_interface::trisolve_lower_matrix
static void trisolve_lower_matrix(const gene_matrix &L, const gene_matrix &B, gene_matrix &X, int)
Definition: eigen3_interface.hh:199
EIGEN_DONT_INLINE
#define EIGEN_DONT_INLINE
Definition: Macros.h:940


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:00:50