Template Struct Ldlt

Struct Documentation

template<typename T>
struct Ldlt

Wrapper class that handles an allocated LDLT decomposition, with an applied permutation. When provided with a matrix A, this internally stores a lower triangular matrix with unit diagonal L, a vector D, and a permutation P such that A = P.T L diag(D) L.T P.

Example usage:

#include <proxsuite/linalg/dense/ldlt.hpp>
#include <proxsuite/linalg/veg/util/dynstack_alloc.hpp>

auto main() -> int {
        constexpr auto DYN = Eigen::Dynamic;
        using Matrix = Eigen::Matrix<double, DYN, DYN>;
        using Vector = Eigen::Matrix<double, DYN, 1>;
        using Ldlt = proxsuite::linalg::dense::Ldlt<double>;
        using proxsuite::linalg::veg::dynstack::StackReq;

        // allocate a matrix `a`
        auto a0 = Matrix{
                        2,
                        2,
        };

        // workspace memory requirements
        auto req =
                        Ldlt::factorize_req(2) |          // initial
factorization of dim 2 Ldlt::insert_block_at_req(2, 1) | // or 1 insertion to
matrix of dim 2 Ldlt::delete_at_req(3, 2) |       // or 2 deletions from matrix
of dim 3 Ldlt::solve_in_place_req(1);      // or solve in place with dim 1

        VEG_MAKE_STACK(stack, req);

        Ldlt ldl;

        // fill up the lower triangular part
        // matrix is
        // 1.0 2.0
        // 2.0 3.0
        a0(0, 0) = 1.0;
        a0(1, 0) = 2.0;
        a0(1, 1) = 3.0;

        ldl.factorize(a0, stack);

        // add one column at the index 1
        // matrix is
        // 1.0 4.0 2.0
        // 4.0 5.0 6.0
        // 2.0 6.0 3.0
        auto c = Matrix{3, 1};
        c(0, 0) = 4.0;
        c(1, 0) = 5.0;
        c(2, 0) = 6.0;
        ldl.insert_block_at(1, c, stack);

        // then delete two rows and columns at indices 0 and 2
        // matrix is
        // 5.0
        proxsuite::linalg::veg::isize const indices[] = {0, 2};
        ldl.delete_at(indices, 2, stack);

        auto rhs = Vector{1};
        rhs[0] = 5.0;

        ldl.solve_in_place(rhs, stack);
        VEG_ASSERT(rhs[0] == 1.0);
}

Public Functions

Ldlt() = default

Default constructor, initialized with a 0×0 empty matrix.

inline void reserve_uninit(isize cap) noexcept

Reserves enough internal storage for a matrix A of size at least cap×cap. This operation invalidates the existing decomposition.

Parameters:

cap – new capacity

inline void reserve(isize cap) noexcept

Reserves enough internal storage for a matrix A of size at least cap×cap. This operation preserves the existing decomposition.

Parameters:

cap – new capacity

inline void delete_at(isize const *indices, isize r, proxsuite::linalg::veg::dynstack::DynStackMut stack)

Given an LDLT decomposition for a matrix A, this computes the decomposition for the matrix A with r columns and rows removed, as indicated by the indices indices[0], ..., indices[r-1].

Parameters:
  • indices – pointer to the array of indices to be deleted

  • r – number of the indices to be deleted

  • stack – workspace memory stack

inline auto choose_insertion_position(isize i, Eigen::Ref<Vec const> a) -> isize
inline void insert_block_at(isize i, Eigen::Ref<ColMat const> a, proxsuite::linalg::veg::dynstack::DynStackMut stack)

Given an LDLT decomposition for a matrix A, this computes the decomposition for the matrix A with extra r columns and rows from a added at the index i.

Parameters:
  • i – index where the block should be inserted

  • a – matrix of the new columns that are inserted

  • stack – workspace memory stack

inline void diagonal_update_clobber_indices(isize *indices, isize r, Eigen::Ref<Vec const> alpha, proxsuite::linalg::veg::dynstack::DynStackMut stack)

Given an LDLT decomposition for a matrix A, this computes the decomposition for the matrix A with the vector alpha added to a diagonal subset, as specified by the provided indices.

The values pointed at by indices are unspecified after a call to this function.

