26 template<
typename SparseMatrixType>
void sparse_block(
const SparseMatrixType&
ref)
30 const Index inner = ref.innerSize();
31 const Index outer = ref.outerSize();
34 typedef typename SparseMatrixType::StorageIndex StorageIndex;
36 double density = (
std::max)(8./(rows*cols), 0.01);
42 Scalar s1 = internal::random<Scalar>();
44 SparseMatrixType
m(rows, cols);
45 DenseMatrix refMat = DenseMatrix::Zero(rows, cols);
46 initSparse<Scalar>(density, refMat,
m);
51 for (
int t=0;
t<10; ++
t)
53 Index j = internal::random<Index>(0,cols-2);
54 Index i = internal::random<Index>(0,rows-2);
55 Index w = internal::random<Index>(1,cols-
j);
56 Index h = internal::random<Index>(1,rows-
i);
64 VERIFY_IS_APPROX(m.block(i,j,h,w).col(
c).coeff(r), refMat.block(i,j,h,w).col(
c).coeff(r));
73 VERIFY_IS_APPROX(m.block(i,j,h,w).row(r).coeff(
c), refMat.block(i,j,h,w).row(r).coeff(
c));
91 if(m.middleCols(j,w).coeff(r,
c) !=
Scalar(0))
95 if(m.middleRows(i,h).coeff(r,
c) !=
Scalar(0))
123 DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);
124 SparseMatrixType
m2(rows, cols);
125 initSparse<Scalar>(density, refMat2,
m2);
126 Index j0 = internal::random<Index>(0,outer-1);
127 Index j1 = internal::random<Index>(0,outer-1);
128 Index r0 = internal::random<Index>(0,rows-1);
129 Index c0 = internal::random<Index>(0,cols-1);
134 m2.innerVector(j0) *=
Scalar(2);
139 refMat2.row(r0) *=
Scalar(3);
143 refMat2.col(c0) *=
Scalar(4);
147 refMat2.row(r0) /=
Scalar(3);
151 refMat2.col(c0) /=
Scalar(4);
158 SparseMatrixType m3(rows,cols);
159 m3.reserve(VectorXi::Constant(outer,
int(inner/2)));
162 m3.insertByOuterInner(
j,k) = internal::convert_index<StorageIndex>(k+1);
177 VERIFY(m3.innerVector(j0).nonZeros() == m3.transpose().innerVector(j0).nonZeros());
186 DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);
187 SparseMatrixType
m2(rows, cols);
188 initSparse<Scalar>(density, refMat2,
m2);
189 if(internal::random<float>(0,1)>0.5f) m2.makeCompressed();
190 Index j0 = internal::random<Index>(0,outer-2);
191 Index j1 = internal::random<Index>(0,outer-2);
192 Index n0 = internal::random<Index>(1,outer-(
std::max)(j0,j1));
193 if(SparseMatrixType::IsRowMajor)
197 if(SparseMatrixType::IsRowMajor)
199 refMat2.middleRows(j0,n0)+refMat2.middleRows(j1,n0));
202 refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0));
206 VERIFY(m2.innerVectors(j0,n0).nonZeros() == m2.transpose().innerVectors(j0,n0).nonZeros());
208 m2.innerVectors(j0,n0) = m2.innerVectors(j0,n0) + m2.innerVectors(j1,n0);
209 if(SparseMatrixType::IsRowMajor)
210 refMat2.middleRows(j0,n0) = (refMat2.middleRows(j0,n0) + refMat2.middleRows(j1,n0)).
eval();
212 refMat2.middleCols(j0,n0) = (refMat2.middleCols(j0,n0) + refMat2.middleCols(j1,n0)).
eval();
219 DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);
220 SparseMatrixType
m2(rows, cols);
221 initSparse<Scalar>(density, refMat2,
m2);
222 Index j0 = internal::random<Index>(0,outer-2);
223 Index j1 = internal::random<Index>(0,outer-2);
224 Index n0 = internal::random<Index>(1,outer-(
std::max)(j0,j1));
225 if(SparseMatrixType::IsRowMajor)
230 if(SparseMatrixType::IsRowMajor)
232 refMat2.block(j0,0,n0,cols)+refMat2.block(j1,0,n0,cols));
235 refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0));
237 Index i = internal::random<Index>(0,m2.outerSize()-1);
238 if(SparseMatrixType::IsRowMajor) {
239 m2.innerVector(i) = m2.innerVector(i) * s1;
240 refMat2.row(i) = refMat2.row(i) * s1;
243 m2.innerVector(i) = m2.innerVector(i) * s1;
244 refMat2.col(i) = refMat2.col(i) * s1;
248 Index r0 = internal::random<Index>(0,rows-2);
249 Index c0 = internal::random<Index>(0,cols-2);
250 Index r1 = internal::random<Index>(1,rows-r0);
251 Index c1 = internal::random<Index>(1,cols-c0);
265 SparseMatrixType m3(rows, cols);
266 DenseMatrix refMat3(rows, cols); refMat3.setZero();
267 Index n = internal::random<Index>(1,10);
270 Index o1 = internal::random<Index>(0,outer-1);
271 Index o2 = internal::random<Index>(0,outer-1);
272 if(SparseMatrixType::IsRowMajor)
274 m3.innerVector(o1) = m2.row(o2);
275 refMat3.row(o1) = refMat2.row(o2);
279 m3.innerVector(o1) = m2.col(o2);
280 refMat3.col(o1) = refMat2.col(o2);
282 if(internal::random<bool>())
294 int r = Eigen::internal::random<int>(1,200),
c = Eigen::internal::random<int>(1,200);
295 if(Eigen::internal::random<int>(0,4) == 0) {
308 r = Eigen::internal::random<int>(1,100);
309 c = Eigen::internal::random<int>(1,100);
310 if(Eigen::internal::random<int>(0,4) == 0) {
Matrix< Scalar, Dynamic, Dynamic > DenseMatrix
m m block(1, 0, 2, 2)<< 4
const StorageIndex & row() const
Matrix< Scalar, Dynamic, 1 > DenseVector
const StorageIndex & col() const
#define VERIFY_IS_APPROX(a, b)
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Eigen::internal::enable_if<(T::Flags &RowMajorBit)==RowMajorBit, typename T::RowXpr >::type innervec(T &A, Index i)
internal::nested_eval< T, 1 >::type eval(const T &xpr)
The matrix class, also used for vectors and row-vectors.
void sparse_block(const SparseMatrixType &ref)
#define EIGEN_UNUSED_VARIABLE(var)