replace boost::format
parent
616b366d8a
commit
9347f35ae5
|
@ -31,7 +31,6 @@
|
|||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
|
||||
#include <boost/format.hpp>
|
||||
#include <vector>
|
||||
|
||||
using namespace std;
|
||||
|
@ -50,8 +49,7 @@ int main(int argc, char* argv[]) {
|
|||
|
||||
// Load the SfM data from file
|
||||
SfmData mydata = SfmData::FromBalFile(filename);
|
||||
cout << boost::format("read %1% tracks on %2% cameras\n") %
|
||||
mydata.numberTracks() % mydata.numberCameras();
|
||||
cout << "read " << mydata.numberTracks() << " tracks on " << mydata.numberCameras() << " cameras" << endl;
|
||||
|
||||
// Create a factor graph
|
||||
ExpressionFactorGraph graph;
|
||||
|
|
|
@ -23,7 +23,6 @@
|
|||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
|
||||
#include <boost/format.hpp>
|
||||
#include <vector>
|
||||
|
||||
using namespace std;
|
||||
|
@ -45,7 +44,7 @@ int main (int argc, char* argv[]) {
|
|||
|
||||
// Load the SfM data from file
|
||||
SfmData mydata = SfmData::FromBalFile(filename);
|
||||
cout << boost::format("read %1% tracks on %2% cameras\n") % mydata.numberTracks() % mydata.numberCameras();
|
||||
cout << "read " << mydata.numberTracks() << " tracks on " << mydata.numberCameras() << " cameras" << endl;
|
||||
|
||||
// Create a factor graph
|
||||
NonlinearFactorGraph graph;
|
||||
|
|
|
@ -26,7 +26,6 @@
|
|||
#include <gtsam/inference/Ordering.h>
|
||||
#include <gtsam/base/timing.h>
|
||||
|
||||
#include <boost/format.hpp>
|
||||
#include <vector>
|
||||
|
||||
using namespace std;
|
||||
|
@ -47,8 +46,7 @@ int main(int argc, char* argv[]) {
|
|||
|
||||
// Load the SfM data from file
|
||||
SfmData mydata = SfmData::FromBalFile(filename);
|
||||
cout << boost::format("read %1% tracks on %2% cameras\n") %
|
||||
mydata.numberTracks() % mydata.numberCameras();
|
||||
cout << "read " << mydata.numberTracks() << " tracks on " << mydata.numberCameras() << " cameras" << endl;
|
||||
|
||||
// Create a factor graph
|
||||
NonlinearFactorGraph graph;
|
||||
|
@ -130,9 +128,9 @@ int main(int argc, char* argv[]) {
|
|||
cout << endl << endl;
|
||||
|
||||
cout << "Time comparison by solving " << filename << " results:" << endl;
|
||||
cout << boost::format("%1% point tracks and %2% cameras\n") %
|
||||
mydata.numberTracks() % mydata.numberCameras()
|
||||
<< endl;
|
||||
|
||||
cout << mydata.numberTracks() << " point tracks and " << mydata.numberCameras()
|
||||
<< " cameras" << endl;
|
||||
|
||||
tictoc_print_();
|
||||
}
|
||||
|
|
|
@ -21,7 +21,6 @@
|
|||
#include <gtsam/discrete/DiscreteValues.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
|
||||
#include <boost/format.hpp>
|
||||
#include <map>
|
||||
|
||||
namespace gtsam {
|
||||
|
@ -86,13 +85,13 @@ class GTSAM_UNSTABLE_EXPORT Constraint : public DiscreteFactor {
|
|||
/// Render as markdown table.
|
||||
std::string markdown(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
|
||||
const Names& names = {}) const override {
|
||||
return (boost::format("`Constraint` on %1% variables\n") % (size())).str();
|
||||
return "`Constraint` on " + std::to_string(size()) + " variables\n";
|
||||
}
|
||||
|
||||
/// Render as html table.
|
||||
std::string html(const KeyFormatter& keyFormatter = DefaultKeyFormatter,
|
||||
const Names& names = {}) const override {
|
||||
return (boost::format("<p>Constraint on %1% variables</p>") % (size())).str();
|
||||
return "<p>Constraint on " + std::to_string(size()) + " variables</p>";
|
||||
}
|
||||
|
||||
/// @}
|
||||
|
|
|
@ -12,8 +12,6 @@
|
|||
#include <gtsam/base/debug.h>
|
||||
#include <gtsam/base/timing.h>
|
||||
|
||||
#include <boost/format.hpp>
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
using namespace std;
|
||||
|
@ -171,8 +169,8 @@ void solveStaged(size_t addMutex = 2) {
|
|||
|
||||
// remove this slot from consideration
|
||||
slotsAvailable[bestSlot] = 0.0;
|
||||
cout << boost::format("%s = %d (%d), count = %d") % scheduler.studentName(6-s)
|
||||
% scheduler.slotName(bestSlot) % bestSlot % count << endl;
|
||||
cout << scheduler.studentName(6 - s) << " = " << scheduler.slotName(bestSlot) << " (" << bestSlot
|
||||
<< "), count = " << count << endl;
|
||||
}
|
||||
tictoc_print_();
|
||||
|
||||
|
@ -229,9 +227,8 @@ void sampleSolutions() {
|
|||
size_t min = *min_element(stats.begin(), stats.end());
|
||||
size_t nz = count_if(stats.begin(), stats.end(), NonZero);
|
||||
if (nz >= 15 && max <= 2) {
|
||||
cout << boost::format(
|
||||
"Sampled schedule %d, min = %d, nz = %d, max = %d\n") % (n + 1) % min
|
||||
% nz % max;
|
||||
cout << "Sampled schedule " << (n + 1) << ", min = " << min << ", nz = " << nz
|
||||
<< ", max = " << max << endl;
|
||||
for (size_t i = 0; i < 7; i++) {
|
||||
cout << schedulers[i].studentName(0) << " : " << schedulers[i].slotName(
|
||||
slots[i]) << endl;
|
||||
|
@ -320,9 +317,8 @@ void accomodateStudent() {
|
|||
DiscreteValues values;
|
||||
values[dkey.first] = bestSlot;
|
||||
size_t count = (*root)(values);
|
||||
cout << boost::format("%s = %d (%d), count = %d") % scheduler.studentName(0)
|
||||
% scheduler.slotName(bestSlot) % bestSlot % count << endl;
|
||||
|
||||
cout << scheduler.studentName(0) << " = " << scheduler.slotName(bestSlot) << " (" << bestSlot
|
||||
<< "), count = " << count << endl;
|
||||
// sample schedules
|
||||
for (size_t n = 0; n < 10; n++) {
|
||||
auto sample0 = chordal->sample();
|
||||
|
|
|
@ -12,8 +12,6 @@
|
|||
#include <gtsam/base/debug.h>
|
||||
#include <gtsam/base/timing.h>
|
||||
|
||||
#include <boost/format.hpp>
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
using namespace std;
|
||||
|
@ -196,8 +194,9 @@ void solveStaged(size_t addMutex = 2) {
|
|||
|
||||
// remove this slot from consideration
|
||||
slotsAvailable[bestSlot] = 0.0;
|
||||
cout << boost::format("%s = %d (%d), count = %d") % scheduler.studentName(NRSTUDENTS-1-s)
|
||||
% scheduler.slotName(bestSlot) % bestSlot % count << endl;
|
||||
cout << scheduler.studentName(NRSTUDENTS - 1 - s) << " = " <<
|
||||
scheduler.slotName(bestSlot) << " (" << bestSlot
|
||||
<< "), count = " << count << endl;
|
||||
}
|
||||
tictoc_print_();
|
||||
}
|
||||
|
@ -238,9 +237,8 @@ void sampleSolutions() {
|
|||
size_t min = *min_element(stats.begin(), stats.end());
|
||||
size_t nz = count_if(stats.begin(), stats.end(), NonZero);
|
||||
if (nz >= 15 && max <= 2) {
|
||||
cout << boost::format(
|
||||
"Sampled schedule %d, min = %d, nz = %d, max = %d\n") % (n + 1) % min
|
||||
% nz % max;
|
||||
cout << "Sampled schedule " << (n + 1) << ", min = " << min
|
||||
<< ", nz = " << nz << ", max = " << max << endl;
|
||||
for (size_t i = 0; i < NRSTUDENTS; i++) {
|
||||
cout << schedulers[i].studentName(0) << " : " << schedulers[i].slotName(
|
||||
slots[i]) << endl;
|
||||
|
|
|
@ -12,8 +12,6 @@
|
|||
#include <gtsam/base/debug.h>
|
||||
#include <gtsam/base/timing.h>
|
||||
|
||||
#include <boost/format.hpp>
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
using namespace std;
|
||||
|
@ -218,8 +216,8 @@ void solveStaged(size_t addMutex = 2) {
|
|||
|
||||
// remove this slot from consideration
|
||||
slotsAvailable[bestSlot] = 0.0;
|
||||
cout << boost::format("%s = %d (%d), count = %d") % scheduler.studentName(NRSTUDENTS-1-s)
|
||||
% scheduler.slotName(bestSlot) % bestSlot % count << endl;
|
||||
cout << scheduler.studentName(NRSTUDENTS - 1 - s) << " = " << scheduler.slotName(bestSlot) << " (" << bestSlot
|
||||
<< "), count = " << count << endl;
|
||||
}
|
||||
tictoc_print_();
|
||||
}
|
||||
|
@ -263,9 +261,7 @@ void sampleSolutions() {
|
|||
size_t min = *min_element(stats.begin(), stats.end());
|
||||
size_t nz = count_if(stats.begin(), stats.end(), NonZero);
|
||||
if (nz >= 16 && max <= 3) {
|
||||
cout << boost::format(
|
||||
"Sampled schedule %d, min = %d, nz = %d, max = %d\n") % (n + 1) % min
|
||||
% nz % max;
|
||||
cout << "Sampled schedule " << n + 1 << ", min = " << min << ", nz = " << nz << ", max = " << max << endl;
|
||||
for (size_t i = 0; i < NRSTUDENTS; i++) {
|
||||
cout << schedulers[i].studentName(0) << " : " << schedulers[i].slotName(
|
||||
slots[i]) << endl;
|
||||
|
|
|
@ -71,7 +71,7 @@ class LoopyBelief {
|
|||
void print(const std::string& s = "") const {
|
||||
cout << s << ":" << endl;
|
||||
for (const auto& [key, _] : starGraphs_) {
|
||||
starGraphs_.at(key).print((boost::format("Node %d:") % key).str());
|
||||
starGraphs_.at(key).print("Node " + std::to_string(key) + ":");
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -127,9 +127,11 @@ class LoopyBelief {
|
|||
val[key] = v;
|
||||
sum += (*beliefAtKey)(val);
|
||||
}
|
||||
// TODO(kartikarcot): Check if this makes sense
|
||||
string sumFactorTable;
|
||||
for (size_t v = 0; v < allDiscreteKeys.at(key).second; ++v)
|
||||
sumFactorTable = (boost::format("%s %f") % sumFactorTable % sum).str();
|
||||
for (size_t v = 0; v < allDiscreteKeys.at(key).second; ++v) {
|
||||
sumFactorTable = sumFactorTable + " " + std::to_string(sum);
|
||||
}
|
||||
DecisionTreeFactor sumFactor(allDiscreteKeys.at(key), sumFactorTable);
|
||||
if (debug) sumFactor.print("denomFactor: ");
|
||||
beliefAtKey =
|
||||
|
|
|
@ -16,7 +16,6 @@
|
|||
*/
|
||||
|
||||
#include <gtsam_unstable/nonlinear/LinearizedFactor.h>
|
||||
#include <boost/format.hpp>
|
||||
#include <iostream>
|
||||
|
||||
namespace gtsam {
|
||||
|
@ -69,8 +68,9 @@ void LinearizedJacobianFactor::print(const std::string& s, const KeyFormatter& k
|
|||
std::cout << keyFormatter(key) << " ";
|
||||
std::cout << std::endl;
|
||||
|
||||
for(const_iterator key=begin(); key!=end(); ++key)
|
||||
std::cout << boost::format("A[%1%]=\n")%keyFormatter(*key) << A(*key) << std::endl;
|
||||
for(const_iterator key=begin(); key!=end(); ++key) {
|
||||
std::cout << "A[" << keyFormatter(*key) << "]=\n" << A(*key) << std::endl;
|
||||
}
|
||||
std::cout << "b=\n" << b() << std::endl;
|
||||
|
||||
lin_points_.print("Linearization Point: ");
|
||||
|
|
|
@ -21,8 +21,6 @@
|
|||
#include <gtsam_unstable/base/DSF.h>
|
||||
#include <gtsam/base/DSFMap.h>
|
||||
|
||||
#include <boost/format.hpp>
|
||||
|
||||
#include <fstream>
|
||||
#include <iostream>
|
||||
#include <random>
|
||||
|
@ -31,7 +29,6 @@
|
|||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
using boost::format;
|
||||
|
||||
int main(int argc, char* argv[]) {
|
||||
|
||||
|
@ -52,8 +49,7 @@ int main(int argc, char* argv[]) {
|
|||
volatile double fpm = 0.5; // fraction of points matched
|
||||
volatile size_t nm = fpm * n * np; // number of matches
|
||||
|
||||
cout << format("\nTesting with %1% images, %2% points, %3% matches\n")
|
||||
% (int)m % (int)N % (int)nm;
|
||||
cout << "\nTesting with " << (int)m << " images, " << (int)N << " points, " << (int)nm << " matches\n";
|
||||
cout << "Generating " << nm << " matches" << endl;
|
||||
std::mt19937 rng;
|
||||
std::uniform_int_distribution<> rn(0, N - 1);
|
||||
|
@ -64,7 +60,7 @@ int main(int argc, char* argv[]) {
|
|||
for (size_t k = 0; k < nm; k++)
|
||||
matches.push_back(Match(rn(rng), rn(rng)));
|
||||
|
||||
os << format("%1%,%2%,%3%,") % (int)m % (int)N % (int)nm;
|
||||
os << (int)m << "," << (int)N << "," << (int)nm << ",";
|
||||
|
||||
{
|
||||
// DSFBase version
|
||||
|
@ -77,7 +73,7 @@ int main(int argc, char* argv[]) {
|
|||
tictoc_getNode(dsftimeNode, dsftime);
|
||||
dsftime = dsftimeNode->secs();
|
||||
os << dsftime << ",";
|
||||
cout << format("DSFBase: %1% s") % dsftime << endl;
|
||||
cout << "DSFBase: " << dsftime << " s" << endl;
|
||||
tictoc_reset_();
|
||||
}
|
||||
|
||||
|
@ -92,7 +88,7 @@ int main(int argc, char* argv[]) {
|
|||
tictoc_getNode(dsftimeNode, dsftime);
|
||||
dsftime = dsftimeNode->secs();
|
||||
os << dsftime << endl;
|
||||
cout << format("DSFMap: %1% s") % dsftime << endl;
|
||||
cout << "DSFMap: " << dsftime << " s" << endl;
|
||||
tictoc_reset_();
|
||||
}
|
||||
|
||||
|
@ -109,7 +105,7 @@ int main(int argc, char* argv[]) {
|
|||
tictoc_getNode(dsftimeNode, dsftime);
|
||||
dsftime = dsftimeNode->secs();
|
||||
os << dsftime << endl;
|
||||
cout << format("DSF functional: %1% s") % dsftime << endl;
|
||||
cout << "DSF functional: " << dsftime << " s" << endl;
|
||||
tictoc_reset_();
|
||||
}
|
||||
|
||||
|
@ -126,7 +122,7 @@ int main(int argc, char* argv[]) {
|
|||
tictoc_getNode(dsftimeNode, dsftime);
|
||||
dsftime = dsftimeNode->secs();
|
||||
os << dsftime << ",";
|
||||
cout << format("DSF in-place: %1% s") % dsftime << endl;
|
||||
cout << "DSF in-place: " << dsftime << " s" << endl;
|
||||
tictoc_reset_();
|
||||
}
|
||||
|
||||
|
|
|
@ -16,9 +16,6 @@
|
|||
* @date Sep 18, 2010
|
||||
*/
|
||||
|
||||
#include <boost/format.hpp>
|
||||
#include <boost/lambda/lambda.hpp>
|
||||
|
||||
#include <gtsam/base/timing.h>
|
||||
#include <gtsam/base/Matrix.h>
|
||||
|
||||
|
@ -30,8 +27,6 @@
|
|||
using namespace std;
|
||||
//namespace ublas = boost::numeric::ublas;
|
||||
//using namespace Eigen;
|
||||
using boost::format;
|
||||
using namespace boost::lambda;
|
||||
|
||||
static std::mt19937 rng;
|
||||
static std::uniform_real_distribution<> uniform(-1.0, 0.0);
|
||||
|
@ -61,10 +56,10 @@ int main(int argc, char* argv[]) {
|
|||
gtsam::SubMatrix top = mat.block(0, 0, n, n);
|
||||
gtsam::SubMatrix block = mat.block(m/4, n/4, m-m/2, n-n/2);
|
||||
|
||||
cout << format(" Basic: %1%x%2%\n") % (int)m % (int)n;
|
||||
cout << format(" Full: mat(%1%:%2%, %3%:%4%)\n") % 0 % (int)m % 0 % (int)n;
|
||||
cout << format(" Top: mat(%1%:%2%, %3%:%4%)\n") % 0 % (int)n % 0 % (int)n;
|
||||
cout << format(" Block: mat(%1%:%2%, %3%:%4%)\n") % size_t(m/4) % size_t(m-m/4) % size_t(n/4) % size_t(n-n/4);
|
||||
cout << " Basic: " << (int)m << "x" << (int)n << endl;
|
||||
cout << " Full: mat(" << 0 << ":" << (int)m << ", " << 0 << ":" << (int)n << ")" << endl;
|
||||
cout << " Top: mat(" << 0 << ":" << (int)n << ", " << 0 << ":" << (int)n << ")" << endl;
|
||||
cout << " Block: mat(" << size_t(m/4) << ":" << size_t(m-m/4) << ", " << size_t(n/4) << ":" << size_t(n-n/4) << ")" << endl;
|
||||
cout << endl;
|
||||
|
||||
{
|
||||
|
@ -87,7 +82,7 @@ int main(int argc, char* argv[]) {
|
|||
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;
|
||||
cout << " Basic: " << double(1000000 * basicTime / double(mat.rows()*mat.cols()*nReps)) << " mus/element" << endl;
|
||||
|
||||
gttic_(fullTime);
|
||||
for(size_t rep=0; rep<nReps; ++rep)
|
||||
|
@ -98,7 +93,7 @@ int main(int argc, char* argv[]) {
|
|||
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;
|
||||
cout << " Full: " << double(1000000 * fullTime / double(full.rows()*full.cols()*nReps)) << " mus/element" << endl;
|
||||
|
||||
gttic_(topTime);
|
||||
for(size_t rep=0; rep<nReps; ++rep)
|
||||
|
@ -109,7 +104,7 @@ int main(int argc, char* argv[]) {
|
|||
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;
|
||||
cout << " Top: " << double(1000000 * topTime / double(top.rows()*top.cols()*nReps)) << " mus/element" << endl;
|
||||
|
||||
gttic_(blockTime);
|
||||
for(size_t rep=0; rep<nReps; ++rep)
|
||||
|
@ -120,7 +115,7 @@ int main(int argc, char* argv[]) {
|
|||
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 << " Block: " << double(1000000 * blockTime / double(block.rows()*block.cols()*nReps)) << " mus/element" << endl;
|
||||
|
||||
cout << endl;
|
||||
}
|
||||
|
@ -145,7 +140,7 @@ int main(int argc, char* argv[]) {
|
|||
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;
|
||||
cout << " Basic: " << double(1000000 * basicTime / double(mat.rows()*mat.cols()*nReps)) << " mus/element" << endl;
|
||||
|
||||
gttic_(fullTime);
|
||||
for(size_t rep=0; rep<nReps; ++rep)
|
||||
|
@ -156,7 +151,7 @@ int main(int argc, char* argv[]) {
|
|||
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;
|
||||
cout << " Full: " << double(1000000 * fullTime / double(full.rows()*full.cols()*nReps)) << " mus/element" << endl;
|
||||
|
||||
gttic_(topTime);
|
||||
for(size_t rep=0; rep<nReps; ++rep)
|
||||
|
@ -167,7 +162,7 @@ int main(int argc, char* argv[]) {
|
|||
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;
|
||||
cout << " Top: " << double(1000000 * topTime / double(top.rows()*top.cols()*nReps)) << " mus/element" << endl;
|
||||
|
||||
gttic_(blockTime);
|
||||
for(size_t rep=0; rep<nReps; ++rep)
|
||||
|
@ -178,7 +173,7 @@ int main(int argc, char* argv[]) {
|
|||
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 << " Block: " << double(1000000 * blockTime / double(block.rows()*block.cols()*nReps)) << " mus/element" << endl;
|
||||
|
||||
cout << endl;
|
||||
}
|
||||
|
@ -203,7 +198,7 @@ int main(int argc, char* argv[]) {
|
|||
tictoc_getNode(basicTimeNode, basicTime);
|
||||
basicTime = basicTimeNode->secs();
|
||||
gtsam::tictoc_reset_();
|
||||
cout << format(" Basic: %1% mus/element") % double(1000000 * basicTime / double(ijs.size()*nReps)) << endl;
|
||||
cout << " Basic: " << double(1000000 * basicTime / double(ijs.size()*nReps)) << " mus/element" << endl;
|
||||
|
||||
gttic_(fullTime);
|
||||
for_each(ijs.begin(), ijs.end(), _1 = make_pair(uniform_i(rng),uniform_j(rng)));
|
||||
|
@ -213,7 +208,7 @@ int main(int argc, char* argv[]) {
|
|||
tictoc_getNode(fullTimeNode, fullTime);
|
||||
fullTime = fullTimeNode->secs();
|
||||
gtsam::tictoc_reset_();
|
||||
cout << format(" Full: %1% mus/element") % double(1000000 * fullTime / double(ijs.size()*nReps)) << endl;
|
||||
cout << " Full: " << double(1000000 * fullTime / double(ijs.size()*nReps)) << " mus/element" << endl;
|
||||
|
||||
gttic_(topTime);
|
||||
for_each(ijs.begin(), ijs.end(), _1 = make_pair(uniform_i(rng)%top.rows(),uniform_j(rng)));
|
||||
|
@ -223,7 +218,7 @@ int main(int argc, char* argv[]) {
|
|||
tictoc_getNode(topTimeNode, topTime);
|
||||
topTime = topTimeNode->secs();
|
||||
gtsam::tictoc_reset_();
|
||||
cout << format(" Top: %1% mus/element") % double(1000000 * topTime / double(ijs.size()*nReps)) << endl;
|
||||
cout << " Top: " << double(1000000 * topTime / double(ijs.size()*nReps)) << " mus/element" << endl;
|
||||
|
||||
gttic_(blockTime);
|
||||
for_each(ijs.begin(), ijs.end(), _1 = make_pair(uniform_i(rng)%block.rows(),uniform_j(rng)%block.cols()));
|
||||
|
@ -233,7 +228,7 @@ int main(int argc, char* argv[]) {
|
|||
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 << " Block: " << double(1000000 * blockTime / double(ijs.size()*nReps)) << " mus/element" << endl;
|
||||
|
||||
cout << endl;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue