Go to the documentation of this file.
    7 #ifndef SPECTRA_BK_LDLT_H 
    8 #define SPECTRA_BK_LDLT_H 
   13 #include <type_traits>   
   15 #include "../Util/CompInfo.h" 
   27 template <
typename Scalar>
 
   41 template <
typename RealScalar>
 
   44     static std::complex<RealScalar> 
conj(
const std::complex<RealScalar>& 
x)
 
   50     static std::complex<RealScalar> 
real(
const std::complex<RealScalar>& 
x)
 
   52         return std::complex<RealScalar>(
x.real(), 
RealScalar(0));
 
   64 template <
typename Scalar = 
double>
 
   82     std::vector<std::pair<Index, Index>> 
m_permc;  
 
  112     template <
typename Derived>
 
  121         if ((!Derived::PlainObject::IsRowMajor) && uplo == 
Eigen::Lower)
 
  125                 const Scalar* begin = &src.coeffRef(
j, 
j);
 
  139                         *dest = src.coeff(
i, 
j);
 
  256                 r = 
k + (ptr - 
head);
 
  281             if (
sigma < abs_elem)
 
  392         if (e11_abs >= e21_abs)
 
  394             const Scalar fac = e21 / e11;
 
  405             const Scalar fac = e11 / e21;
 
  428         if (e11_abs >= e12_abs)
 
  430             const Scalar fac = e12 / e11;
 
  433             x.col(1).array() = (
c2 - fac * 
c1).
array() / (e22 - fac * e21);
 
  434             x.col(0).array() = (
c1 - e21 * 
x.col(1)).
array() / e11;
 
  441             const Scalar fac = e11 / e12;
 
  444             x.col(1).array() = (
c1 - fac * 
c2).
array() / (e21 - fac * e22);
 
  445             x.col(0).array() = (
c2 - e22 * 
x.col(1)).
array() / e12;
 
  497         if (e11 * e22 - e12 * e21 == 
Scalar(0))
 
  522             MapVec(
col_pointer(
j + 
k + 2), ldim - 
j).noalias() -= (
X.col(0).tail(ldim - 
j) * l1j_conj + 
X.col(1).tail(ldim - 
j) * l2j_conj);
 
  526         l1.noalias() = 
X.col(0);
 
  527         l2.noalias() = 
X.col(1);
 
  538     template <
typename Derived>
 
  545     template <
typename Derived>
 
  552             throw std::invalid_argument(
"BKLDLT: matrix must be square");
 
  564         for (
k = 0; 
k < 
m_n - 1; 
k++)
 
  605             throw std::logic_error(
"BKLDLT: need to call compute() first");
 
  625             const Index b2size = b1size - 1;
 
  629                 res.segment(
i + 1, b1size).noalias() -= 
l * 
x[
i];
 
  635                 res.segment(
i + 2, b2size).noalias() -= (
l1 * 
x[
i] + 
l2 * 
x[
i + 1]);
 
  675             x[
i] -= 
l.dot(
res.segment(
i + 1, ldim));
 
  680                 x[
i - 1] -= 
l2.dot(
res.segment(
i + 1, ldim));
 
  686         for (
Index i = npermc - 1; 
i >= 0; 
i--)
 
  704 #endif  // SPECTRA_BK_LDLT_H 
  
BKLDLT(const Eigen::MatrixBase< Derived > &mat, int uplo=Eigen::Lower, const RealScalar &shift=RealScalar(0))
idx_t idx_t idx_t idx_t idx_t * perm
void inverse_inplace_2x2(Scalar &e11, Scalar &e21, Scalar &e22) const
@ Successful
Computation was successful.
void solve_inplace(GenericVector b) const
void copy_data(const Eigen::MatrixBase< Derived > &mat, int uplo, const RealScalar &shift)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
const Scalar & coeff(Index i, Index j) const
Scalar * col_pointer(Index k)
std::vector< std::pair< Index, Index > > m_permc
Scalar & coeff(Index i, Index j)
void compute(const Eigen::MatrixBase< Derived > &mat, int uplo=Eigen::Lower, const RealScalar &shift=RealScalar(0))
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index rows, Index cols)
Eigen::Map< Vector > MapVec
static const double sigma
const Scalar & diag_coeff(Index i) const
void interchange_rows(Index r1, Index r2, Index c1, Index c2)
Scalar & diag_coeff(Index i)
RealScalar find_sigma(Index k, Index r, Index &p)
void solve_inplace_2x2(const Scalar &e11, const Scalar &e21, const Scalar &e22, Scalar &b1, Scalar &b2) const
void pivoting_2x2(Index k, Index r, Index p)
static const Line3 l(Rot3(), 1, 1)
typename Eigen::NumTraits< Scalar >::Real RealScalar
void swap(GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &a, GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &b)
static Scalar real(const Scalar &x)
bool permutate_mat(Index k, const RealScalar &alpha)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE FixedSegmentReturnType< internal::get_fixed_value< NType >::value >::Type head(NType n)
AnnoyingScalar conj(const AnnoyingScalar &x)
void solve_left_2x2(const Scalar &e11, const Scalar &e21, const Scalar &e22, const MapVec &c1, const MapVec &c2, Eigen::Matrix< Scalar, Eigen::Dynamic, 2 > &x) const
A matrix or vector expression mapping an existing array of data.
Vector solve(ConstGenericVector &b) const
void compress_permutation()
NumTraits< Scalar >::Real RealScalar
A matrix or vector expression mapping an existing expression.
CompInfo gaussian_elimination_1x1(Index k)
static std::complex< RealScalar > real(const std::complex< RealScalar > &x)
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE Scalar * data() const
void pivoting_1x1(Index k, Index r)
size_t len(handle h)
Get the length of a Python object.
Base class for all dense matrices, vectors, and expressions.
static Scalar conj(const Scalar &x)
RealScalar find_lambda(Index k, Index &r)
std::vector< Scalar * > m_colptr
static const EIGEN_DEPRECATED end_t end
CompInfo gaussian_elimination_2x2(Index k)
static std::complex< RealScalar > conj(const std::complex< RealScalar > &x)
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
Jet< T, N > sqrt(const Jet< T, N > &f)
static constexpr double k
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
gtsam
Author(s): 
autogenerated on Wed May 28 2025 03:00:56