Go to the documentation of this file.
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";
62 A.resize(A_stl[0].
size(), A_stl.size());
64 for (
int j=0;
j<A_stl.size() ;
j++){
65 for (
int i=0;
i<A_stl[
j].size() ;
i++){
66 A.coeffRef(
i,
j) = A_stl[
j][
i];
72 B.resize(B_stl.size(),1);
74 for (
int i=0;
i<B_stl.size() ;
i++){
75 B.coeffRef(
i) = B_stl[
i];
80 for (
int i=0;
i<B_stl.size() ;
i++){
81 B_stl[
i] =
B.coeff(
i);
88 for (
int j=0;
j<
N;
j++){
90 for (
int i=0;
i<
N;
i++){
91 A_stl[
j][
i] =
A.coeff(
i,
j);
101 X = (
A.transpose()*
B.transpose()).lazy();
105 X = (
A.transpose()*
A).lazy();
109 X = (
A*
A.transpose()).lazy();
117 X = (
A.transpose()*
B);
137 X =
L.template marked<LowerTriangular>().solveTriangular(
B);
141 X =
L.template marked<LowerTriangular>().solveTriangular(
B);
145 C =
X.llt().matrixL();
152 C =
X.lu().matrixLU();
const MatrixType & packedMatrix() const
Returns the internal representation of the decomposition.
Namespace containing all symbols from the Eigen library.
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
static void tridiagonalization(const gene_matrix &X, gene_matrix &C, int N)
Tridiagonal decomposition of a selfadjoint matrix.
static void aat_product(const gene_matrix &A, gene_matrix &X, int N)
static void free_vector(gene_vector &B)
GaussianFactorGraphValuePair Y
static BTL_DONT_INLINE void matrix_from_stl(gene_matrix &A, stl_matrix &A_stl)
const MatrixType & packedMatrix() const
Returns the internal representation of the decomposition.
static void trisolve_lower_matrix(const gene_matrix &L, const gene_matrix &B, gene_matrix &X, int N)
static void axpby(real a, const gene_vector &X, real b, gene_vector &Y, int N)
static void lu_decomp(const gene_matrix &X, gene_matrix &C, int N)
static BTL_DONT_INLINE void matrix_to_stl(gene_matrix &A, stl_matrix &A_stl)
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
static void transposed_matrix_matrix_product(const gene_matrix &A, const gene_matrix &B, gene_matrix &X, int N)
std::vector< real > stl_vector
static void ata_product(const gene_matrix &A, gene_matrix &X, int N)
Eigen::Matrix< real, SIZE, SIZE > gene_matrix
static void matrix_vector_product(const gene_matrix &A, const gene_vector &B, gene_vector &X, int N)
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 std::string name(void)
static BTL_DONT_INLINE void vector_from_stl(gene_vector &B, stl_vector &B_stl)
Matrix< Scalar, Dynamic, Dynamic > C
static void copy_matrix(const gene_matrix &source, gene_matrix &cible, int N)
Eigen::Matrix< real, SIZE, 1 > gene_vector
static void free_matrix(gene_matrix &A, int N)
static void copy_vector(const gene_vector &source, gene_vector &cible, int N)
std::vector< stl_vector > stl_matrix
static void atv_product(gene_matrix &A, gene_vector &B, gene_vector &X, int N)
static void trisolve_lower(const gene_matrix &L, const gene_vector &B, gene_vector &X, int N)
The matrix class, also used for vectors and row-vectors.
static void hessenberg(const gene_matrix &X, gene_matrix &C, int N)
Reduces a square matrix to Hessenberg form by an orthogonal similarity transformation.
static void axpy(real coef, const gene_vector &X, gene_vector &Y, int N)
static void cholesky(const gene_matrix &X, gene_matrix &C, int N)
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:14