Go to the documentation of this file.
   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 )
 
   53     A.resize(A_stl[0].
size(), A_stl.size());
 
   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];
 
   63     B.resize(B_stl.size(),1);
 
   65     for (
unsigned int i=0; 
i<B_stl.size() ; 
i++){
 
   66       B.coeffRef(
i) = B_stl[
i];
 
   71     for (
unsigned int i=0; 
i<B_stl.size() ; 
i++){
 
   72       B_stl[
i] = 
B.coeff(
i);
 
   79     for (
int j=0;
j<
N;
j++){
 
   81       for (
int i=0;
i<
N;
i++){
 
   82         A_stl[
j][
i] = 
A.coeff(
i,
j);
 
   92     X.noalias() = 
A.transpose()*
B.transpose();
 
   98     X.template selfadjointView<Lower>().rankUpdate(
A.transpose());
 
  103     X.template selfadjointView<Lower>().rankUpdate(
A);
 
  111     X.noalias() = (
A.template selfadjointView<Lower>() * 
B);
 
  115   template<
typename Dest, 
typename Src> 
static void triassign(Dest& dst, 
const Src& src)
 
  120     int size = dst.cols();
 
  124       Scalar* 
A0 = dst.data() + 
j*dst.stride();
 
  126       int alignedEnd = starti;
 
  128       alignedEnd = alignedStart + ((
size-alignedStart)/(2*PacketSize))*(PacketSize*2);
 
  131       for (
int index = starti; index<alignedStart ; ++index)
 
  134           dst.copyCoeff(
j, index, src);
 
  136           dst.copyCoeff(index, 
j, src);
 
  140       for (
int index = alignedStart; index<alignedEnd; index+=PacketSize)
 
  143           dst.template copyPacket<Src, Aligned, Unaligned>(
j, index, src);
 
  145           dst.template copyPacket<Src, Aligned, Unaligned>(index, 
j, src);
 
  149       for (
int index = alignedEnd; index<
size; ++index)
 
  152           dst.copyCoeff(
j, index, src);
 
  154           dst.copyCoeff(index, 
j, src);
 
  162     for(
int j=0; 
j<
N; ++
j)
 
  167     for(
int j=0; 
j<
N; ++
j)
 
  168       A.col(
j) += 
X * 
Y[
j];
 
  176     X.noalias() = (
A.transpose()*
B);
 
  200     X = 
L.template triangularView<Upper>().solve(
B);
 
  209     internal::llt_inplace<real,Lower>::blocked(
C);
 
  217     C = 
X.fullPivLu().matrixLU();
 
  
static void partial_lu_decomp(const gene_matrix &X, gene_matrix &C, int N)
static void atv_product(gene_matrix &A, gene_vector &B, gene_vector &X, int)
Eigen::Matrix< real, SIZE, SIZE > gene_matrix
Namespace containing all symbols from the Eigen library.
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
static EIGEN_DONT_INLINE void rot(gene_vector &A, gene_vector &B, real c, real s, int)
internal::packet_traits< Scalar >::type Packet
static void matrix_vector_product(const gene_matrix &A, const gene_vector &B, gene_vector &X, int)
static EIGEN_DONT_INLINE void copy_vector(const gene_vector &source, gene_vector &cible, int)
static void transposed_matrix_matrix_product(const gene_matrix &A, const gene_matrix &B, gene_matrix &X, int)
GaussianFactorGraphValuePair Y
static void trisolve_lower(const gene_matrix &L, const gene_vector &B, gene_vector &X, int)
const unsigned int RowMajorBit
static void 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)
const MatrixType & packedMatrix() const
Returns the internal representation of the decomposition.
static void symv(const gene_matrix &A, const gene_vector &B, gene_vector &X, int)
static BTL_DONT_INLINE void vector_to_stl(gene_vector &B, stl_vector &B_stl)
static void tridiagonalization(const gene_matrix &X, gene_matrix &C, int N)
static void cholesky(const gene_matrix &X, gene_matrix &C, int)
Rotation given by a cosine-sine pair.
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
static std::string name(void)
static void trmm(const gene_matrix &L, const gene_matrix &B, gene_matrix &X, int)
static void axpy(real coef, const gene_vector &X, gene_vector &Y, int)
static void aat_product(const gene_matrix &A, gene_matrix &X, int)
void partial_lu_inplace(MatrixType &lu, TranspositionType &row_transpositions, typename TranspositionType::StorageIndex &nb_transpositions)
static void ata_product(const gene_matrix &A, gene_matrix &X, int)
static BTL_DONT_INLINE void matrix_from_stl(gene_matrix &A, stl_matrix &A_stl)
static void free_vector(gene_vector &)
std::vector< stl_vector > stl_matrix
static Index first_aligned(const DenseBase< Derived > &m)
static EIGEN_DONT_INLINE void ger(gene_matrix &A, gene_vector &X, gene_vector &Y, int N)
static void triassign(Dest &dst, const Src &src)
EIGEN_DEVICE_FUNC void tridiagonalization_inplace(MatrixType &matA, CoeffVectorType &hCoeffs)
static void lu_decomp(const gene_matrix &X, gene_matrix &C, int)
static EIGEN_DONT_INLINE void copy_matrix(const gene_matrix &source, gene_matrix &cible, int)
static BTL_DONT_INLINE void matrix_to_stl(gene_matrix &A, stl_matrix &A_stl)
std::vector< real > stl_vector
Matrix< Scalar, Dynamic, Dynamic > C
#define EIGEN_MAKESTRING(a)
EIGEN_DEFAULT_DENSE_INDEX_TYPE DenseIndex
static void hessenberg(const gene_matrix &X, gene_matrix &C, int)
static EIGEN_DONT_INLINE void syr2(gene_matrix &A, gene_vector &X, gene_vector &Y, int N)
The matrix class, also used for vectors and row-vectors.
static void axpby(real a, const gene_vector &X, real b, gene_vector &Y, int)
A triangularView< Lower >().adjoint().solveInPlace(B)
Reduces a square matrix to Hessenberg form by an orthogonal similarity transformation.
static void free_matrix(gene_matrix &, int)
Eigen::Matrix< real, SIZE, 1 > gene_vector
EIGEN_DEVICE_FUNC void apply_rotation_in_the_plane(DenseBase< VectorX > &xpr_x, DenseBase< VectorY > &xpr_y, const JacobiRotation< OtherScalar > &j)
static void trisolve_lower_matrix(const gene_matrix &L, const gene_matrix &B, gene_matrix &X, int)
#define EIGEN_DONT_INLINE
gtsam
Author(s): 
autogenerated on Wed May 28 2025 03:01:14