Go to the documentation of this file.
14 #include "../Util/CompInfo.h"
26 template <
typename Scalar =
double>
46 std::vector<std::pair<Index, Index> >
m_permc;
95 *dest =
mat.coeff(
i,
j);
134 for (
Index j = k + 1;
j < r;
j++, src++)
192 r = k + (ptr -
head);
217 if (
sigma < abs_elem)
346 if (e11 * e22 - e21 * e21 ==
Scalar(0))
358 X.col(0).noalias() =
l1 * e11 +
l2 * e21;
359 X.col(1).noalias() =
l1 * e21 +
l2 * e22;
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);
392 throw std::invalid_argument(
"BKLDLT: matrix must be square");
404 for (k = 0; k <
m_n - 1; k++)
443 throw std::logic_error(
"BKLDLT: need to call compute() first");
461 const Index b2size = b1size - 1;
465 res.segment(
i + 1, b1size).noalias() -=
l *
x[
i];
471 res.segment(
i + 2, b2size).noalias() -= (
l1 *
x[
i] +
l2 *
x[
i + 1]);
487 const Scalar wi =
x[
i] * e11 +
x[
i + 1] * e21;
488 x[
i + 1] =
x[
i] * e21 +
x[
i + 1] * e22;
501 x[
i] -=
res.segment(
i + 1, ldim).dot(
l);
506 x[
i - 1] -=
res.segment(
i + 1, ldim).dot(
l2);
512 for (
Index i = npermc - 1;
i >= 0;
i--)
idx_t idx_t idx_t idx_t idx_t * perm
Eigen::Ref< Vector > GenericVector
void inverse_inplace_2x2(Scalar &e11, Scalar &e21, Scalar &e22) const
Scalar find_sigma(Index k, Index r, Index &p)
void solve_inplace(GenericVector b) const
BKLDLT(ConstGenericMatrix &mat, int uplo=Eigen::Lower, const Scalar &shift=Scalar(0))
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)
void compute(ConstGenericMatrix &mat, int uplo=Eigen::Lower, const Scalar &shift=Scalar(0))
std::vector< std::pair< Index, Index > > m_permc
Scalar & coeff(Index i, Index j)
Eigen::Matrix< Index, Eigen::Dynamic, 1 > IntVector
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::Ref< Matrix > GenericMatrix
int gaussian_elimination_1x1(Index k)
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
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)
bool permutate_mat(Index k, const Scalar &alpha)
const typedef Eigen::Ref< const Vector > ConstGenericVector
void pivoting_2x2(Index k, Index r, Index p)
static const Line3 l(Rot3(), 1, 1)
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
void swap(GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &a, GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &b)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE FixedSegmentReturnType< internal::get_fixed_value< NType >::value >::Type head(NType n)
A matrix or vector expression mapping an existing array of data.
Vector solve(ConstGenericVector &b) const
void compress_permutation()
void copy_data(ConstGenericMatrix &mat, int uplo, const Scalar &shift)
A matrix or vector expression mapping an existing expression.
const typedef Eigen::Ref< const Matrix > ConstGenericMatrix
Eigen::Map< const Vector > MapConstVec
Scalar find_lambda(Index k, Index &r)
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE Scalar * data() const
@ SUCCESSFUL
Computation was successful.
void pivoting_1x1(Index k, Index r)
size_t len(handle h)
Get the length of a Python object.
std::vector< Scalar * > m_colptr
Eigen::Map< Vector > MapVec
static const EIGEN_DEPRECATED end_t end
int gaussian_elimination_2x2(Index k)
Jet< T, N > sqrt(const Jet< T, N > &f)
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:01:55