21 #ifndef EIGEN_SPARSE_AMD_H 22 #define EIGEN_SPARSE_AMD_H 28 template<
typename T>
inline T amd_flip(
const T&
i) {
return -i-2; }
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]); }
34 template<
typename StorageIndex>
35 static StorageIndex
cs_wclear (StorageIndex mark, StorageIndex lemax, StorageIndex *
w, StorageIndex
n)
38 if(mark < 2 || (mark + lemax < 0))
40 for(k = 0; k <
n; k++)
49 template<
typename StorageIndex>
50 StorageIndex
cs_tdfs(StorageIndex
j, StorageIndex k, StorageIndex *
head,
const StorageIndex *next, StorageIndex *post, StorageIndex *
stack)
52 StorageIndex
i,
p, top = 0;
53 if(!head || !next || !post || !stack)
return (-1);
83 template<
typename Scalar,
typename StorageIndex>
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;
92 StorageIndex
n = StorageIndex(C.
cols());
93 dense = std::max<StorageIndex> (16, StorageIndex(10 *
sqrt(
double(n))));
96 StorageIndex cnz = StorageIndex(C.
nonZeros());
98 t = cnz + cnz/5 + 2*
n;
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);
116 for(k = 0; k <
n; k++)
117 len[k] = Cp[k+1] - Cp[k];
121 for(i = 0; i <=
n; i++)
132 mark = internal::cs_wclear<StorageIndex>(0, 0,
w,
n);
135 for(i = 0; i <
n; i++)
137 bool has_diag =
false;
138 for(
p = Cp[i];
p<Cp[i+1]; ++
p)
146 if(d == 1 && has_diag)
153 else if(d > dense || !has_diag)
163 if(head[d] != -1) last[head[
d]] =
i;
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];
184 if(elenk > 0 && cnz + mindeg >= nzmax)
186 for(j = 0; j <
n; j++)
194 for(q = 0,
p = 0;
p < cnz; )
200 for(k3 = 0; k3 < len[
j]-1; k3++) Ci[q++] = Ci[
p++];
210 pk1 = (elenk == 0) ?
p : cnz;
212 for(k1 = 1; k1 <= elenk + 1; k1++)
226 for(k2 = 1; k2 <= ln; k2++)
229 if((nvi = nv[i]) <= 0)
continue;
233 if(next[i] != -1) last[next[
i]] = last[
i];
236 next[last[
i]] = next[
i];
240 head[degree[
i]] = next[
i];
249 if(elenk != 0) cnz = pk2;
256 mark = internal::cs_wclear<StorageIndex>(mark, lemax,
w,
n);
257 for(pk = pk1; pk < pk2; pk++)
260 if((eln = elen[i]) <= 0)
continue;
263 for(
p = Cp[i];
p <= Cp[
i] + eln - 1;
p++)
272 w[
e] = degree[
e] + wnvi;
278 for(pk = pk1; pk < pk2; pk++)
282 p2 = p1 + elen[
i] - 1;
284 for(h = 0, d = 0,
p = p1;
p <=
p2;
p++)
303 elen[
i] = pn - p1 + 1;
306 for(
p = p2 + 1;
p <
p4;
p++)
309 if((nvj = nv[j]) <= 0)
continue;
326 degree[
i] = std::min<StorageIndex> (degree[
i],
d);
330 len[
i] = pn - p1 + 1;
338 lemax = std::max<StorageIndex>(lemax, dk);
339 mark = internal::cs_wclear<StorageIndex>(mark+lemax, lemax,
w,
n);
342 for(pk = pk1; pk < pk2; pk++)
345 if(nv[i] >= 0)
continue;
349 for(; i != -1 && next[
i] != -1; i = next[
i], mark++)
353 for(
p = Cp[i]+1;
p <= Cp[
i] + ln-1;
p++) w[Ci[
p]] = mark;
355 for(j = next[i]; j != -1; )
357 ok = (len[
j] == ln) && (elen[j] == eln);
358 for(
p = Cp[j] + 1; ok &&
p <= Cp[
j] + ln - 1; p++)
360 if(w[Ci[p]] != mark) ok = 0;
381 for(
p = pk1, pk = pk1; pk < pk2; pk++)
384 if((nvi = -nv[i]) <= 0)
continue;
386 d = degree[
i] + dk - nvi;
387 d = std::min<StorageIndex> (
d, n - nel - nvi);
388 if(head[d] != -1) last[head[
d]] =
i;
392 mindeg = std::min<StorageIndex> (mindeg,
d);
397 if((len[k] =
p-pk1) == 0)
402 if(elenk != 0) cnz =
p;
406 for(i = 0; i <
n; i++) Cp[i] =
amd_flip (Cp[i]);
407 for(j = 0; j <=
n; j++) head[j] = -1;
408 for(j = n; j >= 0; j--)
410 if(nv[j] > 0)
continue;
411 next[
j] = head[Cp[
j]];
414 for(
e = n;
e >= 0;
e--)
416 if(nv[
e] <= 0)
continue;
419 next[
e] = head[Cp[
e]];
423 for(k = 0, i = 0; i <=
n; i++)
425 if(Cp[i] == -1) k = internal::cs_tdfs<StorageIndex>(
i, k,
head, next, perm.
indices().data(),
w);
428 perm.
indices().conservativeResize(n);
435 #endif // EIGEN_SPARSE_AMD_H
static StorageIndex cs_wclear(StorageIndex mark, StorageIndex lemax, StorageIndex *w, StorageIndex n)
const StorageIndex * outerIndexPtr() const
void amd_mark(const T0 *w, const T1 &j)
Namespace containing all symbols from the Eigen library.
void resizeNonZeros(Index size)
static const symbolic::SymbolExpr< internal::symbolic_last_tag > last
const IndicesType & indices() const
bool amd_marked(const T0 *w, const T1 &j)
Matrix stack(size_t nrMatrices,...)
idx_t idx_t idx_t idx_t idx_t * perm
void minimum_degree_ordering(SparseMatrix< Scalar, ColMajor, StorageIndex > &C, PermutationMatrix< Dynamic, Dynamic, StorageIndex > &perm)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EIGEN_DEVICE_FUNC const Scalar & q
#define ei_declare_aligned_stack_constructed_variable(TYPE, NAME, SIZE, BUFFER)
const StorageIndex * innerIndexPtr() const
Matrix< Scalar, Dynamic, Dynamic > C
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE FixedSegmentReturnType< internal::get_fixed_value< NType >::value >::Type head(NType n)
StorageIndex cs_tdfs(StorageIndex j, StorageIndex k, StorageIndex *head, const StorageIndex *next, StorageIndex *post, StorageIndex *stack)
Jet< T, N > sqrt(const Jet< T, N > &f)
size_t len(handle h)
Get the length of a Python object.
void resize(Index newSize)