12 #if 0 // sparse_basic(DynamicSparseMatrix) does not compile at all -> disabled 14 #define EIGEN_SPARSE_COMPRESSED_STORAGE_REALLOCATE_PLUGIN g_realloc_count++; 17 #define EIGEN_SPARSE_ASSIGNMENT_FROM_DENSE_OP_SPARSE_PLUGIN g_dense_op_sparse_count++; 18 #define EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_ADD_DENSE_PLUGIN g_dense_op_sparse_count+=10; 19 #define EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_SUB_DENSE_PLUGIN g_dense_op_sparse_count+=20; 21 #define EIGEN_SPARSE_TEST_INCLUDED_FROM_SPARSE_EXTRA 1 24 #define EIGEN_NO_DEPRECATED_WARNING 27 #define EIGEN_SPARSE_PRODUCT_IGNORE_TEMPORARY_COUNT 28 #include "sparse_product.cpp" 30 #if 0 // sparse_basic(DynamicSparseMatrix) does not compile at all -> disabled 44 #include <unordered_map> 45 #define EIGEN_UNORDERED_MAP_SUPPORT 50 #include <Eigen/SparseExtra> 52 template<
typename SetterType,
typename DenseType,
typename Scalar,
int Options>
53 bool test_random_setter(SparseMatrix<Scalar,Options>& sm,
const DenseType&
ref,
const std::vector<Vector2i>& nonzeroCoords)
58 std::vector<Vector2i> remaining = nonzeroCoords;
59 while(!remaining.empty())
61 int i = internal::random<int>(0,
static_cast<int>(remaining.size())-1);
62 w(remaining[i].
x(),remaining[i].
y()) = ref.coeff(remaining[i].
x(),remaining[i].
y());
63 remaining[
i] = remaining.back();
67 return sm.isApprox(ref);
70 template<
typename SetterType,
typename DenseType,
typename T>
71 bool test_random_setter(DynamicSparseMatrix<T>& sm,
const DenseType&
ref,
const std::vector<Vector2i>& nonzeroCoords)
74 std::vector<Vector2i> remaining = nonzeroCoords;
75 while(!remaining.empty())
77 int i = internal::random<int>(0,
static_cast<int>(remaining.size())-1);
78 sm.coeffRef(remaining[i].
x(),remaining[i].
y()) = ref.coeff(remaining[i].
x(),remaining[i].
y());
79 remaining[
i] = remaining.back();
82 return sm.isApprox(ref);
85 template<
typename SparseMatrixType>
void sparse_extra(
const SparseMatrixType&
ref)
90 enum { Flags = SparseMatrixType::Flags };
97 SparseMatrixType
m(rows, cols);
98 DenseMatrix refMat = DenseMatrix::Zero(rows, cols);
99 DenseVector
vec1 = DenseVector::Random(rows);
101 std::vector<Vector2i> zeroCoords;
102 std::vector<Vector2i> nonzeroCoords;
103 initSparse<Scalar>(density, refMat,
m, 0, &zeroCoords, &nonzeroCoords);
105 if (zeroCoords.size()==0 || nonzeroCoords.size()==0)
109 for (
int i=0;
i<(
int)zeroCoords.size(); ++
i)
112 if(internal::is_same<SparseMatrixType,SparseMatrix<Scalar,Flags> >::
value)
117 m.coeffRef(nonzeroCoords[0].
x(), nonzeroCoords[0].
y()) =
Scalar(5);
118 refMat.coeffRef(nonzeroCoords[0].
x(), nonzeroCoords[0].
y()) =
Scalar(5);
139 #ifdef EIGEN_UNORDERED_MAP_SUPPORT 142 #ifdef EIGEN_GOOGLEHASH_SUPPORT 166 template<
typename SparseMatrixType>
169 typedef Matrix<typename SparseMatrixType::Scalar, Dynamic, Dynamic>
DenseMatrix;
170 Index rows = internal::random<Index>(1,100);
171 Index cols = internal::random<Index>(1,100);
172 SparseMatrixType
m1,
m2;
173 m1 = DenseMatrix::Random(rows, cols).sparseView();
179 template<
typename VectorType>
182 Index size = internal::random<Index>(1,100);
184 v1 = VectorType::Random(size);
193 int s = Eigen::internal::random<int>(1,50);
Matrix< Scalar, Dynamic, Dynamic > DenseMatrix
#define VERIFY_RAISES_ASSERT(a)
#define CALL_SUBTEST_4(FUNC)
bool loadMarketVector(VectorType &vec, const std::string &filename)
#define CALL_SUBTEST_3(FUNC)
static long g_dense_op_sparse_count
Matrix< Scalar, Dynamic, 1 > DenseVector
#define VERIFY_IS_APPROX(a, b)
bool saveMarketVector(const VectorType &vec, const std::string &filename)
#define VERIFY_IS_EQUAL(a, b)
#define CALL_SUBTEST_1(FUNC)
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Reference counting helper.
#define VERIFY_IS_MUCH_SMALLER_THAN(a, b)
#define TEST_SET_BUT_UNUSED_VARIABLE(X)
#define CALL_SUBTEST_5(FUNC)
bool loadMarket(SparseMatrixType &mat, const std::string &filename)
bool saveMarket(const SparseMatrixType &mat, const std::string &filename, int sym=0)
#define CALL_SUBTEST_2(FUNC)
static long g_realloc_count
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
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 x