SimplicialCholesky_impl.h
Go to the documentation of this file.
1 // This file is part of Eigen, a lightweight C++ template library
2 // for linear algebra.
3 //
4 // Copyright (C) 2008-2012 Gael Guennebaud <gael.guennebaud@inria.fr>
5 //
6 // This Source Code Form is subject to the terms of the Mozilla
7 // Public License v. 2.0. If a copy of the MPL was not distributed
8 // with this file, You can obtain one at http://mozilla.org/MPL/2.0/.
9 
10 /*
11 NOTE: these functions have been adapted from the LDL library:
12 
13 LDL Copyright (c) 2005 by Timothy A. Davis. All Rights Reserved.
14 
15 The author of LDL, Timothy A. Davis., has executed a license with Google LLC
16 to permit distribution of this code and derivative works as part of Eigen under
17 the Mozilla Public License v. 2.0, as stated at the top of this file.
18  */
19 
20 #ifndef EIGEN_SIMPLICIAL_CHOLESKY_IMPL_H
21 #define EIGEN_SIMPLICIAL_CHOLESKY_IMPL_H
22 
23 namespace Eigen {
24 
25 template<typename Derived>
27 {
28  const StorageIndex size = StorageIndex(ap.rows());
29  m_matrix.resize(size, size);
30  m_parent.resize(size);
31  m_nonZerosPerCol.resize(size);
32 
34 
35  for(StorageIndex k = 0; k < size; ++k)
36  {
37  /* L(k,:) pattern: all nodes reachable in etree from nz in A(0:k-1,k) */
38  m_parent[k] = -1; /* parent of k is not yet known */
39  tags[k] = k; /* mark node k as visited */
40  m_nonZerosPerCol[k] = 0; /* count of nonzeros in column k of L */
41  for(typename CholMatrixType::InnerIterator it(ap,k); it; ++it)
42  {
43  StorageIndex i = it.index();
44  if(i < k)
45  {
46  /* follow path from i to root of etree, stop at flagged node */
47  for(; tags[i] != k; i = m_parent[i])
48  {
49  /* find parent of i if not yet determined */
50  if (m_parent[i] == -1)
51  m_parent[i] = k;
52  m_nonZerosPerCol[i]++; /* L (k,i) is nonzero */
53  tags[i] = k; /* mark i as visited */
54  }
55  }
56  }
57  }
58 
59  /* construct Lp index array from m_nonZerosPerCol column counts */
60  StorageIndex* Lp = m_matrix.outerIndexPtr();
61  Lp[0] = 0;
62  for(StorageIndex k = 0; k < size; ++k)
63  Lp[k+1] = Lp[k] + m_nonZerosPerCol[k] + (doLDLT ? 0 : 1);
64 
65  m_matrix.resizeNonZeros(Lp[size]);
66 
67  m_isInitialized = true;
68  m_info = Success;
69  m_analysisIsOk = true;
70  m_factorizationIsOk = false;
71 }
72 
73 
74 template<typename Derived>
75 template<bool DoLDLT>
77 {
78  using std::sqrt;
79 
80  eigen_assert(m_analysisIsOk && "You must first call analyzePattern()");
81  eigen_assert(ap.rows()==ap.cols());
82  eigen_assert(m_parent.size()==ap.rows());
83  eigen_assert(m_nonZerosPerCol.size()==ap.rows());
84 
85  const StorageIndex size = StorageIndex(ap.rows());
86  const StorageIndex* Lp = m_matrix.outerIndexPtr();
87  StorageIndex* Li = m_matrix.innerIndexPtr();
88  Scalar* Lx = m_matrix.valuePtr();
89 
93 
94  bool ok = true;
95  m_diag.resize(DoLDLT ? size : 0);
96 
97  for(StorageIndex k = 0; k < size; ++k)
98  {
99  // compute nonzero pattern of kth row of L, in topological order
100  y[k] = Scalar(0); // Y(0:k) is now all zero
101  StorageIndex top = size; // stack for pattern is empty
102  tags[k] = k; // mark node k as visited
103  m_nonZerosPerCol[k] = 0; // count of nonzeros in column k of L
104  for(typename CholMatrixType::InnerIterator it(ap,k); it; ++it)
105  {
106  StorageIndex i = it.index();
107  if(i <= k)
108  {
109  y[i] += numext::conj(it.value()); /* scatter A(i,k) into Y (sum duplicates) */
110  Index len;
111  for(len = 0; tags[i] != k; i = m_parent[i])
112  {
113  pattern[len++] = i; /* L(k,i) is nonzero */
114  tags[i] = k; /* mark i as visited */
115  }
116  while(len > 0)
117  pattern[--top] = pattern[--len];
118  }
119  }
120 
121  /* compute numerical values kth row of L (a sparse triangular solve) */
122 
123  RealScalar d = numext::real(y[k]) * m_shiftScale + m_shiftOffset; // get D(k,k), apply the shift function, and clear Y(k)
124  y[k] = Scalar(0);
125  for(; top < size; ++top)
126  {
127  Index i = pattern[top]; /* pattern[top:n-1] is pattern of L(:,k) */
128  Scalar yi = y[i]; /* get and clear Y(i) */
129  y[i] = Scalar(0);
130 
131  /* the nonzero entry L(k,i) */
132  Scalar l_ki;
133  if(DoLDLT)
134  l_ki = yi / numext::real(m_diag[i]);
135  else
136  yi = l_ki = yi / Lx[Lp[i]];
137 
138  Index p2 = Lp[i] + m_nonZerosPerCol[i];
139  Index p;
140  for(p = Lp[i] + (DoLDLT ? 0 : 1); p < p2; ++p)
141  y[Li[p]] -= numext::conj(Lx[p]) * yi;
142  d -= numext::real(l_ki * numext::conj(yi));
143  Li[p] = k; /* store L(k,i) in column form of L */
144  Lx[p] = l_ki;
145  ++m_nonZerosPerCol[i]; /* increment count of nonzeros in col i */
146  }
147  if(DoLDLT)
148  {
149  m_diag[k] = d;
150  if(d == RealScalar(0))
151  {
152  ok = false; /* failure, D(k,k) is zero */
153  break;
154  }
155  }
156  else
157  {
158  Index p = Lp[k] + m_nonZerosPerCol[k]++;
159  Li[p] = k ; /* store L(k,k) = sqrt (d) in column k */
160  if(d <= RealScalar(0)) {
161  ok = false; /* failure, matrix is not positive definite */
162  break;
163  }
164  Lx[p] = sqrt(d) ;
165  }
166  }
167 
168  m_info = ok ? Success : NumericalIssue;
169  m_factorizationIsOk = true;
170 }
171 
172 } // end namespace Eigen
173 
174 #endif // EIGEN_SIMPLICIAL_CHOLESKY_IMPL_H
Eigen::SparseMatrix::cols
Index cols() const
Definition: SparseMatrix.h:140
Eigen::NumericalIssue
@ NumericalIssue
Definition: Constants.h:444
Eigen
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
Eigen::SparseMatrix< Scalar, ColMajor, StorageIndex >
Eigen::SimplicialCholeskyBase::factorize_preordered
void factorize_preordered(const CholMatrixType &a)
Definition: SimplicialCholesky_impl.h:76
d
static const double d[K][N]
Definition: igam.h:11
eigen_assert
#define eigen_assert(x)
Definition: Macros.h:1037
Eigen::Success
@ Success
Definition: Constants.h:442
real
float real
Definition: datatypes.h:10
Eigen::SimplicialCholeskyBase::StorageIndex
MatrixType::StorageIndex StorageIndex
Definition: SimplicialCholesky.h:66
ei_declare_aligned_stack_constructed_variable
#define ei_declare_aligned_stack_constructed_variable(TYPE, NAME, SIZE, BUFFER)
Definition: Memory.h:768
size
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
simple::p2
static Point3 p2
Definition: testInitializePose3.cpp:51
Eigen::SimplicialCholeskyBase::RealScalar
MatrixType::RealScalar RealScalar
Definition: SimplicialCholesky.h:65
Eigen::SimplicialCholeskyBase::Scalar
MatrixType::Scalar Scalar
Definition: SimplicialCholesky.h:64
conj
AnnoyingScalar conj(const AnnoyingScalar &x)
Definition: AnnoyingScalar.h:104
y
Scalar * y
Definition: level1_cplx_impl.h:124
RealScalar
NumTraits< Scalar >::Real RealScalar
Definition: bench_gemm.cpp:47
Eigen::SparseMatrix< Scalar, ColMajor, StorageIndex >::InnerIterator
Base::InnerIterator InnerIterator
Definition: SparseMatrix.h:114
Eigen::SimplicialCholeskyBase::analyzePattern_preordered
void analyzePattern_preordered(const CholMatrixType &a, bool doLDLT)
Definition: SimplicialCholesky_impl.h:26
p
float * p
Definition: Tutorial_Map_using.cpp:9
len
size_t len(handle h)
Get the length of a Python object.
Definition: pytypes.h:2399
Eigen::SparseMatrix::rows
Index rows() const
Definition: SparseMatrix.h:138
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Scalar
SCALAR Scalar
Definition: bench_gemm.cpp:46
Eigen::Index
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:74


gtsam
Author(s):
autogenerated on Sat Jun 1 2024 03:03:29