timer
							parent
							
								
									27acf2231b
								
							
						
					
					
						commit
						b02c5ceefa
					
				|  | @ -30,6 +30,9 @@ | |||
| 
 | ||||
| namespace gtsam { | ||||
| namespace internal { | ||||
|    | ||||
| // a static shared_ptr to TimingOutline with nullptr as the pointer
 | ||||
| const static std::shared_ptr<TimingOutline> nullTimingOutline; | ||||
| 
 | ||||
| GTSAM_EXPORT std::shared_ptr<TimingOutline> gTimingRoot( | ||||
|     new TimingOutline("Total", getTicTocID("Total"))); | ||||
|  | @ -53,13 +56,16 @@ void TimingOutline::add(size_t usecs, size_t usecsWall) { | |||
| TimingOutline::TimingOutline(const std::string& label, size_t id) : | ||||
|     id_(id), t_(0), tWall_(0), t2_(0.0), tIt_(0), tMax_(0), tMin_(0), n_(0), myOrder_( | ||||
|         0), lastChildOrder_(0), label_(label) { | ||||
| #ifdef GTSAM_USE_BOOST | ||||
| #ifdef GTSAM_USING_NEW_BOOST_TIMERS | ||||
|   timer_.stop(); | ||||
| #endif | ||||
| #endif | ||||
| } | ||||
| 
 | ||||
| /* ************************************************************************* */ | ||||
| size_t TimingOutline::time() const { | ||||
| #ifdef GTSAM_USE_BOOST | ||||
|   size_t time = 0; | ||||
|   bool hasChildren = false; | ||||
|   for(const ChildMap::value_type& child: children_) { | ||||
|  | @ -70,10 +76,14 @@ size_t TimingOutline::time() const { | |||
|     return time; | ||||
|   else | ||||
|     return t_; | ||||
| #else | ||||
|   return 0; | ||||
| #endif | ||||
| } | ||||
| 
 | ||||
| /* ************************************************************************* */ | ||||
| void TimingOutline::print(const std::string& outline) const { | ||||
| #ifdef GTSAM_USE_BOOST | ||||
|   std::string formattedLabel = label_; | ||||
|   std::replace(formattedLabel.begin(), formattedLabel.end(), '_', ' '); | ||||
|   std::cout << outline << "-" << formattedLabel << ": " << self() << " CPU (" | ||||
|  | @ -92,11 +102,12 @@ void TimingOutline::print(const std::string& outline) const { | |||
|     order_child.second->print(childOutline); | ||||
|   } | ||||
|   std::cout.flush(); | ||||
| #endif | ||||
| } | ||||
| 
 | ||||
| void TimingOutline::print2(const std::string& outline, | ||||
|     const double parentTotal) const { | ||||
| 
 | ||||
| #ifdef GTSAM_USE_BOOST | ||||
|   const int w1 = 24, w2 = 2, w3 = 6, w4 = 8, precision = 2; | ||||
|   const double selfTotal = self(), selfMean = selfTotal / double(n_); | ||||
|   const double childTotal = secs(); | ||||
|  | @ -135,11 +146,13 @@ void TimingOutline::print2(const std::string& outline, | |||
|       child.second->print2(childOutline, selfTotal); | ||||
|     } | ||||
|   } | ||||
| #endif | ||||
| } | ||||
| 
 | ||||
| /* ************************************************************************* */ | ||||
| const std::shared_ptr<TimingOutline>& TimingOutline::child(size_t child, | ||||
|     const std::string& label, const std::weak_ptr<TimingOutline>& thisPtr) { | ||||
| #ifdef GTSAM_USE_BOOST | ||||
|   assert(thisPtr.lock().get() == this); | ||||
|   std::shared_ptr<TimingOutline>& result = children_[child]; | ||||
|   if (!result) { | ||||
|  | @ -150,10 +163,15 @@ const std::shared_ptr<TimingOutline>& TimingOutline::child(size_t child, | |||
|     result->parent_ = thisPtr; | ||||
|   } | ||||
|   return result; | ||||
| #else | ||||
|   return nullTimingOutline; | ||||
| #endif | ||||
| } | ||||
| 
 | ||||
| /* ************************************************************************* */ | ||||
| void TimingOutline::tic() { | ||||
| // Disable this entire function if we are not using boost
 | ||||
| #ifdef GTSAM_USE_BOOST | ||||
| #ifdef GTSAM_USING_NEW_BOOST_TIMERS | ||||
|   assert(timer_.is_stopped()); | ||||
|   timer_.start(); | ||||
|  | @ -166,10 +184,14 @@ void TimingOutline::tic() { | |||
| #ifdef GTSAM_USE_TBB | ||||
|   tbbTimer_ = tbb::tick_count::now(); | ||||
| #endif | ||||
| #endif | ||||
| } | ||||
| 
 | ||||
| /* ************************************************************************* */ | ||||
| void TimingOutline::toc() { | ||||
| // Disable this entire function if we are not using boost
 | ||||
| #ifdef GTSAM_USE_BOOST | ||||
| 
 | ||||
| #ifdef GTSAM_USING_NEW_BOOST_TIMERS | ||||
| 
 | ||||
|   assert(!timer_.is_stopped()); | ||||
|  | @ -197,10 +219,12 @@ void TimingOutline::toc() { | |||
| #endif | ||||
| 
 | ||||
|   add(cpuTime, wallTime); | ||||
| #endif | ||||
| } | ||||
| 
 | ||||
| /* ************************************************************************* */ | ||||
| void TimingOutline::finishedIteration() { | ||||
| #ifdef GTSAM_USE_BOOST | ||||
|   if (tIt_ > tMax_) | ||||
|     tMax_ = tIt_; | ||||
|   if (tMin_ == 0 || tIt_ < tMin_) | ||||
|  | @ -209,10 +233,13 @@ void TimingOutline::finishedIteration() { | |||
|   for(ChildMap::value_type& child: children_) { | ||||
|     child.second->finishedIteration(); | ||||
|   } | ||||
| #endif | ||||
| } | ||||
| 
 | ||||
| /* ************************************************************************* */ | ||||
| size_t getTicTocID(const char *descriptionC) { | ||||
| // disable anything which refers to TimingOutline as well, for good measure
 | ||||
| #ifdef GTSAM_USE_BOOST | ||||
|   const std::string description(descriptionC); | ||||
|   // Global (static) map from strings to ID numbers and current next ID number
 | ||||
|   static size_t nextId = 0; | ||||
|  | @ -227,19 +254,27 @@ size_t getTicTocID(const char *descriptionC) { | |||
| 
 | ||||
|   // Return ID
 | ||||
|   return it->second; | ||||
| #else | ||||
|   return 0; | ||||
| #endif | ||||
| } | ||||
| 
 | ||||
| /* ************************************************************************* */ | ||||
| void tic(size_t id, const char *labelC) { | ||||
| // disable anything which refers to TimingOutline as well, for good measure
 | ||||
| #ifdef GTSAM_USE_BOOST | ||||
|   const std::string label(labelC); | ||||
|   std::shared_ptr<TimingOutline> node = //
 | ||||
|       gCurrentTimer.lock()->child(id, label, gCurrentTimer); | ||||
|   gCurrentTimer = node; | ||||
|   node->tic(); | ||||
| #endif | ||||
| } | ||||
| 
 | ||||
| /* ************************************************************************* */ | ||||
| void toc(size_t id, const char *label) { | ||||
| // disable anything which refers to TimingOutline as well, for good measure
 | ||||
| #ifdef GTSAM_USE_BOOST | ||||
|   std::shared_ptr<TimingOutline> current(gCurrentTimer.lock()); | ||||
|   if (id != current->id_) { | ||||
|     gTimingRoot->print(); | ||||
|  | @ -255,6 +290,7 @@ void toc(size_t id, const char *label) { | |||
|   } | ||||
|   current->toc(); | ||||
|   gCurrentTimer = current->parent_; | ||||
| #endif | ||||
| } | ||||
| 
 | ||||
| } // namespace internal
 | ||||
|  |  | |||
|  | @ -21,7 +21,9 @@ | |||
| #include <gtsam/dllexport.h> | ||||
| #include <gtsam/config.h> // for GTSAM_USE_TBB | ||||
| 
 | ||||
| #ifdef GTSAM_USE_BOOST | ||||
| #include <boost/version.hpp> | ||||
| #endif | ||||
| 
 | ||||
| #include <memory> | ||||
| #include <cstddef> | ||||
|  | @ -105,6 +107,7 @@ | |||
| //   have matching gttic/gttoc statments.  You may want to consider reorganizing your timing
 | ||||
| //   outline to match the scope of your code.
 | ||||
| 
 | ||||
| #ifdef GTSAM_USE_BOOST | ||||
| // Automatically use the new Boost timers if version is recent enough.
 | ||||
| #if BOOST_VERSION >= 104800 | ||||
| #  ifndef GTSAM_DISABLE_NEW_TIMERS | ||||
|  | @ -118,6 +121,7 @@ | |||
| #  include <boost/timer.hpp> | ||||
| #  include <gtsam/base/types.h> | ||||
| #endif | ||||
| #endif | ||||
| 
 | ||||
| #ifdef GTSAM_USE_TBB | ||||
| #  include <tbb/tick_count.h> | ||||
|  | @ -160,6 +164,8 @@ namespace gtsam { | |||
|       typedef FastMap<size_t, std::shared_ptr<TimingOutline> > ChildMap; | ||||
|       ChildMap children_; ///< subtrees
 | ||||
| 
 | ||||
| // disable all timers if not using boost
 | ||||
| #ifdef GTSAM_USE_BOOST | ||||
| #ifdef GTSAM_USING_NEW_BOOST_TIMERS | ||||
|       boost::timer::cpu_timer timer_; | ||||
| #else | ||||
|  | @ -168,6 +174,7 @@ namespace gtsam { | |||
| #endif | ||||
| #ifdef GTSAM_USE_TBB | ||||
|       tbb::tick_count tbbTimer_; | ||||
| #endif | ||||
| #endif | ||||
|       void add(size_t usecs, size_t usecsWall); | ||||
| 
 | ||||
|  | @ -176,11 +183,20 @@ namespace gtsam { | |||
|       GTSAM_EXPORT TimingOutline(const std::string& label, size_t myId); | ||||
|       GTSAM_EXPORT size_t time() const; ///< time taken, including children
 | ||||
|       double secs() const { return double(time()) / 1000000.0;} ///< time taken, in seconds, including children
 | ||||
| #ifdef GTSAM_USE_BOOST | ||||
|       double self() const { return double(t_)     / 1000000.0;} ///< self time only, in seconds
 | ||||
|       double wall() const { return double(tWall_) / 1000000.0;} ///< wall time, in seconds
 | ||||
|       double min()  const { return double(tMin_)  / 1000000.0;} ///< min time, in seconds
 | ||||
|       double max()  const { return double(tMax_)  / 1000000.0;} ///< max time, in seconds
 | ||||
|       double mean() const { return self() / double(n_); } ///< mean self time, in seconds
 | ||||
| #else | ||||
|       // make them no-ops if not using boost
 | ||||
|       double self() const { return -1.; } ///< self time only, in seconds
 | ||||
|       double wall() const { return -1.; } ///< wall time, in seconds
 | ||||
|       double min()  const { return -1.; } ///< min time, in seconds
 | ||||
|       double max()  const { return -1.; } ///< max time, in seconds
 | ||||
|       double mean() const { return -1.; } ///< mean self time, in seconds
 | ||||
| #endif | ||||
|       GTSAM_EXPORT void print(const std::string& outline = "") const; | ||||
|       GTSAM_EXPORT void print2(const std::string& outline = "", const double parentTotal = -1.0) const; | ||||
|       GTSAM_EXPORT const std::shared_ptr<TimingOutline>& | ||||
|  |  | |||
|  | @ -26,7 +26,9 @@ | |||
| #include <gtsam/linear/linearExceptions.h> | ||||
| #include <gtsam/inference/Ordering.h> | ||||
| #include <gtsam/base/Vector.h> | ||||
| #ifdef GTSAM_USE_BOOST | ||||
| #include <gtsam/base/timing.h> | ||||
| #endif | ||||
| 
 | ||||
| #include <cmath> | ||||
| #include <fstream> | ||||
|  | @ -121,6 +123,7 @@ bool LevenbergMarquardtOptimizer::tryLambda(const GaussianFactorGraph& linear, | |||
|   auto currentState = static_cast<const State*>(state_.get()); | ||||
|   bool verbose = (params_.verbosityLM >= LevenbergMarquardtParams::TRYLAMBDA); | ||||
| 
 | ||||
| #ifdef GTSAM_USE_BOOST | ||||
| #ifdef GTSAM_USING_NEW_BOOST_TIMERS | ||||
|   boost::timer::cpu_timer lamda_iteration_timer; | ||||
|   lamda_iteration_timer.start(); | ||||
|  | @ -128,6 +131,9 @@ bool LevenbergMarquardtOptimizer::tryLambda(const GaussianFactorGraph& linear, | |||
|   boost::timer lamda_iteration_timer; | ||||
|   lamda_iteration_timer.restart(); | ||||
| #endif | ||||
| #else | ||||
|   auto start = std::chrono::high_resolution_clock::now(); | ||||
| #endif | ||||
| 
 | ||||
|   if (verbose) | ||||
|     cout << "trying lambda = " << currentState->lambda << endl; | ||||
|  | @ -215,11 +221,16 @@ bool LevenbergMarquardtOptimizer::tryLambda(const GaussianFactorGraph& linear, | |||
|   } // if (systemSolvedSuccessfully)
 | ||||
| 
 | ||||
|   if (params_.verbosityLM == LevenbergMarquardtParams::SUMMARY) { | ||||
| #ifdef GTSAM_USE_BOOST | ||||
| // do timing
 | ||||
| #ifdef GTSAM_USING_NEW_BOOST_TIMERS | ||||
|     double iterationTime = 1e-9 * lamda_iteration_timer.elapsed().wall; | ||||
| #else | ||||
|     double iterationTime = lamda_iteration_timer.elapsed(); | ||||
| #endif | ||||
| #else | ||||
|     auto end = std::chrono::high_resolution_clock::now(); | ||||
|     double iterationTime = std::chrono::duration_cast<std::chrono::microseconds>(end - start).count() / 1e6; | ||||
| #endif | ||||
|     if (currentState->iterations == 0) { | ||||
|       cout << "iter      cost      cost_change    lambda  success iter_time" << endl; | ||||
|  | @ -228,7 +239,6 @@ bool LevenbergMarquardtOptimizer::tryLambda(const GaussianFactorGraph& linear, | |||
|          << costChange << " " << setw(3) << setprecision(2) << currentState->lambda << " " << setw(4) | ||||
|          << systemSolvedSuccessfully << " " << setw(3) << setprecision(2) << iterationTime << endl; | ||||
|   } | ||||
| 
 | ||||
|   if (step_is_successful) { | ||||
|     // we have successfully decreased the cost and we have good modelFidelity
 | ||||
|     // NOTE(frank): As we return immediately after this, we move the newValues
 | ||||
|  |  | |||
		Loading…
	
		Reference in New Issue