replace boost random with std random
parent
905be415fa
commit
e993afe2bf
|
@ -50,11 +50,11 @@
|
||||||
#include <boost/program_options.hpp>
|
#include <boost/program_options.hpp>
|
||||||
#include <boost/range/algorithm/set_algorithm.hpp>
|
#include <boost/range/algorithm/set_algorithm.hpp>
|
||||||
#include <boost/range/adaptor/reversed.hpp>
|
#include <boost/range/adaptor/reversed.hpp>
|
||||||
#include <boost/random.hpp>
|
|
||||||
#include <boost/serialization/export.hpp>
|
#include <boost/serialization/export.hpp>
|
||||||
|
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
#include <random>
|
||||||
|
|
||||||
#ifdef GTSAM_USE_TBB
|
#ifdef GTSAM_USE_TBB
|
||||||
#include <tbb/task_arena.h> // tbb::task_arena
|
#include <tbb/task_arena.h> // tbb::task_arena
|
||||||
|
@ -554,8 +554,8 @@ void runCompare()
|
||||||
void runPerturb()
|
void runPerturb()
|
||||||
{
|
{
|
||||||
// Set up random number generator
|
// Set up random number generator
|
||||||
boost::mt19937 rng;
|
std::mt19937 rng;
|
||||||
boost::normal_distribution<double> normal(0.0, perturbationNoise);
|
std::normal_distribution<double> normal(0.0, perturbationNoise);
|
||||||
|
|
||||||
// Perturb values
|
// Perturb values
|
||||||
VectorValues noise;
|
VectorValues noise;
|
||||||
|
|
|
@ -35,7 +35,7 @@ namespace gtsam {
|
||||||
|
|
||||||
// TODO(frank): is this better than SOn::Random?
|
// TODO(frank): is this better than SOn::Random?
|
||||||
// /* *************************************************************************
|
// /* *************************************************************************
|
||||||
// */ static Vector3 randomOmega(boost::mt19937 &rng) {
|
// */ static Vector3 randomOmega(std::mt19937 &rng) {
|
||||||
// static std::uniform_real_distribution<double> randomAngle(-M_PI, M_PI);
|
// static std::uniform_real_distribution<double> randomAngle(-M_PI, M_PI);
|
||||||
// return Unit3::Random(rng).unitVector() * randomAngle(rng);
|
// return Unit3::Random(rng).unitVector() * randomAngle(rng);
|
||||||
// }
|
// }
|
||||||
|
@ -43,7 +43,7 @@ namespace gtsam {
|
||||||
// /* *************************************************************************
|
// /* *************************************************************************
|
||||||
// */
|
// */
|
||||||
// // Create random SO(4) element using direct product of lie algebras.
|
// // Create random SO(4) element using direct product of lie algebras.
|
||||||
// SO4 SO4::Random(boost::mt19937 &rng) {
|
// SO4 SO4::Random(std::mt19937 &rng) {
|
||||||
// Vector6 delta;
|
// Vector6 delta;
|
||||||
// delta << randomOmega(rng), randomOmega(rng);
|
// delta << randomOmega(rng), randomOmega(rng);
|
||||||
// return SO4::Expmap(delta);
|
// return SO4::Expmap(delta);
|
||||||
|
|
|
@ -34,7 +34,7 @@ namespace gtsam {
|
||||||
using SO4 = SO<4>;
|
using SO4 = SO<4>;
|
||||||
|
|
||||||
// /// Random SO(4) element (no big claims about uniformity)
|
// /// Random SO(4) element (no big claims about uniformity)
|
||||||
// static SO4 Random(boost::mt19937 &rng);
|
// static SO4 Random(std::mt19937 &rng);
|
||||||
|
|
||||||
// Below are all declarations of SO<4> specializations.
|
// Below are all declarations of SO<4> specializations.
|
||||||
// They are *defined* in SO4.cpp.
|
// They are *defined* in SO4.cpp.
|
||||||
|
|
|
@ -22,13 +22,14 @@
|
||||||
#include <gtsam/linear/NoiseModel.h>
|
#include <gtsam/linear/NoiseModel.h>
|
||||||
#include <gtsam/linear/VectorValues.h>
|
#include <gtsam/linear/VectorValues.h>
|
||||||
|
|
||||||
#include <boost/random.hpp>
|
#include <random>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
static boost::variate_generator<boost::mt19937, boost::uniform_real<> > rg(boost::mt19937(), boost::uniform_real<>(0.0, 1.0));
|
static std::mt19937 rng;
|
||||||
|
static std::uniform_real_distribution<> rg(0.0, 1.0);
|
||||||
|
|
||||||
int main(int argc, char *argv[]) {
|
int main(int argc, char *argv[]) {
|
||||||
|
|
||||||
|
@ -64,10 +65,10 @@ int main(int argc, char *argv[]) {
|
||||||
Matrix A(blockdim, vardim);
|
Matrix A(blockdim, vardim);
|
||||||
for(size_t j=0; j<blockdim; ++j)
|
for(size_t j=0; j<blockdim; ++j)
|
||||||
for(size_t k=0; k<vardim; ++k)
|
for(size_t k=0; k<vardim; ++k)
|
||||||
A(j,k) = rg();
|
A(j,k) = rg(rng);
|
||||||
Vector b(blockdim);
|
Vector b(blockdim);
|
||||||
for(size_t j=0; j<blockdim; ++j)
|
for(size_t j=0; j<blockdim; ++j)
|
||||||
b(j) = rg();
|
b(j) = rg(rng);
|
||||||
blockGfgs[trial].push_back(boost::make_shared<JacobianFactor>(key, A, b, noise));
|
blockGfgs[trial].push_back(boost::make_shared<JacobianFactor>(key, A, b, noise));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -111,10 +112,10 @@ int main(int argc, char *argv[]) {
|
||||||
// Generate a random Gaussian factor
|
// Generate a random Gaussian factor
|
||||||
for(size_t j=0; j<blockdim; ++j)
|
for(size_t j=0; j<blockdim; ++j)
|
||||||
for(size_t k=0; k<vardim; ++k)
|
for(size_t k=0; k<vardim; ++k)
|
||||||
Acomb(blockdim*i+j, k) = rg();
|
Acomb(blockdim*i+j, k) = rg(rng);
|
||||||
Vector b(blockdim);
|
Vector b(blockdim);
|
||||||
for(size_t j=0; j<blockdim; ++j)
|
for(size_t j=0; j<blockdim; ++j)
|
||||||
bcomb(blockdim*i+j) = rg();
|
bcomb(blockdim*i+j) = rg(rng);
|
||||||
}
|
}
|
||||||
combGfgs[trial].push_back(boost::make_shared<JacobianFactor>(key, Acomb, bcomb,
|
combGfgs[trial].push_back(boost::make_shared<JacobianFactor>(key, Acomb, bcomb,
|
||||||
noiseModel::Isotropic::Sigma(blockdim*nBlocks, 1.0)));
|
noiseModel::Isotropic::Sigma(blockdim*nBlocks, 1.0)));
|
||||||
|
|
|
@ -31,6 +31,7 @@
|
||||||
#include <gtsam/slam/FrobeniusFactor.h>
|
#include <gtsam/slam/FrobeniusFactor.h>
|
||||||
|
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
#include <random>
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
|
@ -76,7 +77,7 @@ int main(int argc, char* argv[]) {
|
||||||
keys[0], keys[1], SO3(Tij.rotation().matrix()), model);
|
keys[0], keys[1], SO3(Tij.rotation().matrix()), model);
|
||||||
}
|
}
|
||||||
|
|
||||||
boost::mt19937 rng(42);
|
std::mt19937 rng(42);
|
||||||
|
|
||||||
// Set parameters to be similar to ceres
|
// Set parameters to be similar to ceres
|
||||||
LevenbergMarquardtParams params;
|
LevenbergMarquardtParams params;
|
||||||
|
|
|
@ -16,7 +16,6 @@
|
||||||
* @date Sep 18, 2010
|
* @date Sep 18, 2010
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <boost/random.hpp>
|
|
||||||
#include <boost/format.hpp>
|
#include <boost/format.hpp>
|
||||||
#include <boost/lambda/lambda.hpp>
|
#include <boost/lambda/lambda.hpp>
|
||||||
|
|
||||||
|
@ -24,6 +23,7 @@
|
||||||
#include <gtsam/base/Matrix.h>
|
#include <gtsam/base/Matrix.h>
|
||||||
|
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
#include <random>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
#include <utility>
|
#include <utility>
|
||||||
|
|
||||||
|
@ -33,7 +33,8 @@ using namespace std;
|
||||||
using boost::format;
|
using boost::format;
|
||||||
using namespace boost::lambda;
|
using namespace boost::lambda;
|
||||||
|
|
||||||
static boost::variate_generator<boost::mt19937, boost::uniform_real<> > rng(boost::mt19937(), boost::uniform_real<>(-1.0, 0.0));
|
static std::mt19937 rng;
|
||||||
|
static std::uniform_real_distribution<> rg(-1.0, 0.0);
|
||||||
//typedef ublas::matrix<double> matrix;
|
//typedef ublas::matrix<double> matrix;
|
||||||
//typedef ublas::matrix_range<matrix> matrix_range;
|
//typedef ublas::matrix_range<matrix> matrix_range;
|
||||||
//typedef Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic> matrix;
|
//typedef Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic> matrix;
|
||||||
|
@ -53,8 +54,8 @@ int main(int argc, char* argv[]) {
|
||||||
volatile size_t n=300;
|
volatile size_t n=300;
|
||||||
volatile size_t nReps = 1000;
|
volatile size_t nReps = 1000;
|
||||||
assert(m > n);
|
assert(m > n);
|
||||||
boost::variate_generator<boost::mt19937, boost::uniform_int<size_t> > rni(boost::mt19937(), boost::uniform_int<size_t>(0,m-1));
|
std::uniform_int_distribution<size_t> ri(0,m-1);
|
||||||
boost::variate_generator<boost::mt19937, boost::uniform_int<size_t> > rnj(boost::mt19937(), boost::uniform_int<size_t>(0,n-1));
|
std::uniform_int_distribution<size_t> rj(0,n-1);
|
||||||
gtsam::Matrix mat((int)m,(int)n);
|
gtsam::Matrix mat((int)m,(int)n);
|
||||||
gtsam::SubMatrix full = mat.block(0, 0, m, n);
|
gtsam::SubMatrix full = mat.block(0, 0, m, n);
|
||||||
gtsam::SubMatrix top = mat.block(0, 0, n, n);
|
gtsam::SubMatrix top = mat.block(0, 0, n, n);
|
||||||
|
@ -75,13 +76,13 @@ int main(int argc, char* argv[]) {
|
||||||
for(size_t rep=0; rep<1000; ++rep)
|
for(size_t rep=0; rep<1000; ++rep)
|
||||||
for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
||||||
for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
||||||
mat(i,j) = rng();
|
mat(i,j) = rg(rng);
|
||||||
|
|
||||||
gttic_(basicTime);
|
gttic_(basicTime);
|
||||||
for(size_t rep=0; rep<nReps; ++rep)
|
for(size_t rep=0; rep<nReps; ++rep)
|
||||||
for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
||||||
for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
||||||
mat(i,j) = rng();
|
mat(i,j) = rg(rng);
|
||||||
gttoc_(basicTime);
|
gttoc_(basicTime);
|
||||||
tictoc_getNode(basicTimeNode, basicTime);
|
tictoc_getNode(basicTimeNode, basicTime);
|
||||||
basicTime = basicTimeNode->secs();
|
basicTime = basicTimeNode->secs();
|
||||||
|
@ -92,7 +93,7 @@ int main(int argc, char* argv[]) {
|
||||||
for(size_t rep=0; rep<nReps; ++rep)
|
for(size_t rep=0; rep<nReps; ++rep)
|
||||||
for(size_t i=0; i<(size_t)full.rows(); ++i)
|
for(size_t i=0; i<(size_t)full.rows(); ++i)
|
||||||
for(size_t j=0; j<(size_t)full.cols(); ++j)
|
for(size_t j=0; j<(size_t)full.cols(); ++j)
|
||||||
full(i,j) = rng();
|
full(i,j) = rg(rng);
|
||||||
gttoc_(fullTime);
|
gttoc_(fullTime);
|
||||||
tictoc_getNode(fullTimeNode, fullTime);
|
tictoc_getNode(fullTimeNode, fullTime);
|
||||||
fullTime = fullTimeNode->secs();
|
fullTime = fullTimeNode->secs();
|
||||||
|
@ -103,7 +104,7 @@ int main(int argc, char* argv[]) {
|
||||||
for(size_t rep=0; rep<nReps; ++rep)
|
for(size_t rep=0; rep<nReps; ++rep)
|
||||||
for(size_t i=0; i<(size_t)top.rows(); ++i)
|
for(size_t i=0; i<(size_t)top.rows(); ++i)
|
||||||
for(size_t j=0; j<(size_t)top.cols(); ++j)
|
for(size_t j=0; j<(size_t)top.cols(); ++j)
|
||||||
top(i,j) = rng();
|
top(i,j) = rg(rng);
|
||||||
gttoc_(topTime);
|
gttoc_(topTime);
|
||||||
tictoc_getNode(topTimeNode, topTime);
|
tictoc_getNode(topTimeNode, topTime);
|
||||||
topTime = topTimeNode->secs();
|
topTime = topTimeNode->secs();
|
||||||
|
@ -114,7 +115,7 @@ int main(int argc, char* argv[]) {
|
||||||
for(size_t rep=0; rep<nReps; ++rep)
|
for(size_t rep=0; rep<nReps; ++rep)
|
||||||
for(size_t i=0; i<(size_t)block.rows(); ++i)
|
for(size_t i=0; i<(size_t)block.rows(); ++i)
|
||||||
for(size_t j=0; j<(size_t)block.cols(); ++j)
|
for(size_t j=0; j<(size_t)block.cols(); ++j)
|
||||||
block(i,j) = rng();
|
block(i,j) = rg(rng);
|
||||||
gttoc_(blockTime);
|
gttoc_(blockTime);
|
||||||
tictoc_getNode(blockTimeNode, blockTime);
|
tictoc_getNode(blockTimeNode, blockTime);
|
||||||
blockTime = blockTimeNode->secs();
|
blockTime = blockTimeNode->secs();
|
||||||
|
@ -133,13 +134,13 @@ int main(int argc, char* argv[]) {
|
||||||
for(size_t rep=0; rep<1000; ++rep)
|
for(size_t rep=0; rep<1000; ++rep)
|
||||||
for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
||||||
for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
||||||
mat(i,j) = rng();
|
mat(i,j) = rg(rng);
|
||||||
|
|
||||||
gttic_(basicTime);
|
gttic_(basicTime);
|
||||||
for(size_t rep=0; rep<nReps; ++rep)
|
for(size_t rep=0; rep<nReps; ++rep)
|
||||||
for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
||||||
for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
||||||
mat(i,j) = rng();
|
mat(i,j) = rg(rng);
|
||||||
gttoc_(basicTime);
|
gttoc_(basicTime);
|
||||||
tictoc_getNode(basicTimeNode, basicTime);
|
tictoc_getNode(basicTimeNode, basicTime);
|
||||||
basicTime = basicTimeNode->secs();
|
basicTime = basicTimeNode->secs();
|
||||||
|
@ -150,7 +151,7 @@ int main(int argc, char* argv[]) {
|
||||||
for(size_t rep=0; rep<nReps; ++rep)
|
for(size_t rep=0; rep<nReps; ++rep)
|
||||||
for(size_t j=0; j<(size_t)full.cols(); ++j)
|
for(size_t j=0; j<(size_t)full.cols(); ++j)
|
||||||
for(size_t i=0; i<(size_t)full.rows(); ++i)
|
for(size_t i=0; i<(size_t)full.rows(); ++i)
|
||||||
full(i,j) = rng();
|
full(i,j) = rg(rng);
|
||||||
gttoc_(fullTime);
|
gttoc_(fullTime);
|
||||||
tictoc_getNode(fullTimeNode, fullTime);
|
tictoc_getNode(fullTimeNode, fullTime);
|
||||||
fullTime = fullTimeNode->secs();
|
fullTime = fullTimeNode->secs();
|
||||||
|
@ -161,7 +162,7 @@ int main(int argc, char* argv[]) {
|
||||||
for(size_t rep=0; rep<nReps; ++rep)
|
for(size_t rep=0; rep<nReps; ++rep)
|
||||||
for(size_t j=0; j<(size_t)top.cols(); ++j)
|
for(size_t j=0; j<(size_t)top.cols(); ++j)
|
||||||
for(size_t i=0; i<(size_t)top.rows(); ++i)
|
for(size_t i=0; i<(size_t)top.rows(); ++i)
|
||||||
top(i,j) = rng();
|
top(i,j) = rg(rng);
|
||||||
gttoc_(topTime);
|
gttoc_(topTime);
|
||||||
tictoc_getNode(topTimeNode, topTime);
|
tictoc_getNode(topTimeNode, topTime);
|
||||||
topTime = topTimeNode->secs();
|
topTime = topTimeNode->secs();
|
||||||
|
@ -172,7 +173,7 @@ int main(int argc, char* argv[]) {
|
||||||
for(size_t rep=0; rep<nReps; ++rep)
|
for(size_t rep=0; rep<nReps; ++rep)
|
||||||
for(size_t j=0; j<(size_t)block.cols(); ++j)
|
for(size_t j=0; j<(size_t)block.cols(); ++j)
|
||||||
for(size_t i=0; i<(size_t)block.rows(); ++i)
|
for(size_t i=0; i<(size_t)block.rows(); ++i)
|
||||||
block(i,j) = rng();
|
block(i,j) = rg(rng);
|
||||||
gttoc_(blockTime);
|
gttoc_(blockTime);
|
||||||
tictoc_getNode(blockTimeNode, blockTime);
|
tictoc_getNode(blockTimeNode, blockTime);
|
||||||
blockTime = blockTimeNode->secs();
|
blockTime = blockTimeNode->secs();
|
||||||
|
@ -190,14 +191,14 @@ int main(int argc, char* argv[]) {
|
||||||
cout << "Row-major matrix, random assignment:" << endl;
|
cout << "Row-major matrix, random assignment:" << endl;
|
||||||
|
|
||||||
// Do a few initial assignments to let any cache effects stabilize
|
// Do a few initial assignments to let any cache effects stabilize
|
||||||
for_each(ijs.begin(), ijs.end(), _1 = make_pair(rni(),rnj()));
|
for_each(ijs.begin(), ijs.end(), _1 = make_pair(ri(rng),rj(rng)));
|
||||||
for(size_t rep=0; rep<1000; ++rep)
|
for(size_t rep=0; rep<1000; ++rep)
|
||||||
for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = rng(); }
|
for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = rg(rng); }
|
||||||
|
|
||||||
gttic_(basicTime);
|
gttic_(basicTime);
|
||||||
for_each(ijs.begin(), ijs.end(), _1 = make_pair(rni(),rnj()));
|
for_each(ijs.begin(), ijs.end(), _1 = make_pair(ri(rng),rj(rng)));
|
||||||
for(size_t rep=0; rep<1000; ++rep)
|
for(size_t rep=0; rep<1000; ++rep)
|
||||||
for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = rng(); }
|
for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = rg(rng); }
|
||||||
gttoc_(basicTime);
|
gttoc_(basicTime);
|
||||||
tictoc_getNode(basicTimeNode, basicTime);
|
tictoc_getNode(basicTimeNode, basicTime);
|
||||||
basicTime = basicTimeNode->secs();
|
basicTime = basicTimeNode->secs();
|
||||||
|
@ -205,9 +206,9 @@ int main(int argc, char* argv[]) {
|
||||||
cout << format(" Basic: %1% mus/element") % double(1000000 * basicTime / double(ijs.size()*nReps)) << endl;
|
cout << format(" Basic: %1% mus/element") % double(1000000 * basicTime / double(ijs.size()*nReps)) << endl;
|
||||||
|
|
||||||
gttic_(fullTime);
|
gttic_(fullTime);
|
||||||
for_each(ijs.begin(), ijs.end(), _1 = make_pair(rni(),rnj()));
|
for_each(ijs.begin(), ijs.end(), _1 = make_pair(ri(rng),rj(rng)));
|
||||||
for(size_t rep=0; rep<1000; ++rep)
|
for(size_t rep=0; rep<1000; ++rep)
|
||||||
for(const ij_t& ij: ijs) { full(ij.first, ij.second) = rng(); }
|
for(const ij_t& ij: ijs) { full(ij.first, ij.second) = rg(rng); }
|
||||||
gttoc_(fullTime);
|
gttoc_(fullTime);
|
||||||
tictoc_getNode(fullTimeNode, fullTime);
|
tictoc_getNode(fullTimeNode, fullTime);
|
||||||
fullTime = fullTimeNode->secs();
|
fullTime = fullTimeNode->secs();
|
||||||
|
@ -215,9 +216,9 @@ int main(int argc, char* argv[]) {
|
||||||
cout << format(" Full: %1% mus/element") % double(1000000 * fullTime / double(ijs.size()*nReps)) << endl;
|
cout << format(" Full: %1% mus/element") % double(1000000 * fullTime / double(ijs.size()*nReps)) << endl;
|
||||||
|
|
||||||
gttic_(topTime);
|
gttic_(topTime);
|
||||||
for_each(ijs.begin(), ijs.end(), _1 = make_pair(rni()%top.rows(),rnj()));
|
for_each(ijs.begin(), ijs.end(), _1 = make_pair(ri(rng)%top.rows(),rj(rng)));
|
||||||
for(size_t rep=0; rep<1000; ++rep)
|
for(size_t rep=0; rep<1000; ++rep)
|
||||||
for(const ij_t& ij: ijs) { top(ij.first, ij.second) = rng(); }
|
for(const ij_t& ij: ijs) { top(ij.first, ij.second) = rg(rng); }
|
||||||
gttoc_(topTime);
|
gttoc_(topTime);
|
||||||
tictoc_getNode(topTimeNode, topTime);
|
tictoc_getNode(topTimeNode, topTime);
|
||||||
topTime = topTimeNode->secs();
|
topTime = topTimeNode->secs();
|
||||||
|
@ -225,9 +226,9 @@ int main(int argc, char* argv[]) {
|
||||||
cout << format(" Top: %1% mus/element") % double(1000000 * topTime / double(ijs.size()*nReps)) << endl;
|
cout << format(" Top: %1% mus/element") % double(1000000 * topTime / double(ijs.size()*nReps)) << endl;
|
||||||
|
|
||||||
gttic_(blockTime);
|
gttic_(blockTime);
|
||||||
for_each(ijs.begin(), ijs.end(), _1 = make_pair(rni()%block.rows(),rnj()%block.cols()));
|
for_each(ijs.begin(), ijs.end(), _1 = make_pair(ri(rng)%block.rows(),rj(rng)%block.cols()));
|
||||||
for(size_t rep=0; rep<1000; ++rep)
|
for(size_t rep=0; rep<1000; ++rep)
|
||||||
for(const ij_t& ij: ijs) { block(ij.first, ij.second) = rng(); }
|
for(const ij_t& ij: ijs) { block(ij.first, ij.second) = rg(rng); }
|
||||||
gttoc_(blockTime);
|
gttoc_(blockTime);
|
||||||
tictoc_getNode(blockTimeNode, blockTime);
|
tictoc_getNode(blockTimeNode, blockTime);
|
||||||
blockTime = blockTimeNode->secs();
|
blockTime = blockTimeNode->secs();
|
||||||
|
@ -250,7 +251,7 @@ int main(int argc, char* argv[]) {
|
||||||
// matrix mat(5,5);
|
// matrix mat(5,5);
|
||||||
// for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
// for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
||||||
// for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
// for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
||||||
// mat(i,j) = rng();
|
// mat(i,j) = rg(rng);
|
||||||
//
|
//
|
||||||
// tri = ublas::triangular_adaptor<matrix, ublas::upper>(mat);
|
// tri = ublas::triangular_adaptor<matrix, ublas::upper>(mat);
|
||||||
// cout << " Assigned from triangular adapter: " << tri << endl;
|
// cout << " Assigned from triangular adapter: " << tri << endl;
|
||||||
|
@ -259,13 +260,13 @@ int main(int argc, char* argv[]) {
|
||||||
//
|
//
|
||||||
// for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
// for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
||||||
// for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
// for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
||||||
// mat(i,j) = rng();
|
// mat(i,j) = rg(rng);
|
||||||
// mat = tri;
|
// mat = tri;
|
||||||
// cout << " Assign matrix from triangular: " << mat << endl;
|
// cout << " Assign matrix from triangular: " << mat << endl;
|
||||||
//
|
//
|
||||||
// for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
// for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
||||||
// for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
// for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
||||||
// mat(i,j) = rng();
|
// mat(i,j) = rg(rng);
|
||||||
// (ublas::triangular_adaptor<matrix, ublas::upper>(mat)) = tri;
|
// (ublas::triangular_adaptor<matrix, ublas::upper>(mat)) = tri;
|
||||||
// cout << " Assign triangular adaptor from triangular: " << mat << endl;
|
// cout << " Assign triangular adaptor from triangular: " << mat << endl;
|
||||||
// }
|
// }
|
||||||
|
@ -281,7 +282,7 @@ int main(int argc, char* argv[]) {
|
||||||
// matrix mat(5,7);
|
// matrix mat(5,7);
|
||||||
// for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
// for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
||||||
// for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
// for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
||||||
// mat(i,j) = rng();
|
// mat(i,j) = rg(rng);
|
||||||
//
|
//
|
||||||
// tri = ublas::triangular_adaptor<matrix, ublas::upper>(mat);
|
// tri = ublas::triangular_adaptor<matrix, ublas::upper>(mat);
|
||||||
// cout << " Assigned from triangular adapter: " << tri << endl;
|
// cout << " Assigned from triangular adapter: " << tri << endl;
|
||||||
|
@ -290,13 +291,13 @@ int main(int argc, char* argv[]) {
|
||||||
//
|
//
|
||||||
// for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
// for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
||||||
// for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
// for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
||||||
// mat(i,j) = rng();
|
// mat(i,j) = rg(rng);
|
||||||
// mat = tri;
|
// mat = tri;
|
||||||
// cout << " Assign matrix from triangular: " << mat << endl;
|
// cout << " Assign matrix from triangular: " << mat << endl;
|
||||||
//
|
//
|
||||||
// for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
// for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
||||||
// for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
// for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
||||||
// mat(i,j) = rng();
|
// mat(i,j) = rg(rng);
|
||||||
// mat = ublas::triangular_adaptor<matrix, ublas::upper>(mat);
|
// mat = ublas::triangular_adaptor<matrix, ublas::upper>(mat);
|
||||||
// cout << " Assign matrix from triangular adaptor of self: " << mat << endl;
|
// cout << " Assign matrix from triangular adaptor of self: " << mat << endl;
|
||||||
// }
|
// }
|
||||||
|
|
Loading…
Reference in New Issue