31 #ifndef SPARSELU_PANEL_BMOD_H 32 #define SPARSELU_PANEL_BMOD_H 55 template <
typename Scalar,
typename StorageIndex>
61 Index ksub,jj,nextl_col;
62 Index fsupc, nsupc, nsupr, nrow;
66 Index segsize,no_zeros ;
71 for (ksub = 0; ksub < nseg; ksub++)
78 krep = segrep(k); k--;
80 nsupc = krep - fsupc + 1;
83 lptr = glu.
xlsub(fsupc);
88 for (jj = jcol; jj < jcol +
w; jj++)
90 nextl_col = (jj-jcol) * m;
93 kfnz = repfnz_col(krep);
97 segsize = krep - kfnz + 1;
104 Index ldu = internal::first_multiple<Index>(u_rows, PacketSize);
109 for (jj = jcol; jj < jcol +
w; jj++)
111 nextl_col = (jj-jcol) * m;
115 kfnz = repfnz_col(krep);
119 segsize = krep - kfnz + 1;
120 luptr = glu.
xlusup(fsupc);
121 no_zeros = kfnz - fsupc;
123 Index isub = lptr + no_zeros;
124 Index off = u_rows-segsize;
125 for (
Index i = 0;
i < off;
i++)
U(
i,u_col) = 0;
129 U(
i+off,u_col) = dense_col(irow);
135 luptr = glu.
xlusup(fsupc);
137 no_zeros = (krep - u_rows + 1) - fsupc;
138 luptr += lda * no_zeros + no_zeros;
140 U = A.template triangularView<UnitLower>().solve(U);
147 Index ldl = internal::first_multiple<Index>(nrow, PacketSize);
152 internal::sparselu_gemm<Scalar>(L.rows(), L.cols(), B.cols(), B.data(), B.
outerStride(), U.data(), U.outerStride(), L.data(), L.
outerStride());
156 for (jj = jcol; jj < jcol +
w; jj++)
158 nextl_col = (jj-jcol) * m;
162 kfnz = repfnz_col(krep);
166 segsize = krep - kfnz + 1;
167 no_zeros = kfnz - fsupc;
168 Index isub = lptr + no_zeros;
170 Index off = u_rows-segsize;
174 dense_col(irow) = U.coeff(
i+off,u_col);
175 U.coeffRef(
i+off,u_col) = 0;
182 dense_col(irow) -= L.coeff(
i,u_col);
183 L.coeffRef(
i,u_col) = 0;
191 for (jj = jcol; jj < jcol +
w; jj++)
193 nextl_col = (jj-jcol) * m;
197 kfnz = repfnz_col(krep);
201 segsize = krep - kfnz + 1;
202 luptr = glu.
xlusup(fsupc);
208 no_zeros = kfnz - fsupc;
223 #endif // SPARSELU_PANEL_BMOD_H
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar * data() const
A matrix or vector expression mapping an existing array of data.
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate offset
Namespace containing all symbols from the Eigen library.
void panel_bmod(const Index m, const Index w, const Index jcol, const Index nseg, ScalarVector &dense, ScalarVector &tempv, IndexVector &segrep, IndexVector &repfnz, GlobalLU_t &glu)
Performs numeric block updates (sup-panel) in topological order.
static EIGEN_DONT_INLINE void run(const Index segsize, BlockScalarVector &dense, ScalarVector &tempv, ScalarVector &lusup, Index &luptr, const Index lda, const Index nrow, IndexVector &lsub, const Index lptr, const Index no_zeros)
static Index first_default_aligned(const DenseBase< Derived > &m)
Expression of a fixed-size or dynamic-size sub-vector.
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index outerStride() const
The matrix class, also used for vectors and row-vectors.
Convenience specialization of Stride to specify only an outer stride See class Map for some examples...