14 #include "../Util/CompInfo.h" 26 template <
typename Scalar =
double>
46 std::vector<std::pair<Index, Index> >
m_permc;
65 m_colptr.reserve(m_n);
68 for (Index
i = 0;
i <
m_n;
i++)
70 m_colptr.push_back(head);
80 for (Index
j = 0;
j <
m_n;
j++)
82 const Scalar* begin = &mat.coeffRef(
j,
j);
83 const Index
len = m_n -
j;
91 for (Index
i = 0;
i <
m_n;
i++)
93 for (Index
j =
i;
j <
m_n;
j++, dest++)
95 *dest = mat.coeff(
i,
j);
105 for (Index
i = 0;
i <
m_n;
i++)
108 const Index
perm = (m_perm[
i] >= 0) ? (m_perm[
i]) : (-m_perm[
i] - 1);
110 m_permc.push_back(std::make_pair(i, perm));
134 for (Index
j = k + 1;
j < r;
j++, src++)
155 m_perm[k] = -m_perm[k] - 1;
156 m_perm[k + 1] = -m_perm[k + 1] - 1;
166 for (Index
j = c1;
j <=
c2;
j++)
189 if (lambda < abs_elem)
214 for (Index
j = k;
j < r;
j++)
217 if (sigma < abs_elem)
241 if (abs_akk < alpha * lambda)
246 if (sigma * abs_akk < alpha * lambda * lambda)
248 if (abs_akk >= alpha * sigma)
325 const Index ldim = m_n - k - 1;
326 MapVec
l(lptr, ldim);
327 for (Index
j = 0;
j < ldim;
j++)
346 if (e11 * e22 - e21 * e21 ==
Scalar(0))
354 const Index ldim = m_n - k - 2;
355 MapVec
l1(l1ptr, ldim),
l2(l2ptr, ldim);
358 X.col(0).noalias() =
l1 * e11 + l2 * e21;
359 X.col(1).noalias() =
l1 * e21 + l2 * e22;
362 for (Index
j = 0;
j < ldim;
j++)
364 MapVec(
col_pointer(
j + k + 2), ldim -
j).noalias() -= (X.col(0).tail(ldim -
j) * l1ptr[
j] + X.col(1).tail(ldim -
j) * l2ptr[
j]);
368 l1.noalias() = X.col(0);
369 l2.noalias() = X.col(1);
391 if (m_n != mat.cols())
392 throw std::invalid_argument(
"BKLDLT: matrix must be square");
394 m_perm.setLinSpaced(m_n, 0, m_n - 1);
398 m_data.
resize((m_n * (m_n + 1)) / 2);
404 for (k = 0; k < m_n - 1; k++)
443 throw std::logic_error(
"BKLDLT: need to call compute() first");
449 Index npermc = m_permc.size();
450 for (Index
i = 0;
i < npermc;
i++)
457 const Index
end = (m_perm[m_n - 1] < 0) ? (m_n - 3) : (m_n - 2);
458 for (Index
i = 0;
i <=
end;
i++)
460 const Index b1size = m_n -
i - 1;
461 const Index b2size = b1size - 1;
464 MapConstVec
l(&
coeff(i + 1, i), b1size);
465 res.segment(i + 1, b1size).noalias() -= l * x[
i];
469 MapConstVec
l1(&
coeff(i + 2, i), b2size);
470 MapConstVec
l2(&
coeff(i + 2, i + 1), b2size);
471 res.segment(i + 2, b2size).noalias() -= (l1 * x[
i] + l2 * x[i + 1]);
477 for (Index
i = 0;
i <
m_n;
i++)
487 const Scalar wi = x[
i] * e11 + x[
i + 1] * e21;
488 x[
i + 1] = x[
i] * e21 + x[
i + 1] * e22;
496 Index
i = (m_perm[m_n - 1] < 0) ? (m_n - 3) : (m_n - 2);
499 const Index ldim = m_n - i - 1;
500 MapConstVec
l(&
coeff(i + 1, i), ldim);
501 x[
i] -= res.segment(i + 1, ldim).dot(l);
505 MapConstVec
l2(&
coeff(i + 1, i - 1), ldim);
506 x[i - 1] -= res.segment(i + 1, ldim).dot(l2);
512 for (Index i = npermc - 1; i >= 0; i--)
518 Vector
solve(ConstGenericVector&
b)
const
Vector solve(ConstGenericVector &b) const
Eigen::Ref< Vector > GenericVector
void compute(ConstGenericMatrix &mat, int uplo=Eigen::Lower, const Scalar &shift=Scalar(0))
std::vector< std::pair< Index, Index > > m_permc
const Eigen::Ref< const Vector > ConstGenericVector
Scalar find_sigma(Index k, Index r, Index &p)
A matrix or vector expression mapping an existing array of data.
void solve_inplace(GenericVector b) const
static const double sigma
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar * data() const
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Eigen::Ref< Matrix > GenericMatrix
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
bool permutate_mat(Index k, const Scalar &alpha)
Computation was successful.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Scalar * col_pointer(Index k)
int gaussian_elimination_1x1(Index k)
void inverse_inplace_2x2(Scalar &e11, Scalar &e21, Scalar &e22) const
const Eigen::Ref< const Matrix > ConstGenericMatrix
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
Scalar & coeff(Index i, Index j)
Eigen::Matrix< Index, Eigen::Dynamic, 1 > IntVector
static const Line3 l(Rot3(), 1, 1)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index rows, Index cols)
constexpr int first(int i)
Implementation details for constexpr functions.
const Scalar & diag_coeff(Index i) const
void compress_permutation()
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
void interchange_rows(Index r1, Index r2, Index c1, Index c2)
idx_t idx_t idx_t idx_t idx_t * perm
Scalar & diag_coeff(Index i)
Scalar find_lambda(Index k, Index &r)
void copy_data(ConstGenericMatrix &mat, int uplo, const Scalar &shift)
void pivoting_2x2(Index k, Index r, Index p)
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
A matrix or vector expression mapping an existing expression.
void pivoting_1x1(Index k, Index r)
EIGEN_DEVICE_FUNC SegmentReturnType head(Index n)
This is the const version of head(Index).
Eigen::Map< const Vector > MapConstVec
std::vector< Scalar * > m_colptr
Eigen::Map< Vector > MapVec
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
int gaussian_elimination_2x2(Index k)
void swap(mpfr::mpreal &x, mpfr::mpreal &y)
BKLDLT(ConstGenericMatrix &mat, int uplo=Eigen::Lower, const Scalar &shift=Scalar(0))