From 4a854f7e22dbcf9eacedf99a108c274d6283f1aa Mon Sep 17 00:00:00 2001 From: dellaert Date: Wed, 15 Oct 2014 11:01:27 +0200 Subject: [PATCH] No using namespace in headers --- .../timing/timeCameraExpression.cpp | 3 ++ gtsam_unstable/timing/timeLinearize.h | 30 +++++++++---------- .../timing/timeOneCameraExpression.cpp | 3 ++ 3 files changed, 20 insertions(+), 16 deletions(-) diff --git a/gtsam_unstable/timing/timeCameraExpression.cpp b/gtsam_unstable/timing/timeCameraExpression.cpp index 0e3a02c31..04908f129 100644 --- a/gtsam_unstable/timing/timeCameraExpression.cpp +++ b/gtsam_unstable/timing/timeCameraExpression.cpp @@ -24,6 +24,9 @@ #include #include "timeLinearize.h" +using namespace std; +using namespace gtsam; + #define time timeMultiThreaded boost::shared_ptr fixedK(new Cal3_S2()); diff --git a/gtsam_unstable/timing/timeLinearize.h b/gtsam_unstable/timing/timeLinearize.h index 62c6fc978..dfb63ffa3 100644 --- a/gtsam_unstable/timing/timeLinearize.h +++ b/gtsam_unstable/timing/timeLinearize.h @@ -23,36 +23,34 @@ #include #include -#include // std::setprecision -using namespace std; -using namespace gtsam; +#include static const int n = 1000000; -void timeSingleThreaded(const string& str, const NonlinearFactor::shared_ptr& f, - const Values& values) { +void timeSingleThreaded(const std::string& str, + const gtsam::NonlinearFactor::shared_ptr& f, const gtsam::Values& values) { long timeLog = clock(); - GaussianFactor::shared_ptr gf; + gtsam::GaussianFactor::shared_ptr gf; for (int i = 0; i < n; i++) gf = f->linearize(values); long timeLog2 = clock(); double seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC; - // cout << ((double) n / seconds) << " calls/second" << endl; - cout << setprecision(3); - cout << str << ((double) seconds * 1000000 / n) << " musecs/call" << endl; + std::cout << std::setprecision(3); + std::cout << str << ((double) seconds * 1000000 / n) << " musecs/call" + << std::endl; } -void timeMultiThreaded(const string& str, const NonlinearFactor::shared_ptr& f, - const Values& values) { - NonlinearFactorGraph graph; +void timeMultiThreaded(const std::string& str, + const gtsam::NonlinearFactor::shared_ptr& f, const gtsam::Values& values) { + gtsam::NonlinearFactorGraph graph; for (int i = 0; i < n; i++) graph.push_back(f); long timeLog = clock(); - GaussianFactorGraph::shared_ptr gfg = graph.linearize(values); + gtsam::GaussianFactorGraph::shared_ptr gfg = graph.linearize(values); long timeLog2 = clock(); double seconds = (double) (timeLog2 - timeLog) / CLOCKS_PER_SEC; - // cout << ((double) n / seconds) << " calls/second" << endl; - cout << setprecision(3); - cout << str << ((double) seconds * 1000000 / n) << " musecs/call" << endl; + std::cout << std::setprecision(3); + std::cout << str << ((double) seconds * 1000000 / n) << " musecs/call" + << std::endl; } diff --git a/gtsam_unstable/timing/timeOneCameraExpression.cpp b/gtsam_unstable/timing/timeOneCameraExpression.cpp index d85359ee5..67b83b78b 100644 --- a/gtsam_unstable/timing/timeOneCameraExpression.cpp +++ b/gtsam_unstable/timing/timeOneCameraExpression.cpp @@ -20,6 +20,9 @@ #include #include "timeLinearize.h" +using namespace std; +using namespace gtsam; + #define time timeMultiThreaded int main() {