Parameters:
  • indices – pointer to the array of indices of diagonal elements that are updated

  • r – number of the indices to be updated

  • stack – workspace memory stack

inline void rank_r_update(Eigen::Ref<ColMat const> w, Eigen::Ref<Vec const> alpha, proxsuite::linalg::veg::dynstack::DynStackMut stack)

Given an LDLT decomposition for a matrix A, this computes the decomposition for the rank-updated matrix A + w×diag(alpha)×w.T

Parameters:
  • w – rank update matrix

  • alpha – rank update diagonal vector

  • stack – workspace memory stack

inline auto dim() const noexcept -> isize

Returns the dimension of the stored decomposition.

inline auto ld_col() const noexcept -> Eigen::Map<ColMat const, Eigen::Unaligned, Eigen::OuterStride<DYN>>
inline auto ld_col_mut() noexcept -> Eigen::Map<ColMat, Eigen::Unaligned, Eigen::OuterStride<DYN>>
inline auto ld_row() const noexcept -> Eigen::Map<RowMat const, Eigen::Unaligned, Eigen::OuterStride<DYN>>
inline auto ld_row_mut() noexcept -> Eigen::Map<RowMat, Eigen::Unaligned, Eigen::OuterStride<DYN>>
inline auto l() const noexcept -> LView
inline auto l_mut() noexcept -> LViewMut
inline auto lt() const noexcept -> LTView
inline auto lt_mut() noexcept -> LTViewMut
inline auto d() const noexcept -> DView
inline auto d_mut() noexcept -> DViewMut
inline auto p() const -> Perm
inline auto pt() const -> Perm
inline void factorize(Eigen::Ref<ColMat const> mat, proxsuite::linalg::veg::dynstack::DynStackMut stack)

Computes the decomposition of a given matrix A. The matrix is interpreted as a symmetric matrix and only the lower triangular part of A is accessed.

Parameters:
  • mat – matrix whose decomposition should be computed

  • stack – workspace memory stack

inline void solve_in_place(Eigen::Ref<Vec> rhs, proxsuite::linalg::veg::dynstack::DynStackMut stack) const

Solves the system A×x = rhs, and stores the result in rhs.

Parameters:
  • rhs – right hand side of the linear system

  • stack – workspace memory stack

inline auto dbg_reconstructed_matrix_internal() const -> ColMat
inline auto dbg_reconstructed_matrix() const -> ColMat

Public Static Functions

static inline auto rank_r_update_req(isize n, isize r) noexcept -> proxsuite::linalg::veg::dynstack::StackReq

Returns the memory storage requirements for performing a rank k update on a matrix with size at most n×n, with k r.

Parameters:
  • n – maximum dimension of the matrix

  • r – maximum number of simultaneous rank updates

static inline auto delete_at_req(isize n, isize r) noexcept -> proxsuite::linalg::veg::dynstack::StackReq

Returns the memory storage requirements for deleting at most r rows and columns from a matrix with size at most n×n.

Parameters:
  • n – maximum dimension of the matrix

  • r – maximum number of rows to be deleted

static inline auto insert_block_at_req(isize n, isize r) noexcept -> proxsuite::linalg::veg::dynstack::StackReq

Returns the memory storage requirements for inserting at most r rows and columns from a matrix with size at most n×n.

Parameters:
  • n – maximum dimension of the matrix

  • r – maximum number of rows to be inserted

static inline auto diagonal_update_req(isize n, isize r) noexcept -> proxsuite::linalg::veg::dynstack::StackReq

Returns the memory storage requirements for a diagonal subsection update with size at most r, in a matrix with size at most n×n.

Parameters:
  • n – maximum dimension of the matrix

  • r – maximum size of diagonal subsection that gets updated

static inline auto factorize_req(isize n) -> proxsuite::linalg::veg::dynstack::StackReq

Returns the memory storage requirements for a factorization of a matrix of size at most n×n

Parameters:

n – maximum dimension of the matrix

static inline auto solve_in_place_req(isize n) -> proxsuite::linalg::veg::dynstack::StackReq

Returns the memory storage requirements for solving a linear system with a decomposition of dimension at most n

Parameters:

n – maximum dimension of the matrix