18 #ifndef EIGEN2_INTERFACE_HH 19 #define EIGEN2_INTERFACE_HH 22 #include <Eigen/Cholesky> 28 using namespace Eigen;
30 template<
class real,
int SIZE=Dynamic>
46 static inline std::string
name(
void )
48 #if defined(EIGEN_VECTORIZE_SSE) 49 if (
SIZE==
Dynamic)
return "eigen2";
else return "tiny_eigen2";
50 #elif defined(EIGEN_VECTORIZE_ALTIVEC) || defined(EIGEN_VECTORIZE_VSX) 51 if (
SIZE==
Dynamic)
return "eigen2";
else return "tiny_eigen2";
53 if (
SIZE==
Dynamic)
return "eigen2_novec";
else return "tiny_eigen2_novec";
64 for (
int j=0;
j<A_stl.size() ;
j++){
65 for (
int i=0;
i<A_stl[
j].size() ;
i++){
74 for (
int i=0;
i<B_stl.size() ;
i++){
80 for (
int i=0;
i<B_stl.size() ;
i++){
88 for (
int j=0;
j<
N;
j++){
90 for (
int i=0;
i<
N;
i++){
101 X = (A.transpose()*B.transpose()).lazy();
104 static inline void ata_product(
const gene_matrix & A, gene_matrix &
X,
int N){
105 X = (A.transpose()*A).lazy();
108 static inline void aat_product(
const gene_matrix & A, gene_matrix &
X,
int N){
109 X = (A*A.transpose()).lazy();
116 static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector &
X,
int N){
117 X = (A.transpose()*B);
120 static inline void axpy(
real coef,
const gene_vector &
X, gene_vector &
Y,
int N){
128 static inline void copy_matrix(
const gene_matrix & source, gene_matrix & cible,
int N){
132 static inline void copy_vector(
const gene_vector & source, gene_vector & cible,
int N){
136 static inline void trisolve_lower(
const gene_matrix &
L,
const gene_vector& B, gene_vector&
X,
int N){
137 X = L.template marked<LowerTriangular>().solveTriangular(B);
141 X = L.template marked<LowerTriangular>().solveTriangular(B);
144 static inline void cholesky(
const gene_matrix &
X, gene_matrix &
C,
int N){
145 C = X.llt().matrixL();
151 static inline void lu_decomp(
const gene_matrix &
X, gene_matrix &
C,
int N){
152 C = X.lu().matrixLU();
160 static inline void hessenberg(
const gene_matrix &
X, gene_matrix &
C,
int N){
static void axpby(real a, const gene_vector &X, real b, gene_vector &Y, int N)
static void trisolve_lower_matrix(const gene_matrix &L, const gene_matrix &B, gene_matrix &X, int N)
static void aat_product(const gene_matrix &A, gene_matrix &X, int N)
Namespace containing all symbols from the Eigen library.
static BTL_DONT_INLINE void matrix_from_stl(gene_matrix &A, stl_matrix &A_stl)
Tridiagonal decomposition of a selfadjoint matrix.
static void free_vector(gene_vector &B)
static BTL_DONT_INLINE void matrix_to_stl(gene_matrix &A, stl_matrix &A_stl)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar & coeffRef(Index rowId, Index colId)
static void lu_decomp(const gene_matrix &X, gene_matrix &C, int N)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index rows, Index cols)
std::vector< real > stl_vector
static void matrix_matrix_product(const gene_matrix &A, const gene_matrix &B, gene_matrix &X, int N)
static BTL_DONT_INLINE void vector_to_stl(gene_vector &B, stl_vector &B_stl)
static void transposed_matrix_matrix_product(const gene_matrix &A, const gene_matrix &B, gene_matrix &X, int N)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar & coeff(Index rowId, Index colId) const
static BTL_DONT_INLINE void vector_from_stl(gene_vector &B, stl_vector &B_stl)
static void matrix_vector_product(const gene_matrix &A, const gene_vector &B, gene_vector &X, int N)
static void ata_product(const gene_matrix &A, gene_matrix &X, int N)
Eigen::Matrix< real, SIZE, SIZE > gene_matrix
static std::string name(void)
static void copy_vector(const gene_vector &source, gene_vector &cible, int N)
Matrix< Scalar, Dynamic, Dynamic > C
static void copy_matrix(const gene_matrix &source, gene_matrix &cible, int N)
static void trisolve_lower(const gene_matrix &L, const gene_vector &B, gene_vector &X, int N)
static void free_matrix(gene_matrix &A, int N)
Reduces a square matrix to Hessenberg form by an orthogonal similarity transformation.
std::vector< stl_vector > stl_matrix
static void atv_product(gene_matrix &A, gene_vector &B, gene_vector &X, int N)
static void hessenberg(const gene_matrix &X, gene_matrix &C, int N)
static void cholesky(const gene_matrix &X, gene_matrix &C, int N)
static void axpy(real coef, const gene_vector &X, gene_vector &Y, int N)
Eigen::Matrix< real, SIZE, 1 > gene_vector
The matrix class, also used for vectors and row-vectors.
static void tridiagonalization(const gene_matrix &X, gene_matrix &C, int N)