Amd.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) 2010 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: this routine has been adapted from the CSparse library:
12 
13 Copyright (c) 2006, Timothy A. Davis.
14 http://www.suitesparse.com
15 
16 The author of CSparse, Timothy A. Davis., has executed a license with Google LLC
17 to permit distribution of this code and derivative works as part of Eigen under
18 the Mozilla Public License v. 2.0, as stated at the top of this file.
19 */
20 
21 #ifndef EIGEN_SPARSE_AMD_H
22 #define EIGEN_SPARSE_AMD_H
23 
24 namespace Eigen {
25 
26 namespace internal {
27 
28 template<typename T> inline T amd_flip(const T& i) { return -i-2; }
29 template<typename T> inline T amd_unflip(const T& i) { return i<0 ? amd_flip(i) : i; }
30 template<typename T0, typename T1> inline bool amd_marked(const T0* w, const T1& j) { return w[j]<0; }
31 template<typename T0, typename T1> inline void amd_mark(const T0* w, const T1& j) { return w[j] = amd_flip(w[j]); }
32 
33 /* clear w */
34 template<typename StorageIndex>
35 static StorageIndex cs_wclear (StorageIndex mark, StorageIndex lemax, StorageIndex *w, StorageIndex n)
36 {
37  StorageIndex k;
38  if(mark < 2 || (mark + lemax < 0))
39  {
40  for(k = 0; k < n; k++)
41  if(w[k] != 0)
42  w[k] = 1;
43  mark = 2;
44  }
45  return (mark); /* at this point, w[0..n-1] < mark holds */
46 }
47 
48 /* depth-first search and postorder of a tree rooted at node j */
49 template<typename StorageIndex>
50 StorageIndex cs_tdfs(StorageIndex j, StorageIndex k, StorageIndex *head, const StorageIndex *next, StorageIndex *post, StorageIndex *stack)
51 {
52  StorageIndex i, p, top = 0;
53  if(!head || !next || !post || !stack) return (-1); /* check inputs */
54  stack[0] = j; /* place j on the stack */
55  while (top >= 0) /* while (stack is not empty) */
56  {
57  p = stack[top]; /* p = top of stack */
58  i = head[p]; /* i = youngest child of p */
59  if(i == -1)
60  {
61  top--; /* p has no unordered children left */
62  post[k++] = p; /* node p is the kth postordered node */
63  }
64  else
65  {
66  head[p] = next[i]; /* remove i from children of p */
67  stack[++top] = i; /* start dfs on child node i */
68  }
69  }
70  return k;
71 }
72 
73 
83 template<typename Scalar, typename StorageIndex>
85 {
86  using std::sqrt;
87 
88  StorageIndex d, dk, dext, lemax = 0, e, elenk, eln, i, j, k, k1,
89  k2, k3, jlast, ln, dense, nzmax, mindeg = 0, nvi, nvj, nvk, mark, wnvi,
90  ok, nel = 0, p, p1, p2, p3, p4, pj, pk, pk1, pk2, pn, q, t, h;
91 
92  StorageIndex n = StorageIndex(C.cols());
93  dense = std::max<StorageIndex> (16, StorageIndex(10 * sqrt(double(n)))); /* find dense threshold */
94  dense = (std::min)(n-2, dense);
95 
96  StorageIndex cnz = StorageIndex(C.nonZeros());
97  perm.resize(n+1);
98  t = cnz + cnz/5 + 2*n; /* add elbow room to C */
99  C.resizeNonZeros(t);
100 
101  // get workspace
102  ei_declare_aligned_stack_constructed_variable(StorageIndex,W,8*(n+1),0);
103  StorageIndex* len = W;
104  StorageIndex* nv = W + (n+1);
105  StorageIndex* next = W + 2*(n+1);
106  StorageIndex* head = W + 3*(n+1);
107  StorageIndex* elen = W + 4*(n+1);
108  StorageIndex* degree = W + 5*(n+1);
109  StorageIndex* w = W + 6*(n+1);
110  StorageIndex* hhead = W + 7*(n+1);
111  StorageIndex* last = perm.indices().data(); /* use P as workspace for last */
112 
113  /* --- Initialize quotient graph ---------------------------------------- */
114  StorageIndex* Cp = C.outerIndexPtr();
115  StorageIndex* Ci = C.innerIndexPtr();
116  for(k = 0; k < n; k++)
117  len[k] = Cp[k+1] - Cp[k];
118  len[n] = 0;
119  nzmax = t;
120 
121  for(i = 0; i <= n; i++)
122  {
123  head[i] = -1; // degree list i is empty
124  last[i] = -1;
125  next[i] = -1;
126  hhead[i] = -1; // hash list i is empty
127  nv[i] = 1; // node i is just one node
128  w[i] = 1; // node i is alive
129  elen[i] = 0; // Ek of node i is empty
130  degree[i] = len[i]; // degree of node i
131  }
132  mark = internal::cs_wclear<StorageIndex>(0, 0, w, n); /* clear w */
133 
134  /* --- Initialize degree lists ------------------------------------------ */
135  for(i = 0; i < n; i++)
136  {
137  bool has_diag = false;
138  for(p = Cp[i]; p<Cp[i+1]; ++p)
139  if(Ci[p]==i)
140  {
141  has_diag = true;
142  break;
143  }
144 
145  d = degree[i];
146  if(d == 1 && has_diag) /* node i is empty */
147  {
148  elen[i] = -2; /* element i is dead */
149  nel++;
150  Cp[i] = -1; /* i is a root of assembly tree */
151  w[i] = 0;
152  }
153  else if(d > dense || !has_diag) /* node i is dense or has no structural diagonal element */
154  {
155  nv[i] = 0; /* absorb i into element n */
156  elen[i] = -1; /* node i is dead */
157  nel++;
158  Cp[i] = amd_flip (n);
159  nv[n]++;
160  }
161  else
162  {
163  if(head[d] != -1) last[head[d]] = i;
164  next[i] = head[d]; /* put node i in degree list d */
165  head[d] = i;
166  }
167  }
168 
169  elen[n] = -2; /* n is a dead element */
170  Cp[n] = -1; /* n is a root of assembly tree */
171  w[n] = 0; /* n is a dead element */
172 
173  while (nel < n) /* while (selecting pivots) do */
174  {
175  /* --- Select node of minimum approximate degree -------------------- */
176  for(k = -1; mindeg < n && (k = head[mindeg]) == -1; mindeg++) {}
177  if(next[k] != -1) last[next[k]] = -1;
178  head[mindeg] = next[k]; /* remove k from degree list */
179  elenk = elen[k]; /* elenk = |Ek| */
180  nvk = nv[k]; /* # of nodes k represents */
181  nel += nvk; /* nv[k] nodes of A eliminated */
182 
183  /* --- Garbage collection ------------------------------------------- */
184  if(elenk > 0 && cnz + mindeg >= nzmax)
185  {
186  for(j = 0; j < n; j++)
187  {
188  if((p = Cp[j]) >= 0) /* j is a live node or element */
189  {
190  Cp[j] = Ci[p]; /* save first entry of object */
191  Ci[p] = amd_flip (j); /* first entry is now amd_flip(j) */
192  }
193  }
194  for(q = 0, p = 0; p < cnz; ) /* scan all of memory */
195  {
196  if((j = amd_flip (Ci[p++])) >= 0) /* found object j */
197  {
198  Ci[q] = Cp[j]; /* restore first entry of object */
199  Cp[j] = q++; /* new pointer to object j */
200  for(k3 = 0; k3 < len[j]-1; k3++) Ci[q++] = Ci[p++];
201  }
202  }
203  cnz = q; /* Ci[cnz...nzmax-1] now free */
204  }
205 
206  /* --- Construct new element ---------------------------------------- */
207  dk = 0;
208  nv[k] = -nvk; /* flag k as in Lk */
209  p = Cp[k];
210  pk1 = (elenk == 0) ? p : cnz; /* do in place if elen[k] == 0 */
211  pk2 = pk1;
212  for(k1 = 1; k1 <= elenk + 1; k1++)
213  {
214  if(k1 > elenk)
215  {
216  e = k; /* search the nodes in k */
217  pj = p; /* list of nodes starts at Ci[pj]*/
218  ln = len[k] - elenk; /* length of list of nodes in k */
219  }
220  else
221  {
222  e = Ci[p++]; /* search the nodes in e */
223  pj = Cp[e];
224  ln = len[e]; /* length of list of nodes in e */
225  }
226  for(k2 = 1; k2 <= ln; k2++)
227  {
228  i = Ci[pj++];
229  if((nvi = nv[i]) <= 0) continue; /* node i dead, or seen */
230  dk += nvi; /* degree[Lk] += size of node i */
231  nv[i] = -nvi; /* negate nv[i] to denote i in Lk*/
232  Ci[pk2++] = i; /* place i in Lk */
233  if(next[i] != -1) last[next[i]] = last[i];
234  if(last[i] != -1) /* remove i from degree list */
235  {
236  next[last[i]] = next[i];
237  }
238  else
239  {
240  head[degree[i]] = next[i];
241  }
242  }
243  if(e != k)
244  {
245  Cp[e] = amd_flip (k); /* absorb e into k */
246  w[e] = 0; /* e is now a dead element */
247  }
248  }
249  if(elenk != 0) cnz = pk2; /* Ci[cnz...nzmax] is free */
250  degree[k] = dk; /* external degree of k - |Lk\i| */
251  Cp[k] = pk1; /* element k is in Ci[pk1..pk2-1] */
252  len[k] = pk2 - pk1;
253  elen[k] = -2; /* k is now an element */
254 
255  /* --- Find set differences ----------------------------------------- */
256  mark = internal::cs_wclear<StorageIndex>(mark, lemax, w, n); /* clear w if necessary */
257  for(pk = pk1; pk < pk2; pk++) /* scan 1: find |Le\Lk| */
258  {
259  i = Ci[pk];
260  if((eln = elen[i]) <= 0) continue;/* skip if elen[i] empty */
261  nvi = -nv[i]; /* nv[i] was negated */
262  wnvi = mark - nvi;
263  for(p = Cp[i]; p <= Cp[i] + eln - 1; p++) /* scan Ei */
264  {
265  e = Ci[p];
266  if(w[e] >= mark)
267  {
268  w[e] -= nvi; /* decrement |Le\Lk| */
269  }
270  else if(w[e] != 0) /* ensure e is a live element */
271  {
272  w[e] = degree[e] + wnvi; /* 1st time e seen in scan 1 */
273  }
274  }
275  }
276 
277  /* --- Degree update ------------------------------------------------ */
278  for(pk = pk1; pk < pk2; pk++) /* scan2: degree update */
279  {
280  i = Ci[pk]; /* consider node i in Lk */
281  p1 = Cp[i];
282  p2 = p1 + elen[i] - 1;
283  pn = p1;
284  for(h = 0, d = 0, p = p1; p <= p2; p++) /* scan Ei */
285  {
286  e = Ci[p];
287  if(w[e] != 0) /* e is an unabsorbed element */
288  {
289  dext = w[e] - mark; /* dext = |Le\Lk| */
290  if(dext > 0)
291  {
292  d += dext; /* sum up the set differences */
293  Ci[pn++] = e; /* keep e in Ei */
294  h += e; /* compute the hash of node i */
295  }
296  else
297  {
298  Cp[e] = amd_flip (k); /* aggressive absorb. e->k */
299  w[e] = 0; /* e is a dead element */
300  }
301  }
302  }
303  elen[i] = pn - p1 + 1; /* elen[i] = |Ei| */
304  p3 = pn;
305  p4 = p1 + len[i];
306  for(p = p2 + 1; p < p4; p++) /* prune edges in Ai */
307  {
308  j = Ci[p];
309  if((nvj = nv[j]) <= 0) continue; /* node j dead or in Lk */
310  d += nvj; /* degree(i) += |j| */
311  Ci[pn++] = j; /* place j in node list of i */
312  h += j; /* compute hash for node i */
313  }
314  if(d == 0) /* check for mass elimination */
315  {
316  Cp[i] = amd_flip (k); /* absorb i into k */
317  nvi = -nv[i];
318  dk -= nvi; /* |Lk| -= |i| */
319  nvk += nvi; /* |k| += nv[i] */
320  nel += nvi;
321  nv[i] = 0;
322  elen[i] = -1; /* node i is dead */
323  }
324  else
325  {
326  degree[i] = std::min<StorageIndex> (degree[i], d); /* update degree(i) */
327  Ci[pn] = Ci[p3]; /* move first node to end */
328  Ci[p3] = Ci[p1]; /* move 1st el. to end of Ei */
329  Ci[p1] = k; /* add k as 1st element in of Ei */
330  len[i] = pn - p1 + 1; /* new len of adj. list of node i */
331  h %= n; /* finalize hash of i */
332  next[i] = hhead[h]; /* place i in hash bucket */
333  hhead[h] = i;
334  last[i] = h; /* save hash of i in last[i] */
335  }
336  } /* scan2 is done */
337  degree[k] = dk; /* finalize |Lk| */
338  lemax = std::max<StorageIndex>(lemax, dk);
339  mark = internal::cs_wclear<StorageIndex>(mark+lemax, lemax, w, n); /* clear w */
340 
341  /* --- Supernode detection ------------------------------------------ */
342  for(pk = pk1; pk < pk2; pk++)
343  {
344  i = Ci[pk];
345  if(nv[i] >= 0) continue; /* skip if i is dead */
346  h = last[i]; /* scan hash bucket of node i */
347  i = hhead[h];
348  hhead[h] = -1; /* hash bucket will be empty */
349  for(; i != -1 && next[i] != -1; i = next[i], mark++)
350  {
351  ln = len[i];
352  eln = elen[i];
353  for(p = Cp[i]+1; p <= Cp[i] + ln-1; p++) w[Ci[p]] = mark;
354  jlast = i;
355  for(j = next[i]; j != -1; ) /* compare i with all j */
356  {
357  ok = (len[j] == ln) && (elen[j] == eln);
358  for(p = Cp[j] + 1; ok && p <= Cp[j] + ln - 1; p++)
359  {
360  if(w[Ci[p]] != mark) ok = 0; /* compare i and j*/
361  }
362  if(ok) /* i and j are identical */
363  {
364  Cp[j] = amd_flip (i); /* absorb j into i */
365  nv[i] += nv[j];
366  nv[j] = 0;
367  elen[j] = -1; /* node j is dead */
368  j = next[j]; /* delete j from hash bucket */
369  next[jlast] = j;
370  }
371  else
372  {
373  jlast = j; /* j and i are different */
374  j = next[j];
375  }
376  }
377  }
378  }
379 
380  /* --- Finalize new element------------------------------------------ */
381  for(p = pk1, pk = pk1; pk < pk2; pk++) /* finalize Lk */
382  {
383  i = Ci[pk];
384  if((nvi = -nv[i]) <= 0) continue;/* skip if i is dead */
385  nv[i] = nvi; /* restore nv[i] */
386  d = degree[i] + dk - nvi; /* compute external degree(i) */
387  d = std::min<StorageIndex> (d, n - nel - nvi);
388  if(head[d] != -1) last[head[d]] = i;
389  next[i] = head[d]; /* put i back in degree list */
390  last[i] = -1;
391  head[d] = i;
392  mindeg = std::min<StorageIndex> (mindeg, d); /* find new minimum degree */
393  degree[i] = d;
394  Ci[p++] = i; /* place i in Lk */
395  }
396  nv[k] = nvk; /* # nodes absorbed into k */
397  if((len[k] = p-pk1) == 0) /* length of adj list of element k*/
398  {
399  Cp[k] = -1; /* k is a root of the tree */
400  w[k] = 0; /* k is now a dead element */
401  }
402  if(elenk != 0) cnz = p; /* free unused space in Lk */
403  }
404 
405  /* --- Postordering ----------------------------------------------------- */
406  for(i = 0; i < n; i++) Cp[i] = amd_flip (Cp[i]);/* fix assembly tree */
407  for(j = 0; j <= n; j++) head[j] = -1;
408  for(j = n; j >= 0; j--) /* place unordered nodes in lists */
409  {
410  if(nv[j] > 0) continue; /* skip if j is an element */
411  next[j] = head[Cp[j]]; /* place j in list of its parent */
412  head[Cp[j]] = j;
413  }
414  for(e = n; e >= 0; e--) /* place elements in lists */
415  {
416  if(nv[e] <= 0) continue; /* skip unless e is an element */
417  if(Cp[e] != -1)
418  {
419  next[e] = head[Cp[e]]; /* place e in list of its parent */
420  head[Cp[e]] = e;
421  }
422  }
423  for(k = 0, i = 0; i <= n; i++) /* postorder the assembly tree */
424  {
425  if(Cp[i] == -1) k = internal::cs_tdfs<StorageIndex>(i, k, head, next, perm.indices().data(), w);
426  }
427 
428  perm.indices().conservativeResize(n);
429 }
430 
431 } // namespace internal
432 
433 } // end namespace Eigen
434 
435 #endif // EIGEN_SPARSE_AMD_H
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
perm
idx_t idx_t idx_t idx_t idx_t * perm
Definition: include/metis.h:223
Eigen
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
Eigen::SparseMatrix< Scalar, ColMajor, StorageIndex >
Eigen::internal::cs_wclear
static StorageIndex cs_wclear(StorageIndex mark, StorageIndex lemax, StorageIndex *w, StorageIndex n)
Definition: Amd.h:35
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
Eigen::internal::cs_tdfs
StorageIndex cs_tdfs(StorageIndex j, StorageIndex k, StorageIndex *head, const StorageIndex *next, StorageIndex *post, StorageIndex *stack)
Definition: Amd.h:50
Eigen::internal::amd_marked
bool amd_marked(const T0 *w, const T1 &j)
Definition: Amd.h:30
h
const double h
Definition: testSimpleHelicopter.cpp:19
ei_declare_aligned_stack_constructed_variable
#define ei_declare_aligned_stack_constructed_variable(TYPE, NAME, SIZE, BUFFER)
Definition: Memory.h:768
Eigen::last
static const symbolic::SymbolExpr< internal::symbolic_last_tag > last
Definition: IndexedViewHelper.h:38
n
int n
Definition: BiCGSTAB_simple.cpp:1
simple::p2
static Point3 p2
Definition: testInitializePose3.cpp:51
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
Eigen::internal::amd_flip
T amd_flip(const T &i)
Definition: Amd.h:28
Eigen::numext::q
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:1984
Eigen::internal::amd_unflip
T amd_unflip(const T &i)
Definition: Amd.h:29
k1
double k1(double x)
Definition: k1.c:133
gtsam::stack
Matrix stack(size_t nrMatrices,...)
Definition: Matrix.cpp:395
degree
const double degree
Definition: SimpleRotation.cpp:59
simple::p3
static Point3 p3
Definition: testInitializePose3.cpp:53
Eigen::Triplet< double >
head
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE FixedSegmentReturnType< internal::get_fixed_value< NType >::value >::Type head(NType n)
Definition: BlockMethods.h:1208
p1
Vector3f p1
Definition: MatrixBase_all.cpp:2
p4
KeyInt p4(x4, 4)
C
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:50
Eigen::PlainObjectBase::cols
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT
Definition: PlainObjectBase.h:145
gtsam::symbol_shorthand::W
Key W(std::uint64_t j)
Definition: inference/Symbol.h:170
Eigen::PermutationMatrix< Dynamic, Dynamic, StorageIndex >
p
float * p
Definition: Tutorial_Map_using.cpp:9
Eigen::internal::amd_mark
void amd_mark(const T0 *w, const T1 &j)
Definition: Amd.h:31
Eigen::internal::minimum_degree_ordering
void minimum_degree_ordering(SparseMatrix< Scalar, ColMajor, StorageIndex > &C, PermutationMatrix< Dynamic, Dynamic, StorageIndex > &perm)
Definition: Amd.h:84
min
#define min(a, b)
Definition: datatypes.h:19
len
size_t len(handle h)
Get the length of a Python object.
Definition: pytypes.h:2399
internal
Definition: BandTriangularSolver.h:13
T1
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
align_3::t
Point2 t(10, 10)
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


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