Go to the documentation of this file.00001
00009
00010
00011
00012
00013 #define EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET
00014
00015
00016
00017
00018
00019 #include <iostream>
00020 #include <ecl/time.hpp>
00021 #include <ecl/threads/priority.hpp>
00022 #include <ecl/linear_algebra.hpp>
00023 #include <ecl/linear_algebra/sparse.hpp>
00024
00025
00026
00027
00028
00029 using ecl::linear_algebra::SparseMatrix;
00030 using ecl::linear_algebra::DynamicSparseMatrix;
00031 using ecl::linear_algebra::MatrixXd;
00032 using ecl::StopWatch;
00033
00034
00035
00036
00037 #define LM (303)
00038 void test_sparse_matrix( int num )
00039 {
00040 DynamicSparseMatrix<double> hh(20, LM);
00041 MatrixXd P(LM,LM);
00042 hh.setZero();
00043 P.setZero();
00044 for( int i=0; i<20; i++ )
00045 for( int j=0; j<3; j++ )
00046 hh.coeffRef(i,j) = 1;
00047
00048 for( int i=0; i<10; i++)
00049 {
00050 for( int j=0; j<2; j++ )
00051 {
00052 for( int k=0; k<3; k++ )
00053 {
00054 hh.coeffRef( i*2+j, (i*4)+k ) = 1;
00055 }
00056 }
00057 }
00058
00059 SparseMatrix<double> H(hh);
00060 ecl::StopWatch time;
00061 for( int i=0; i<num; i++ )
00062 {
00063 MatrixXd S = H*P*H.transpose();
00064 S(4,4)= i;
00065 }
00066 std::cout << time.elapsed();
00067 }
00068
00069 void test_dense_matrix( int num )
00070 {
00071 MatrixXd H(20, LM);
00072 MatrixXd P(LM,LM);
00073 H.setZero();
00074 P.setZero();
00075 for( int i=0; i<20; i++ )
00076 for( int j=0; j<3; j++ )
00077 H(i,j) = 1;
00078
00079 for( int i=0; i<10; i++)
00080 {
00081 for( int j=0; j<2; j++ )
00082 {
00083 for( int k=0; k<3; k++ )
00084 {
00085 H( i*2+j, (i*4)+k ) = 1;
00086 }
00087 }
00088 }
00089
00090 ecl::StopWatch time;
00091 for( int i=0; i<num; i++ )
00092 {
00093 MatrixXd S = H*P*H.transpose();
00094 S(4,4)= i;
00095 }
00096 std::cout << time.elapsed();
00097 }
00098
00099 void compare_multiplication()
00100 {
00101 std::cout << "==========================" << std::endl;
00102 std::cout << "S=H P T'" << std::endl;
00103 std::cout << "Start sparse: ";
00104 test_sparse_matrix(1000);
00105 std::cout << std::endl;
00106
00107 std::cout << "Start dense: ";
00108 test_dense_matrix(1000);
00109 std::cout << std::endl;
00110 std::cout << "==========================" << std::endl;
00111 }
00112
00113 void fill_sparse( int num )
00114 {
00115 ecl::StopWatch time;
00116 DynamicSparseMatrix<double> hh(20, LM);
00117 for( int i=0; i<num; i++)
00118 {
00119 for( int j=0; j<20; j++ )
00120 for( int k=0; k<LM; k++ )
00121 hh.coeffRef(j,k) = (double)j*k;
00122 }
00123
00124 std::cout << time.elapsed();
00125 }
00126
00127 void fill_dense( int num )
00128 {
00129 ecl::StopWatch time;
00130 MatrixXd hh(20, LM);
00131 for( int i=0; i<num; i++ )
00132 {
00133 for( int j=0; j<20; j++ )
00134 for( int k=0; k<LM; k++ )
00135 hh(j,k) = (double)j*k;
00136 }
00137
00138 std::cout << time.elapsed();
00139 }
00140
00141 void compare_filling()
00142 {
00143 std::cout << "==========================" << std::endl;
00144 std::cout << "Filling " << std::endl;
00145 std::cout << "fill sparse: ";
00146 fill_sparse(1000);
00147 std::cout << std::endl;
00148 std::cout << "fill dense: ";
00149 fill_dense(1000);
00150 std::cout << std::endl;
00151 std::cout << "==========================" << std::endl;
00152 }
00153
00154 int main(int argc, char **argv) {
00155
00156 try {
00157 ecl::set_priority(ecl::RealTimePriority4);
00158 } catch ( ecl::StandardException &e ) {
00159
00160 }
00161
00162 compare_multiplication();
00163 compare_filling();
00164
00165 return 0;
00166 }