18 #ifndef EIGEN3_INTERFACE_HH 19 #define EIGEN3_INTERFACE_HH 21 #include <Eigen/Eigen> 25 using namespace Eigen;
27 template<
class real,
int SIZE=Dynamic>
43 static inline std::string
name(
void )
55 for (
unsigned int j=0;
j<A_stl.size() ;
j++){
56 for (
unsigned int i=0;
i<A_stl[
j].size() ;
i++){
65 for (
unsigned int i=0;
i<B_stl.size() ;
i++){
71 for (
unsigned int i=0;
i<B_stl.size() ;
i++){
79 for (
int j=0;
j<
N;
j++){
81 for (
int i=0;
i<
N;
i++){
92 X.noalias() = A.transpose()*B.transpose();
99 static inline void aat_product(
const gene_matrix &
A, gene_matrix &
X,
int ){
101 X.template selfadjointView<Lower>().rankUpdate(A);
108 static inline void symv(
const gene_matrix &
A,
const gene_vector & B, gene_vector &
X,
int ){
109 X.noalias() = (A.template selfadjointView<Lower>() * B);
113 template<
typename Dest,
typename Src>
static void triassign(Dest& dst,
const Src& src)
117 const int PacketSize =
sizeof(
Packet)/
sizeof(Scalar);
118 int size = dst.cols();
122 Scalar* A0 = dst.data() +
j*dst.stride();
124 int alignedEnd = starti;
126 alignedEnd = alignedStart + ((size-alignedStart)/(2*PacketSize))*(PacketSize*2);
129 for (
int index = starti; index<alignedStart ; ++index)
132 dst.copyCoeff(
j, index, src);
134 dst.copyCoeff(index,
j, src);
138 for (
int index = alignedStart; index<alignedEnd; index+=PacketSize)
141 dst.template copyPacket<Src, Aligned, Unaligned>(
j, index, src);
143 dst.template copyPacket<Src, Aligned, Unaligned>(index,
j, src);
147 for (
int index = alignedEnd; index<
size; ++index)
150 dst.copyCoeff(
j, index, src);
152 dst.copyCoeff(index,
j, src);
160 for(
int j=0;
j<
N; ++
j)
161 A.col(
j).tail(N-
j) += X[
j] * Y.tail(N-
j) + Y[
j] * X.tail(N-
j);
165 for(
int j=0;
j<
N; ++
j)
166 A.col(
j) += X * Y[
j];
173 static inline void atv_product(gene_matrix &
A, gene_vector & B, gene_vector &
X,
int ){
174 X.noalias() = (A.transpose()*B);
177 static inline void axpy(
real coef,
const gene_vector &
X, gene_vector &
Y,
int ){
193 static inline void trisolve_lower(
const gene_matrix &
L,
const gene_vector& B, gene_vector&
X,
int ){
198 X = L.template triangularView<Upper>().solve(B);
201 static inline void trmm(
const gene_matrix &
L,
const gene_matrix& B, gene_matrix&
X,
int ){
205 static inline void cholesky(
const gene_matrix &
X, gene_matrix &
C,
int ){
207 internal::llt_inplace<real,Lower>::blocked(C);
214 static inline void lu_decomp(
const gene_matrix &
X, gene_matrix &
C,
int ){
215 C = X.fullPivLu().matrixLU();
232 static inline void hessenberg(
const gene_matrix &
X, gene_matrix &
C,
int ){
internal::packet_traits< Scalar >::type Packet
static EIGEN_DONT_INLINE void syr2(gene_matrix &A, gene_vector &X, gene_vector &Y, int N)
#define EIGEN_MAKESTRING(a)
static BTL_DONT_INLINE void vector_to_stl(gene_vector &B, stl_vector &B_stl)
static Index first_aligned(const DenseBase< Derived > &m)
Eigen::Matrix< real, SIZE, 1 > gene_vector
static void axpy(real coef, const gene_vector &X, gene_vector &Y, int)
static void trisolve_lower_matrix(const gene_matrix &L, const gene_matrix &B, gene_matrix &X, int)
static void atv_product(gene_matrix &A, gene_vector &B, gene_vector &X, int)
static EIGEN_DONT_INLINE void rot(gene_vector &A, gene_vector &B, real c, real s, int)
Namespace containing all symbols from the Eigen library.
static void free_vector(gene_vector &)
std::vector< stl_vector > stl_matrix
Rotation given by a cosine-sine pair.
static void aat_product(const gene_matrix &A, gene_matrix &X, int)
Eigen::Matrix< real, SIZE, SIZE > gene_matrix
const unsigned int RowMajorBit
static EIGEN_DONT_INLINE void ger(gene_matrix &A, gene_vector &X, gene_vector &Y, int N)
static void transposed_matrix_matrix_product(const gene_matrix &A, const gene_matrix &B, gene_matrix &X, int)
static BTL_DONT_INLINE void vector_from_stl(gene_vector &B, stl_vector &B_stl)
#define EIGEN_DONT_INLINE
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar & coeffRef(Index rowId, Index colId)
static void symv(const gene_matrix &A, const gene_vector &B, gene_vector &X, int)
static EIGEN_DONT_INLINE void copy_matrix(const gene_matrix &source, gene_matrix &cible, int)
static void tridiagonalization(const gene_matrix &X, gene_matrix &C, int N)
static EIGEN_DONT_INLINE void copy_vector(const gene_vector &source, gene_vector &cible, int)
static void matrix_vector_product(const gene_matrix &A, const gene_vector &B, gene_vector &X, int)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index rows, Index cols)
static void cholesky(const gene_matrix &X, gene_matrix &C, int)
static void matrix_matrix_product(const gene_matrix &A, const gene_matrix &B, gene_matrix &X, int)
void partial_lu_inplace(MatrixType &lu, TranspositionType &row_transpositions, typename TranspositionType::StorageIndex &nb_transpositions)
static BTL_DONT_INLINE void matrix_to_stl(gene_matrix &A, stl_matrix &A_stl)
static std::string name(void)
std::vector< real > stl_vector
static void axpby(real a, const gene_vector &X, real b, gene_vector &Y, int)
static void trmm(const gene_matrix &L, const gene_matrix &B, gene_matrix &X, int)
static BTL_DONT_INLINE void matrix_from_stl(gene_matrix &A, stl_matrix &A_stl)
Matrix< Scalar, Dynamic, Dynamic > C
static void free_matrix(gene_matrix &, int)
EIGEN_DEFAULT_DENSE_INDEX_TYPE DenseIndex
void tridiagonalization_inplace(MatrixType &matA, CoeffVectorType &hCoeffs)
A triangularView< Lower >().adjoint().solveInPlace(B)
Reduces a square matrix to Hessenberg form by an orthogonal similarity transformation.
static void triassign(Dest &dst, const Src &src)
void apply_rotation_in_the_plane(DenseBase< VectorX > &xpr_x, DenseBase< VectorY > &xpr_y, const JacobiRotation< OtherScalar > &j)
static void lu_decomp(const gene_matrix &X, gene_matrix &C, int)
static void partial_lu_decomp(const gene_matrix &X, gene_matrix &C, int N)
The matrix class, also used for vectors and row-vectors.
static void trisolve_lower(const gene_matrix &L, const gene_vector &B, gene_vector &X, int)
static void hessenberg(const gene_matrix &X, gene_matrix &C, int)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar & coeff(Index rowId, Index colId) const