update timing to use internal timing.h api
parent
b4eb0c233d
commit
93b4081c7f
|
@ -24,7 +24,6 @@
|
|||
#include <gtsam/discrete/DecisionTree-inl.h> // for convert only
|
||||
#define DISABLE_TIMING
|
||||
|
||||
#include <boost/timer.hpp>
|
||||
#include <boost/tokenizer.hpp>
|
||||
#include <boost/assign/std/map.hpp>
|
||||
#include <boost/assign/std/vector.hpp>
|
||||
|
@ -32,6 +31,7 @@ using namespace boost::assign;
|
|||
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <gtsam/discrete/Signature.h>
|
||||
#include <gtsam/base/timing.h>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
@ -75,16 +75,15 @@ void dot(const T&f, const string& filename) {
|
|||
// instrumented operators
|
||||
/* ******************************************************************************** */
|
||||
size_t muls = 0, adds = 0;
|
||||
boost::timer timer;
|
||||
double elapsed;
|
||||
void resetCounts() {
|
||||
muls = 0;
|
||||
adds = 0;
|
||||
timer.restart();
|
||||
}
|
||||
void printCounts(const string& s) {
|
||||
#ifndef DISABLE_TIMING
|
||||
cout << boost::format("%s: %3d muls, %3d adds, %g ms.") % s % muls % adds
|
||||
% (1000 * timer.elapsed()) << endl;
|
||||
% (1000 * elapsed) << endl;
|
||||
#endif
|
||||
resetCounts();
|
||||
}
|
||||
|
@ -148,6 +147,7 @@ TEST(ADT, joint)
|
|||
DiscreteKey A(0, 2), S(1, 2), T(2, 2), L(3, 2), B(4, 2), E(5, 2), X(6, 2), D(7, 2);
|
||||
|
||||
resetCounts();
|
||||
gttic_(asiaCPTs);
|
||||
ADT pA = create(A % "99/1");
|
||||
ADT pS = create(S % "50/50");
|
||||
ADT pT = create(T | A = "99/1 95/5");
|
||||
|
@ -156,10 +156,15 @@ TEST(ADT, joint)
|
|||
ADT pE = create((E | T, L) = "F T T T");
|
||||
ADT pX = create(X | E = "95/5 2/98");
|
||||
ADT pD = create((D | E, B) = "9/1 2/8 3/7 1/9");
|
||||
gttoc_(asiaCPTs);
|
||||
tictoc_getNode(asiaCPTsNode, asiaCPTs);
|
||||
elapsed = asiaCPTsNode->secs();
|
||||
tictoc_reset_();
|
||||
printCounts("Asia CPTs");
|
||||
|
||||
// Create joint
|
||||
resetCounts();
|
||||
gttic_(asiaJoint);
|
||||
ADT joint = pA;
|
||||
dot(joint, "Asia-A");
|
||||
joint = apply(joint, pS, &mul);
|
||||
|
@ -177,6 +182,10 @@ TEST(ADT, joint)
|
|||
joint = apply(joint, pD, &mul);
|
||||
dot(joint, "Asia-ASTLBEXD");
|
||||
EXPECT_LONGS_EQUAL(346, (long)muls);
|
||||
gttoc_(asiaJoint);
|
||||
tictoc_getNode(asiaJointNode, asiaJoint);
|
||||
elapsed = asiaJointNode->secs();
|
||||
tictoc_reset_();
|
||||
printCounts("Asia joint");
|
||||
|
||||
ADT pASTL = pA;
|
||||
|
@ -199,6 +208,7 @@ TEST(ADT, inference)
|
|||
B(2,2), L(3,2), E(4,2), S(5,2), T(6,2), X(7,2);
|
||||
|
||||
resetCounts();
|
||||
gttic_(infCPTs);
|
||||
ADT pA = create(A % "99/1");
|
||||
ADT pS = create(S % "50/50");
|
||||
ADT pT = create(T | A = "99/1 95/5");
|
||||
|
@ -207,10 +217,15 @@ TEST(ADT, inference)
|
|||
ADT pE = create((E | T, L) = "F T T T");
|
||||
ADT pX = create(X | E = "95/5 2/98");
|
||||
ADT pD = create((D | E, B) = "9/1 2/8 3/7 1/9");
|
||||
gttoc_(infCPTs);
|
||||
tictoc_getNode(infCPTsNode, infCPTs);
|
||||
elapsed = infCPTsNode->secs();
|
||||
tictoc_reset_();
|
||||
// printCounts("Inference CPTs");
|
||||
|
||||
// Create joint
|
||||
resetCounts();
|
||||
gttic_(asiaProd);
|
||||
ADT joint = pA;
|
||||
dot(joint, "Joint-Product-A");
|
||||
joint = apply(joint, pS, &mul);
|
||||
|
@ -228,8 +243,14 @@ TEST(ADT, inference)
|
|||
joint = apply(joint, pD, &mul);
|
||||
dot(joint, "Joint-Product-ASTLBEXD");
|
||||
EXPECT_LONGS_EQUAL(370, (long)muls); // different ordering
|
||||
gttoc_(asiaProd);
|
||||
tictoc_getNode(asiaProdNode, asiaProd);
|
||||
elapsed = asiaProdNode->secs();
|
||||
tictoc_reset_();
|
||||
printCounts("Asia product");
|
||||
|
||||
resetCounts();
|
||||
gttic_(asiaSum);
|
||||
ADT marginal = joint;
|
||||
marginal = marginal.combine(X, &add_);
|
||||
dot(marginal, "Joint-Sum-ADBLEST");
|
||||
|
@ -240,6 +261,10 @@ TEST(ADT, inference)
|
|||
marginal = marginal.combine(E, &add_);
|
||||
dot(marginal, "Joint-Sum-ADBL");
|
||||
EXPECT_LONGS_EQUAL(161, (long)adds);
|
||||
gttoc_(asiaSum);
|
||||
tictoc_getNode(asiaSumNode, asiaSum);
|
||||
elapsed = asiaSumNode->secs();
|
||||
tictoc_reset_();
|
||||
printCounts("Asia sum");
|
||||
}
|
||||
|
||||
|
@ -249,6 +274,7 @@ TEST(ADT, factor_graph)
|
|||
DiscreteKey B(0,2), L(1,2), E(2,2), S(3,2), T(4,2), X(5,2);
|
||||
|
||||
resetCounts();
|
||||
gttic_(createCPTs);
|
||||
ADT pS = create(S % "50/50");
|
||||
ADT pT = create(T % "95/5");
|
||||
ADT pL = create(L | S = "99/1 90/10");
|
||||
|
@ -256,10 +282,15 @@ TEST(ADT, factor_graph)
|
|||
ADT pX = create(X | E = "95/5 2/98");
|
||||
ADT pD = create(B | E = "1/8 7/9");
|
||||
ADT pB = create(B | S = "70/30 40/60");
|
||||
gttoc_(createCPTs);
|
||||
tictoc_getNode(createCPTsNode, createCPTs);
|
||||
elapsed = createCPTsNode->secs();
|
||||
tictoc_reset_();
|
||||
// printCounts("Create CPTs");
|
||||
|
||||
// Create joint
|
||||
resetCounts();
|
||||
gttic_(asiaFG);
|
||||
ADT fg = pS;
|
||||
fg = apply(fg, pT, &mul);
|
||||
fg = apply(fg, pL, &mul);
|
||||
|
@ -269,8 +300,14 @@ TEST(ADT, factor_graph)
|
|||
fg = apply(fg, pD, &mul);
|
||||
dot(fg, "FactorGraph");
|
||||
EXPECT_LONGS_EQUAL(158, (long)muls);
|
||||
gttoc_(asiaFG);
|
||||
tictoc_getNode(asiaFGNode, asiaFG);
|
||||
elapsed = asiaFGNode->secs();
|
||||
tictoc_reset_();
|
||||
printCounts("Asia FG");
|
||||
|
||||
resetCounts();
|
||||
gttic_(marg);
|
||||
fg = fg.combine(X, &add_);
|
||||
dot(fg, "Marginalized-6X");
|
||||
fg = fg.combine(T, &add_);
|
||||
|
@ -282,49 +319,83 @@ TEST(ADT, factor_graph)
|
|||
fg = fg.combine(L, &add_);
|
||||
dot(fg, "Marginalized-2L");
|
||||
EXPECT(adds = 54);
|
||||
gttoc_(marg);
|
||||
tictoc_getNode(margNode, marg);
|
||||
elapsed = margNode->secs();
|
||||
tictoc_reset_();
|
||||
printCounts("marginalize");
|
||||
|
||||
// BLESTX
|
||||
|
||||
// Eliminate X
|
||||
resetCounts();
|
||||
gttic_(elimX);
|
||||
ADT fE = pX;
|
||||
dot(fE, "Eliminate-01-fEX");
|
||||
fE = fE.combine(X, &add_);
|
||||
dot(fE, "Eliminate-02-fE");
|
||||
gttoc_(elimX);
|
||||
tictoc_getNode(elimXNode, elimX);
|
||||
elapsed = elimXNode->secs();
|
||||
tictoc_reset_();
|
||||
printCounts("Eliminate X");
|
||||
|
||||
// Eliminate T
|
||||
resetCounts();
|
||||
gttic_(elimT);
|
||||
ADT fLE = pT;
|
||||
fLE = apply(fLE, pE, &mul);
|
||||
dot(fLE, "Eliminate-03-fLET");
|
||||
fLE = fLE.combine(T, &add_);
|
||||
dot(fLE, "Eliminate-04-fLE");
|
||||
gttoc_(elimT);
|
||||
tictoc_getNode(elimTNode, elimT);
|
||||
elapsed = elimTNode->secs();
|
||||
tictoc_reset_();
|
||||
printCounts("Eliminate T");
|
||||
|
||||
// Eliminate S
|
||||
resetCounts();
|
||||
gttic_(elimS);
|
||||
ADT fBL = pS;
|
||||
fBL = apply(fBL, pL, &mul);
|
||||
fBL = apply(fBL, pB, &mul);
|
||||
dot(fBL, "Eliminate-05-fBLS");
|
||||
fBL = fBL.combine(S, &add_);
|
||||
dot(fBL, "Eliminate-06-fBL");
|
||||
gttoc_(elimS);
|
||||
tictoc_getNode(elimSNode, elimS);
|
||||
elapsed = elimSNode->secs();
|
||||
tictoc_reset_();
|
||||
printCounts("Eliminate S");
|
||||
|
||||
// Eliminate E
|
||||
resetCounts();
|
||||
gttic_(elimE);
|
||||
ADT fBL2 = fE;
|
||||
fBL2 = apply(fBL2, fLE, &mul);
|
||||
fBL2 = apply(fBL2, pD, &mul);
|
||||
dot(fBL2, "Eliminate-07-fBLE");
|
||||
fBL2 = fBL2.combine(E, &add_);
|
||||
dot(fBL2, "Eliminate-08-fBL2");
|
||||
gttoc_(elimE);
|
||||
tictoc_getNode(elimENode, elimE);
|
||||
elapsed = elimENode->secs();
|
||||
tictoc_reset_();
|
||||
printCounts("Eliminate E");
|
||||
|
||||
// Eliminate L
|
||||
resetCounts();
|
||||
gttic_(elimL);
|
||||
ADT fB = fBL;
|
||||
fB = apply(fB, fBL2, &mul);
|
||||
dot(fB, "Eliminate-09-fBL");
|
||||
fB = fB.combine(L, &add_);
|
||||
dot(fB, "Eliminate-10-fB");
|
||||
gttoc_(elimL);
|
||||
tictoc_getNode(elimLNode, elimL);
|
||||
elapsed = elimLNode->secs();
|
||||
tictoc_reset_();
|
||||
printCounts("Eliminate L");
|
||||
}
|
||||
|
||||
|
|
|
@ -17,7 +17,6 @@
|
|||
* @date Jan 30, 2012
|
||||
*/
|
||||
|
||||
#include <boost/timer.hpp>
|
||||
#include <boost/assign/std/vector.hpp>
|
||||
using namespace boost::assign;
|
||||
|
||||
|
|
|
@ -15,7 +15,8 @@
|
|||
#include <vector>
|
||||
#include <boost/tuple/tuple.hpp>
|
||||
#include <boost/shared_array.hpp>
|
||||
#include <boost/timer.hpp>
|
||||
|
||||
#include <gtsam/base/timing.h>
|
||||
|
||||
#include "FindSeparator.h"
|
||||
|
||||
|
|
|
@ -16,11 +16,11 @@
|
|||
* @date Oct 26, 2013
|
||||
*/
|
||||
|
||||
#include <gtsam/base/timing.h>
|
||||
#include <gtsam/base/DSFVector.h>
|
||||
#include <gtsam_unstable/base/DSF.h>
|
||||
#include <gtsam/base/DSFMap.h>
|
||||
|
||||
#include <boost/timer.hpp>
|
||||
#include <boost/format.hpp>
|
||||
#include <boost/assign/std/vector.hpp>
|
||||
|
||||
|
@ -33,7 +33,6 @@
|
|||
using namespace std;
|
||||
using namespace gtsam;
|
||||
using namespace boost::assign;
|
||||
using boost::timer;
|
||||
using boost::format;
|
||||
|
||||
int main(int argc, char* argv[]) {
|
||||
|
@ -61,7 +60,7 @@ int main(int argc, char* argv[]) {
|
|||
cout << "Generating " << nm << " matches" << endl;
|
||||
std::mt19937 rng;
|
||||
std::uniform_int_distribution<> rn(0, N - 1);
|
||||
|
||||
|
||||
typedef pair<size_t, size_t> Match;
|
||||
vector<Match> matches;
|
||||
matches.reserve(nm);
|
||||
|
@ -72,46 +71,66 @@ int main(int argc, char* argv[]) {
|
|||
|
||||
{
|
||||
// DSFBase version
|
||||
timer tim;
|
||||
double dsftime = 0;
|
||||
gttic_(dsftime);
|
||||
DSFBase dsf(N); // Allow for N keys
|
||||
for(const Match& m: matches)
|
||||
dsf.merge(m.first, m.second);
|
||||
os << tim.elapsed() << ",";
|
||||
cout << format("DSFBase: %1% s") % tim.elapsed() << endl;
|
||||
gttoc_(dsftime);
|
||||
tictoc_getNode(dsftimeNode, dsftime);
|
||||
dsftime = dsftimeNode->secs();
|
||||
os << dsftime << ",";
|
||||
cout << format("DSFBase: %1% s") % dsftime << endl;
|
||||
tictoc_reset_();
|
||||
}
|
||||
|
||||
{
|
||||
// DSFMap version
|
||||
timer tim;
|
||||
double dsftime = 0;
|
||||
gttic_(dsftime);
|
||||
DSFMap<size_t> dsf;
|
||||
for(const Match& m: matches)
|
||||
dsf.merge(m.first, m.second);
|
||||
os << tim.elapsed() << endl;
|
||||
cout << format("DSFMap: %1% s") % tim.elapsed() << endl;
|
||||
gttoc_(dsftime);
|
||||
tictoc_getNode(dsftimeNode, dsftime);
|
||||
dsftime = dsftimeNode->secs();
|
||||
os << dsftime << endl;
|
||||
cout << format("DSFMap: %1% s") % dsftime << endl;
|
||||
tictoc_reset_();
|
||||
}
|
||||
|
||||
if (false) {
|
||||
// DSF version, functional
|
||||
timer tim;
|
||||
double dsftime = 0;
|
||||
gttic_(dsftime);
|
||||
DSF<size_t> dsf;
|
||||
for (size_t j = 0; j < N; j++)
|
||||
dsf = dsf.makeSet(j);
|
||||
for(const Match& m: matches)
|
||||
dsf = dsf.makeUnion(m.first, m.second);
|
||||
os << tim.elapsed() << endl;
|
||||
cout << format("DSF functional: %1% s") % tim.elapsed() << endl;
|
||||
gttoc_(dsftime);
|
||||
tictoc_getNode(dsftimeNode, dsftime);
|
||||
dsftime = dsftimeNode->secs();
|
||||
os << dsftime << endl;
|
||||
cout << format("DSF functional: %1% s") % dsftime << endl;
|
||||
tictoc_reset_();
|
||||
}
|
||||
|
||||
if (false) {
|
||||
// DSF version, in place - always slower - use functional !
|
||||
timer tim;
|
||||
double dsftime = 0;
|
||||
gttic_(dsftime);
|
||||
DSF<size_t> dsf;
|
||||
for (size_t j = 0; j < N; j++)
|
||||
dsf.makeSetInPlace(j);
|
||||
for(const Match& m: matches)
|
||||
dsf.makeUnionInPlace(m.first, m.second);
|
||||
os << tim.elapsed() << ",";
|
||||
cout << format("DSF in-place: %1% s") % tim.elapsed() << endl;
|
||||
gttoc_(dsftime);
|
||||
tictoc_getNode(dsftimeNode, dsftime);
|
||||
dsftime = dsftimeNode->secs();
|
||||
os << dsftime << ",";
|
||||
cout << format("DSF in-place: %1% s") % dsftime << endl;
|
||||
tictoc_reset_();
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
*/
|
||||
|
||||
#include <iostream>
|
||||
#include <boost/timer.hpp>
|
||||
#include <gtsam/base/timing.h>
|
||||
#include <gtsam/base/Matrix.h>
|
||||
|
||||
using namespace std;
|
||||
|
@ -54,7 +54,7 @@ double timeCollect(size_t p, size_t m, size_t n, bool passDims, size_t reps) {
|
|||
Matrix result;
|
||||
double elapsed;
|
||||
{
|
||||
boost::timer t;
|
||||
gttic_(elapsed);
|
||||
|
||||
if (passDims)
|
||||
for (size_t i=0; i<reps; ++i)
|
||||
|
@ -62,7 +62,11 @@ double timeCollect(size_t p, size_t m, size_t n, bool passDims, size_t reps) {
|
|||
else
|
||||
for (size_t i=0; i<reps; ++i)
|
||||
result = collect(matrices);
|
||||
elapsed = t.elapsed();
|
||||
|
||||
gttoc_(elapsed);
|
||||
tictoc_getNode(elapsedNode, elapsed);
|
||||
elapsed = elapsedNode->secs();
|
||||
tictoc_reset_();
|
||||
}
|
||||
// delete the matrices
|
||||
for (size_t i=0; i<p;++i) {
|
||||
|
@ -95,10 +99,15 @@ double timeVScaleColumn(size_t m, size_t n, size_t reps) {
|
|||
double elapsed;
|
||||
Matrix result;
|
||||
{
|
||||
boost::timer t;
|
||||
gttic_(elapsed);
|
||||
|
||||
for (size_t i=0; i<reps; ++i)
|
||||
Matrix result = vector_scale(M,V);
|
||||
elapsed = t.elapsed();
|
||||
|
||||
gttoc_(elapsed);
|
||||
tictoc_getNode(elapsedNode, elapsed);
|
||||
elapsed = elapsedNode->secs();
|
||||
tictoc_reset_();
|
||||
}
|
||||
|
||||
return elapsed;
|
||||
|
@ -126,10 +135,15 @@ double timeVScaleRow(size_t m, size_t n, size_t reps) {
|
|||
double elapsed;
|
||||
Matrix result;
|
||||
{
|
||||
boost::timer t;
|
||||
gttic_(elapsed);
|
||||
|
||||
for (size_t i=0; i<reps; ++i)
|
||||
result = vector_scale(V,M);
|
||||
elapsed = t.elapsed();
|
||||
|
||||
gttoc_(elapsed);
|
||||
tictoc_getNode(elapsedNode, elapsed);
|
||||
elapsed = elapsedNode->secs();
|
||||
tictoc_reset_();
|
||||
}
|
||||
|
||||
return elapsed;
|
||||
|
@ -156,12 +170,17 @@ double timeColumn(size_t reps) {
|
|||
double elapsed;
|
||||
Vector result;
|
||||
{
|
||||
boost::timer t;
|
||||
gttic_(elapsed);
|
||||
|
||||
for (size_t i=0; i<reps; ++i)
|
||||
for (size_t j = 0; j<n; ++j)
|
||||
//result = ublas::matrix_column<Matrix>(M, j);
|
||||
result = column(M, j);
|
||||
elapsed = t.elapsed();
|
||||
|
||||
gttoc_(elapsed);
|
||||
tictoc_getNode(elapsedNode, elapsed);
|
||||
elapsed = elapsedNode->secs();
|
||||
tictoc_reset_();
|
||||
}
|
||||
return elapsed;
|
||||
}
|
||||
|
@ -198,12 +217,17 @@ double timeHouseholder(size_t reps) {
|
|||
// perform timing
|
||||
double elapsed;
|
||||
{
|
||||
boost::timer t;
|
||||
gttic_(elapsed);
|
||||
|
||||
for (size_t i=0; i<reps; ++i) {
|
||||
Matrix A = Abase;
|
||||
householder_(A,3);
|
||||
}
|
||||
elapsed = t.elapsed();
|
||||
|
||||
gttoc_(elapsed);
|
||||
tictoc_getNode(elapsedNode, elapsed);
|
||||
elapsed = elapsedNode->secs();
|
||||
tictoc_reset_();
|
||||
}
|
||||
return elapsed;
|
||||
}
|
||||
|
@ -222,13 +246,18 @@ double timeMatrixInsert(size_t reps) {
|
|||
// perform timing
|
||||
double elapsed;
|
||||
{
|
||||
boost::timer t;
|
||||
gttic_(elapsed);
|
||||
|
||||
Matrix big = bigBase;
|
||||
for (size_t rep=0; rep<reps; ++rep)
|
||||
for (size_t i=0; i<100; i += 5)
|
||||
for (size_t j=0; j<100; j += 5)
|
||||
insertSub(big, small, i,j);
|
||||
elapsed = t.elapsed();
|
||||
|
||||
gttoc_(elapsed);
|
||||
tictoc_getNode(elapsedNode, elapsed);
|
||||
elapsed = elapsedNode->secs();
|
||||
tictoc_reset_();
|
||||
}
|
||||
return elapsed;
|
||||
}
|
||||
|
|
|
@ -17,10 +17,10 @@
|
|||
*/
|
||||
|
||||
#include <boost/random.hpp>
|
||||
#include <boost/timer.hpp>
|
||||
#include <boost/format.hpp>
|
||||
#include <boost/lambda/lambda.hpp>
|
||||
|
||||
#include <gtsam/base/timing.h>
|
||||
#include <gtsam/base/Matrix.h>
|
||||
|
||||
#include <iostream>
|
||||
|
@ -30,7 +30,6 @@
|
|||
using namespace std;
|
||||
//namespace ublas = boost::numeric::ublas;
|
||||
//using namespace Eigen;
|
||||
using boost::timer;
|
||||
using boost::format;
|
||||
using namespace boost::lambda;
|
||||
|
||||
|
@ -68,7 +67,6 @@ int main(int argc, char* argv[]) {
|
|||
cout << endl;
|
||||
|
||||
{
|
||||
timer tim;
|
||||
double basicTime, fullTime, topTime, blockTime;
|
||||
|
||||
cout << "Row-major matrix, row-major assignment:" << endl;
|
||||
|
@ -79,43 +77,54 @@ int main(int argc, char* argv[]) {
|
|||
for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
||||
mat(i,j) = rng();
|
||||
|
||||
tim.restart();
|
||||
gttic_(basicTime);
|
||||
for(size_t rep=0; rep<nReps; ++rep)
|
||||
for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
||||
for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
||||
mat(i,j) = rng();
|
||||
basicTime = tim.elapsed();
|
||||
gttoc_(basicTime);
|
||||
tictoc_getNode(basicTimeNode, basicTime);
|
||||
basicTime = basicTimeNode->secs();
|
||||
gtsam::tictoc_reset_();
|
||||
cout << format(" Basic: %1% mus/element") % double(1000000 * basicTime / double(mat.rows()*mat.cols()*nReps)) << endl;
|
||||
|
||||
tim.restart();
|
||||
gttic_(fullTime);
|
||||
for(size_t rep=0; rep<nReps; ++rep)
|
||||
for(size_t i=0; i<(size_t)full.rows(); ++i)
|
||||
for(size_t j=0; j<(size_t)full.cols(); ++j)
|
||||
full(i,j) = rng();
|
||||
fullTime = tim.elapsed();
|
||||
gttoc_(fullTime);
|
||||
tictoc_getNode(fullTimeNode, fullTime);
|
||||
fullTime = fullTimeNode->secs();
|
||||
gtsam::tictoc_reset_();
|
||||
cout << format(" Full: %1% mus/element") % double(1000000 * fullTime / double(full.rows()*full.cols()*nReps)) << endl;
|
||||
|
||||
tim.restart();
|
||||
gttic_(topTime);
|
||||
for(size_t rep=0; rep<nReps; ++rep)
|
||||
for(size_t i=0; i<(size_t)top.rows(); ++i)
|
||||
for(size_t j=0; j<(size_t)top.cols(); ++j)
|
||||
top(i,j) = rng();
|
||||
topTime = tim.elapsed();
|
||||
gttoc_(topTime);
|
||||
tictoc_getNode(topTimeNode, topTime);
|
||||
topTime = topTimeNode->secs();
|
||||
gtsam::tictoc_reset_();
|
||||
cout << format(" Top: %1% mus/element") % double(1000000 * topTime / double(top.rows()*top.cols()*nReps)) << endl;
|
||||
|
||||
tim.restart();
|
||||
gttic_(blockTime);
|
||||
for(size_t rep=0; rep<nReps; ++rep)
|
||||
for(size_t i=0; i<(size_t)block.rows(); ++i)
|
||||
for(size_t j=0; j<(size_t)block.cols(); ++j)
|
||||
block(i,j) = rng();
|
||||
blockTime = tim.elapsed();
|
||||
gttoc_(blockTime);
|
||||
tictoc_getNode(blockTimeNode, blockTime);
|
||||
blockTime = blockTimeNode->secs();
|
||||
gtsam::tictoc_reset_();
|
||||
cout << format(" Block: %1% mus/element") % double(1000000 * blockTime / double(block.rows()*block.cols()*nReps)) << endl;
|
||||
|
||||
cout << endl;
|
||||
}
|
||||
|
||||
{
|
||||
timer tim;
|
||||
double basicTime, fullTime, topTime, blockTime;
|
||||
|
||||
cout << "Row-major matrix, column-major assignment:" << endl;
|
||||
|
@ -126,43 +135,54 @@ int main(int argc, char* argv[]) {
|
|||
for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
||||
mat(i,j) = rng();
|
||||
|
||||
tim.restart();
|
||||
gttic_(basicTime);
|
||||
for(size_t rep=0; rep<nReps; ++rep)
|
||||
for(size_t j=0; j<(size_t)mat.cols(); ++j)
|
||||
for(size_t i=0; i<(size_t)mat.rows(); ++i)
|
||||
mat(i,j) = rng();
|
||||
basicTime = tim.elapsed();
|
||||
gttoc_(basicTime);
|
||||
tictoc_getNode(basicTimeNode, basicTime);
|
||||
basicTime = basicTimeNode->secs();
|
||||
gtsam::tictoc_reset_();
|
||||
cout << format(" Basic: %1% mus/element") % double(1000000 * basicTime / double(mat.rows()*mat.cols()*nReps)) << endl;
|
||||
|
||||
tim.restart();
|
||||
gttic_(fullTime);
|
||||
for(size_t rep=0; rep<nReps; ++rep)
|
||||
for(size_t j=0; j<(size_t)full.cols(); ++j)
|
||||
for(size_t i=0; i<(size_t)full.rows(); ++i)
|
||||
full(i,j) = rng();
|
||||
fullTime = tim.elapsed();
|
||||
gttoc_(fullTime);
|
||||
tictoc_getNode(fullTimeNode, fullTime);
|
||||
fullTime = fullTimeNode->secs();
|
||||
gtsam::tictoc_reset_();
|
||||
cout << format(" Full: %1% mus/element") % double(1000000 * fullTime / double(full.rows()*full.cols()*nReps)) << endl;
|
||||
|
||||
tim.restart();
|
||||
gttic_(topTime);
|
||||
for(size_t rep=0; rep<nReps; ++rep)
|
||||
for(size_t j=0; j<(size_t)top.cols(); ++j)
|
||||
for(size_t i=0; i<(size_t)top.rows(); ++i)
|
||||
top(i,j) = rng();
|
||||
topTime = tim.elapsed();
|
||||
gttoc_(topTime);
|
||||
tictoc_getNode(topTimeNode, topTime);
|
||||
topTime = topTimeNode->secs();
|
||||
gtsam::tictoc_reset_();
|
||||
cout << format(" Top: %1% mus/element") % double(1000000 * topTime / double(top.rows()*top.cols()*nReps)) << endl;
|
||||
|
||||
tim.restart();
|
||||
gttic_(blockTime);
|
||||
for(size_t rep=0; rep<nReps; ++rep)
|
||||
for(size_t j=0; j<(size_t)block.cols(); ++j)
|
||||
for(size_t i=0; i<(size_t)block.rows(); ++i)
|
||||
block(i,j) = rng();
|
||||
blockTime = tim.elapsed();
|
||||
gttoc_(blockTime);
|
||||
tictoc_getNode(blockTimeNode, blockTime);
|
||||
blockTime = blockTimeNode->secs();
|
||||
gtsam::tictoc_reset_();
|
||||
cout << format(" Block: %1% mus/element") % double(1000000 * blockTime / double(block.rows()*block.cols()*nReps)) << endl;
|
||||
|
||||
cout << endl;
|
||||
}
|
||||
|
||||
{
|
||||
timer tim;
|
||||
double basicTime, fullTime, topTime, blockTime;
|
||||
typedef pair<size_t,size_t> ij_t;
|
||||
vector<ij_t> ijs(100000);
|
||||
|
@ -174,28 +194,44 @@ int main(int argc, char* argv[]) {
|
|||
for(size_t rep=0; rep<1000; ++rep)
|
||||
for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = rng(); }
|
||||
|
||||
gttic_(basicTime);
|
||||
for_each(ijs.begin(), ijs.end(), _1 = make_pair(rni(),rnj()));
|
||||
for(size_t rep=0; rep<1000; ++rep)
|
||||
for(const ij_t& ij: ijs) { mat(ij.first, ij.second) = rng(); }
|
||||
basicTime = tim.elapsed();
|
||||
gttoc_(basicTime);
|
||||
tictoc_getNode(basicTimeNode, basicTime);
|
||||
basicTime = basicTimeNode->secs();
|
||||
gtsam::tictoc_reset_();
|
||||
cout << format(" Basic: %1% mus/element") % double(1000000 * basicTime / double(ijs.size()*nReps)) << endl;
|
||||
|
||||
gttic_(fullTime);
|
||||
for_each(ijs.begin(), ijs.end(), _1 = make_pair(rni(),rnj()));
|
||||
for(size_t rep=0; rep<1000; ++rep)
|
||||
for(const ij_t& ij: ijs) { full(ij.first, ij.second) = rng(); }
|
||||
fullTime = tim.elapsed();
|
||||
gttoc_(fullTime);
|
||||
tictoc_getNode(fullTimeNode, fullTime);
|
||||
fullTime = fullTimeNode->secs();
|
||||
gtsam::tictoc_reset_();
|
||||
cout << format(" Full: %1% mus/element") % double(1000000 * fullTime / double(ijs.size()*nReps)) << endl;
|
||||
|
||||
gttic_(topTime);
|
||||
for_each(ijs.begin(), ijs.end(), _1 = make_pair(rni()%top.rows(),rnj()));
|
||||
for(size_t rep=0; rep<1000; ++rep)
|
||||
for(const ij_t& ij: ijs) { top(ij.first, ij.second) = rng(); }
|
||||
topTime = tim.elapsed();
|
||||
gttoc_(topTime);
|
||||
tictoc_getNode(topTimeNode, topTime);
|
||||
topTime = topTimeNode->secs();
|
||||
gtsam::tictoc_reset_();
|
||||
cout << format(" Top: %1% mus/element") % double(1000000 * topTime / double(ijs.size()*nReps)) << endl;
|
||||
|
||||
gttic_(blockTime);
|
||||
for_each(ijs.begin(), ijs.end(), _1 = make_pair(rni()%block.rows(),rnj()%block.cols()));
|
||||
for(size_t rep=0; rep<1000; ++rep)
|
||||
for(const ij_t& ij: ijs) { block(ij.first, ij.second) = rng(); }
|
||||
blockTime = tim.elapsed();
|
||||
gttoc_(blockTime);
|
||||
tictoc_getNode(blockTimeNode, blockTime);
|
||||
blockTime = blockTimeNode->secs();
|
||||
gtsam::tictoc_reset_();
|
||||
cout << format(" Block: %1% mus/element") % double(1000000 * blockTime / double(ijs.size()*nReps)) << endl;
|
||||
|
||||
cout << endl;
|
||||
|
|
Loading…
Reference in New Issue