No using namespace in headers
parent
898c06ccbb
commit
4a854f7e22
|
@ -24,6 +24,9 @@
|
||||||
#include <gtsam/geometry/Cal3_S2.h>
|
#include <gtsam/geometry/Cal3_S2.h>
|
||||||
#include "timeLinearize.h"
|
#include "timeLinearize.h"
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
using namespace gtsam;
|
||||||
|
|
||||||
#define time timeMultiThreaded
|
#define time timeMultiThreaded
|
||||||
|
|
||||||
boost::shared_ptr<Cal3_S2> fixedK(new Cal3_S2());
|
boost::shared_ptr<Cal3_S2> fixedK(new Cal3_S2());
|
||||||
|
|
|
@ -23,36 +23,34 @@
|
||||||
|
|
||||||
#include <time.h>
|
#include <time.h>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include <iomanip> // std::setprecision
|
#include <iomanip>
|
||||||
using namespace std;
|
|
||||||
using namespace gtsam;
|
|
||||||
|
|
||||||
static const int n = 1000000;
|
static const int n = 1000000;
|
||||||
|
|
||||||
void timeSingleThreaded(const string& str, const NonlinearFactor::shared_ptr& f,
|
void timeSingleThreaded(const std::string& str,
|
||||||
const Values& values) {
|
const gtsam::NonlinearFactor::shared_ptr& f, const gtsam::Values& values) {
|
||||||
long timeLog = clock();
|
long timeLog = clock();
|
||||||
GaussianFactor::shared_ptr gf;
|
gtsam::GaussianFactor::shared_ptr gf;
|
||||||
for (int i = 0; i < n; i++)
|
for (int i = 0; i < n; i++)
|
||||||
gf = f->linearize(values);
|
gf = f->linearize(values);
|
||||||
long timeLog2 = clock();
|
long timeLog2 = clock();
|
||||||
double seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC;
|
double seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC;
|
||||||
// cout << ((double) n / seconds) << " calls/second" << endl;
|
std::cout << std::setprecision(3);
|
||||||
cout << setprecision(3);
|
std::cout << str << ((double) seconds * 1000000 / n) << " musecs/call"
|
||||||
cout << str << ((double) seconds * 1000000 / n) << " musecs/call" << endl;
|
<< std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
void timeMultiThreaded(const string& str, const NonlinearFactor::shared_ptr& f,
|
void timeMultiThreaded(const std::string& str,
|
||||||
const Values& values) {
|
const gtsam::NonlinearFactor::shared_ptr& f, const gtsam::Values& values) {
|
||||||
NonlinearFactorGraph graph;
|
gtsam::NonlinearFactorGraph graph;
|
||||||
for (int i = 0; i < n; i++)
|
for (int i = 0; i < n; i++)
|
||||||
graph.push_back(f);
|
graph.push_back(f);
|
||||||
long timeLog = clock();
|
long timeLog = clock();
|
||||||
GaussianFactorGraph::shared_ptr gfg = graph.linearize(values);
|
gtsam::GaussianFactorGraph::shared_ptr gfg = graph.linearize(values);
|
||||||
long timeLog2 = clock();
|
long timeLog2 = clock();
|
||||||
double seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC;
|
double seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC;
|
||||||
// cout << ((double) n / seconds) << " calls/second" << endl;
|
std::cout << std::setprecision(3);
|
||||||
cout << setprecision(3);
|
std::cout << str << ((double) seconds * 1000000 / n) << " musecs/call"
|
||||||
cout << str << ((double) seconds * 1000000 / n) << " musecs/call" << endl;
|
<< std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -20,6 +20,9 @@
|
||||||
#include <gtsam_unstable/nonlinear/ExpressionFactor.h>
|
#include <gtsam_unstable/nonlinear/ExpressionFactor.h>
|
||||||
#include "timeLinearize.h"
|
#include "timeLinearize.h"
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
using namespace gtsam;
|
||||||
|
|
||||||
#define time timeMultiThreaded
|
#define time timeMultiThreaded
|
||||||
|
|
||||||
int main() {
|
int main() {
|
||||||
|
|
Loading…
Reference in New Issue