Added some handy methods, and formatted cpp file using BORG style
parent
8740e9d8fd
commit
194cae51ef
|
@ -29,11 +29,10 @@
|
|||
#include <gtsam/base/timing.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
/* ************************************************************************* */
|
||||
namespace internal {
|
||||
|
||||
GTSAM_EXPORT boost::shared_ptr<TimingOutline> timingRoot(new TimingOutline("Total", getTicTocID("Total")));
|
||||
GTSAM_EXPORT boost::shared_ptr<TimingOutline> timingRoot(
|
||||
new TimingOutline("Total", getTicTocID("Total")));
|
||||
GTSAM_EXPORT boost::weak_ptr<TimingOutline> timingCurrent(timingRoot);
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
@ -45,15 +44,15 @@ void TimingOutline::add(size_t usecs, size_t usecsWall) {
|
|||
t_ += usecs;
|
||||
tWall_ += usecsWall;
|
||||
tIt_ += usecs;
|
||||
t2_ += (double(usecs)/1000000.0)*(double(usecs)/1000000.0);
|
||||
++ n_;
|
||||
double secs = (double(usecs) / 1000000.0);
|
||||
t2_ += secs * secs;
|
||||
++n_;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
TimingOutline::TimingOutline(const std::string& label, size_t myId) :
|
||||
myId_(myId), t_(0), tWall_(0), t2_(0.0), tIt_(0), tMax_(0), tMin_(0), n_(0),
|
||||
myOrder_(0), lastChildOrder_(0), label_(label)
|
||||
{
|
||||
myId_(myId), t_(0), tWall_(0), t2_(0.0), tIt_(0), tMax_(0), tMin_(0), n_(0), myOrder_(
|
||||
0), lastChildOrder_(0), label_(label) {
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
timer_.stop();
|
||||
#endif
|
||||
|
@ -67,7 +66,7 @@ size_t TimingOutline::time() const {
|
|||
time += child.second->time();
|
||||
hasChildren = true;
|
||||
}
|
||||
if(hasChildren)
|
||||
if (hasChildren)
|
||||
return time;
|
||||
else
|
||||
return t_;
|
||||
|
@ -77,9 +76,9 @@ size_t TimingOutline::time() const {
|
|||
void TimingOutline::print(const std::string& outline) const {
|
||||
std::string formattedLabel = label_;
|
||||
boost::replace_all(formattedLabel, "_", " ");
|
||||
std::cout << outline << "-" << formattedLabel << ": " << double(t_)/1000000.0 << " CPU (" <<
|
||||
n_ << " times, " << double(tWall_)/1000000.0 << " wall, " << double(time())/1000000.0 << " children, min: "
|
||||
<< double(tMin_)/1000000.0 << " max: " << double(tMax_)/1000000.0 << ")\n";
|
||||
std::cout << outline << "-" << formattedLabel << ": " << self() << " CPU ("
|
||||
<< n_ << " times, " << wall() << " wall, " << secs() << " children, min: "
|
||||
<< min() << " max: " << max() << ")\n";
|
||||
// Order children
|
||||
typedef FastMap<size_t, boost::shared_ptr<TimingOutline> > ChildOrder;
|
||||
ChildOrder childOrder;
|
||||
|
@ -95,39 +94,43 @@ void TimingOutline::print(const std::string& outline) const {
|
|||
std::cout.flush();
|
||||
}
|
||||
|
||||
void TimingOutline::print2(const std::string& outline, const double parentTotal) const {
|
||||
void TimingOutline::print2(const std::string& outline,
|
||||
const double parentTotal) const {
|
||||
|
||||
const int w1 = 24, w2 = 2, w3 = 6, w4 = 8, precision = 2;
|
||||
const double selfTotal = double(t_)/(1000000.0),
|
||||
selfMean = selfTotal/double(n_);
|
||||
const double childTotal = double(time())/(1000000.0);
|
||||
const double selfTotal = self(), selfMean = selfTotal / double(n_);
|
||||
const double childTotal = secs();
|
||||
|
||||
// compute standard deviation
|
||||
const double selfStd = sqrt(t2_/double(n_) - selfMean*selfMean);
|
||||
const std::string label = outline + label_ + ": " ;
|
||||
const double selfStd = sqrt(t2_ / double(n_) - selfMean * selfMean);
|
||||
const std::string label = outline + label_ + ": ";
|
||||
|
||||
if ( n_ == 0 ) {
|
||||
std::cout << label << std::fixed << std::setprecision(precision) << childTotal << " seconds" << std::endl;
|
||||
}
|
||||
else {
|
||||
std::cout << std::setw(w1+outline.length()) << label ;
|
||||
std::cout << std::setiosflags(std::ios::right) << std::setw(w2) << n_ << " (times), "
|
||||
<< std::setiosflags(std::ios::right) << std::fixed << std::setw(w3) << std::setprecision(precision) << selfMean << " (mean), "
|
||||
<< std::setiosflags(std::ios::right) << std::fixed << std::setw(w3) << std::setprecision(precision) << selfStd << " (std),"
|
||||
<< std::setiosflags(std::ios::right) << std::fixed << std::setw(w4) << std::setprecision(precision) << selfTotal << " (total),";
|
||||
if (n_ == 0) {
|
||||
std::cout << label << std::fixed << std::setprecision(precision)
|
||||
<< childTotal << " seconds" << std::endl;
|
||||
} else {
|
||||
std::cout << std::setw(w1 + outline.length()) << label;
|
||||
std::cout << std::setiosflags(std::ios::right) << std::setw(w2) << n_
|
||||
<< " (times), " << std::setiosflags(std::ios::right) << std::fixed
|
||||
<< std::setw(w3) << std::setprecision(precision) << selfMean
|
||||
<< " (mean), " << std::setiosflags(std::ios::right) << std::fixed
|
||||
<< std::setw(w3) << std::setprecision(precision) << selfStd << " (std),"
|
||||
<< std::setiosflags(std::ios::right) << std::fixed << std::setw(w4)
|
||||
<< std::setprecision(precision) << selfTotal << " (total),";
|
||||
|
||||
if ( parentTotal > 0.0 )
|
||||
std::cout << std::setiosflags(std::ios::right) << std::fixed << std::setw(w3) << std::setprecision(precision) << 100.0*selfTotal/parentTotal << " (%)";
|
||||
if (parentTotal > 0.0)
|
||||
std::cout << std::setiosflags(std::ios::right) << std::fixed
|
||||
<< std::setw(w3) << std::setprecision(precision)
|
||||
<< 100.0 * selfTotal / parentTotal << " (%)";
|
||||
|
||||
std::cout << std::endl;
|
||||
}
|
||||
|
||||
BOOST_FOREACH(const ChildMap::value_type& child, children_) {
|
||||
std::string childOutline(outline);
|
||||
if ( n_ == 0 ) {
|
||||
if (n_ == 0) {
|
||||
child.second->print2(childOutline, childTotal);
|
||||
}
|
||||
else {
|
||||
} else {
|
||||
childOutline += " ";
|
||||
child.second->print2(childOutline, selfTotal);
|
||||
}
|
||||
|
@ -135,13 +138,14 @@ void TimingOutline::print2(const std::string& outline, const double parentTotal)
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
const boost::shared_ptr<TimingOutline>& TimingOutline::child(size_t child, const std::string& label, const boost::weak_ptr<TimingOutline>& thisPtr) {
|
||||
const boost::shared_ptr<TimingOutline>& TimingOutline::child(size_t child,
|
||||
const std::string& label, const boost::weak_ptr<TimingOutline>& thisPtr) {
|
||||
assert(thisPtr.lock().get() == this);
|
||||
boost::shared_ptr<TimingOutline>& result = children_[child];
|
||||
if(!result) {
|
||||
if (!result) {
|
||||
// Create child if necessary
|
||||
result.reset(new TimingOutline(label, child));
|
||||
++ this->lastChildOrder_;
|
||||
++this->lastChildOrder_;
|
||||
result->myOrder_ = this->lastChildOrder_;
|
||||
result->parent_ = thisPtr;
|
||||
}
|
||||
|
@ -149,8 +153,7 @@ const boost::shared_ptr<TimingOutline>& TimingOutline::child(size_t child, const
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void TimingOutline::ticInternal()
|
||||
{
|
||||
void TimingOutline::ticInternal() {
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
assert(timer_.is_stopped());
|
||||
timer_.start();
|
||||
|
@ -166,8 +169,7 @@ void TimingOutline::ticInternal()
|
|||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void TimingOutline::tocInternal()
|
||||
{
|
||||
void TimingOutline::tocInternal() {
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
|
||||
assert(!timer_.is_stopped());
|
||||
|
@ -190,7 +192,8 @@ void TimingOutline::tocInternal()
|
|||
#endif
|
||||
|
||||
#ifdef GTSAM_USE_TBB
|
||||
size_t wallTime = size_t((tbb::tick_count::now() - tbbTimer_).seconds() * 1e6);
|
||||
size_t wallTime = size_t(
|
||||
(tbb::tick_count::now() - tbbTimer_).seconds() * 1e6);
|
||||
#endif
|
||||
|
||||
add(cpuTime, wallTime);
|
||||
|
@ -198,9 +201,9 @@ void TimingOutline::tocInternal()
|
|||
|
||||
/* ************************************************************************* */
|
||||
void TimingOutline::finishedIteration() {
|
||||
if(tIt_ > tMax_)
|
||||
if (tIt_ > tMax_)
|
||||
tMax_ = tIt_;
|
||||
if(tMin_ == 0 || tIt_ < tMin_)
|
||||
if (tMin_ == 0 || tIt_ < tMin_)
|
||||
tMin_ = tIt_;
|
||||
tIt_ = 0;
|
||||
BOOST_FOREACH(ChildMap::value_type& child, children_) {
|
||||
|
@ -208,56 +211,59 @@ void TimingOutline::finishedIteration() {
|
|||
}
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
// Generate or retrieve a unique global ID number that will be used to look up tic_/toc statements
|
||||
size_t getTicTocID(const char *descriptionC) {
|
||||
const std::string description(descriptionC);
|
||||
// Global (static) map from strings to ID numbers and current next ID number
|
||||
static size_t nextId = 0;
|
||||
static gtsam::FastMap<std::string, size_t> idMap;
|
||||
/* ************************************************************************* */
|
||||
// Generate or retrieve a unique global ID number that will be used to look up tic_/toc statements
|
||||
size_t getTicTocID(const char *descriptionC) {
|
||||
const std::string description(descriptionC);
|
||||
// Global (static) map from strings to ID numbers and current next ID number
|
||||
static size_t nextId = 0;
|
||||
static gtsam::FastMap<std::string, size_t> idMap;
|
||||
|
||||
// Retrieve or add this string
|
||||
gtsam::FastMap<std::string, size_t>::const_iterator it = idMap.find(description);
|
||||
if(it == idMap.end()) {
|
||||
it = idMap.insert(std::make_pair(description, nextId)).first;
|
||||
++ nextId;
|
||||
}
|
||||
|
||||
// Return ID
|
||||
return it->second;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void ticInternal(size_t id, const char *labelC) {
|
||||
const std::string label(labelC);
|
||||
if(ISDEBUG("timing-verbose"))
|
||||
std::cout << "gttic_(" << id << ", " << label << ")" << std::endl;
|
||||
boost::shared_ptr<TimingOutline> node = timingCurrent.lock()->child(id, label, timingCurrent);
|
||||
timingCurrent = node;
|
||||
node->ticInternal();
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void tocInternal(size_t id, const char *label) {
|
||||
if(ISDEBUG("timing-verbose"))
|
||||
std::cout << "gttoc(" << id << ", " << label << ")" << std::endl;
|
||||
boost::shared_ptr<TimingOutline> current(timingCurrent.lock());
|
||||
if(id != current->myId_) {
|
||||
timingRoot->print();
|
||||
throw std::invalid_argument(
|
||||
(boost::format("gtsam timing: Mismatched tic/toc: gttoc(\"%s\") called when last tic was \"%s\".") %
|
||||
label % current->label_).str());
|
||||
}
|
||||
if(!current->parent_.lock()) {
|
||||
timingRoot->print();
|
||||
throw std::invalid_argument(
|
||||
(boost::format("gtsam timing: Mismatched tic/toc: extra gttoc(\"%s\"), already at the root") %
|
||||
label).str());
|
||||
}
|
||||
current->tocInternal();
|
||||
timingCurrent = current->parent_;
|
||||
// Retrieve or add this string
|
||||
gtsam::FastMap<std::string, size_t>::const_iterator it = idMap.find(
|
||||
description);
|
||||
if (it == idMap.end()) {
|
||||
it = idMap.insert(std::make_pair(description, nextId)).first;
|
||||
++nextId;
|
||||
}
|
||||
|
||||
// Return ID
|
||||
return it->second;
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void ticInternal(size_t id, const char *labelC) {
|
||||
const std::string label(labelC);
|
||||
if (ISDEBUG("timing-verbose"))
|
||||
std::cout << "gttic_(" << id << ", " << label << ")" << std::endl;
|
||||
boost::shared_ptr<TimingOutline> node = //
|
||||
timingCurrent.lock()->child(id, label, timingCurrent);
|
||||
timingCurrent = node;
|
||||
node->ticInternal();
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
void tocInternal(size_t id, const char *label) {
|
||||
if (ISDEBUG("timing-verbose"))
|
||||
std::cout << "gttoc(" << id << ", " << label << ")" << std::endl;
|
||||
boost::shared_ptr<TimingOutline> current(timingCurrent.lock());
|
||||
if (id != current->myId_) {
|
||||
timingRoot->print();
|
||||
throw std::invalid_argument(
|
||||
(boost::format(
|
||||
"gtsam timing: Mismatched tic/toc: gttoc(\"%s\") called when last tic was \"%s\".")
|
||||
% label % current->label_).str());
|
||||
}
|
||||
if (!current->parent_.lock()) {
|
||||
timingRoot->print();
|
||||
throw std::invalid_argument(
|
||||
(boost::format(
|
||||
"gtsam timing: Mismatched tic/toc: extra gttoc(\"%s\"), already at the root")
|
||||
% label).str());
|
||||
}
|
||||
current->tocInternal();
|
||||
timingCurrent = current->parent_;
|
||||
}
|
||||
|
||||
} // namespace internal
|
||||
} // namespace gtsam
|
||||
|
|
|
@ -129,12 +129,15 @@ namespace gtsam {
|
|||
GTSAM_EXPORT void ticInternal(size_t id, const char *label);
|
||||
GTSAM_EXPORT void tocInternal(size_t id, const char *label);
|
||||
|
||||
/**
|
||||
* Timing Entry, arranged in a tree
|
||||
*/
|
||||
class GTSAM_EXPORT TimingOutline {
|
||||
protected:
|
||||
size_t myId_;
|
||||
size_t t_;
|
||||
size_t tWall_;
|
||||
double t2_ ; /* cache the \sum t_i^2 */
|
||||
double t2_ ; ///< cache the \sum t_i^2
|
||||
size_t tIt_;
|
||||
size_t tMax_;
|
||||
size_t tMin_;
|
||||
|
@ -142,9 +145,12 @@ namespace gtsam {
|
|||
size_t myOrder_;
|
||||
size_t lastChildOrder_;
|
||||
std::string label_;
|
||||
boost::weak_ptr<TimingOutline> parent_;
|
||||
|
||||
// Tree structure
|
||||
boost::weak_ptr<TimingOutline> parent_; ///< parent pointer
|
||||
typedef FastMap<size_t, boost::shared_ptr<TimingOutline> > ChildMap;
|
||||
ChildMap children_;
|
||||
ChildMap children_; ///< subtrees
|
||||
|
||||
#ifdef GTSAM_USING_NEW_BOOST_TIMERS
|
||||
boost::timer::cpu_timer timer_;
|
||||
#else
|
||||
|
@ -155,12 +161,21 @@ namespace gtsam {
|
|||
tbb::tick_count tbbTimer_;
|
||||
#endif
|
||||
void add(size_t usecs, size_t usecsWall);
|
||||
|
||||
public:
|
||||
/// Constructor
|
||||
TimingOutline(const std::string& label, size_t myId);
|
||||
size_t time() const;
|
||||
size_t time() const; ///< time taken, including children
|
||||
double secs() const { return double(time()) / 1000000.0;} ///< time taken, in seconds, including children
|
||||
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
|
||||
void print(const std::string& outline = "") const;
|
||||
void print2(const std::string& outline = "", const double parentTotal = -1.0) const;
|
||||
const boost::shared_ptr<TimingOutline>& child(size_t child, const std::string& label, const boost::weak_ptr<TimingOutline>& thisPtr);
|
||||
const boost::shared_ptr<TimingOutline>&
|
||||
child(size_t child, const std::string& label, const boost::weak_ptr<TimingOutline>& thisPtr);
|
||||
void ticInternal();
|
||||
void tocInternal();
|
||||
void finishedIteration();
|
||||
|
@ -168,6 +183,9 @@ namespace gtsam {
|
|||
GTSAM_EXPORT friend void tocInternal(size_t id, const char *label);
|
||||
}; // \TimingOutline
|
||||
|
||||
/**
|
||||
* No documentation
|
||||
*/
|
||||
class AutoTicToc {
|
||||
private:
|
||||
size_t id_;
|
||||
|
@ -188,28 +206,45 @@ namespace gtsam {
|
|||
// static variable is created for each tic/toc statement storing an integer ID, but the
|
||||
// integer ID is only looked up by string once when the static variable is initialized
|
||||
// as the program starts.
|
||||
|
||||
// tic
|
||||
#define gttic_(label) \
|
||||
static const size_t label##_id_tic = ::gtsam::internal::getTicTocID(#label); \
|
||||
::gtsam::internal::AutoTicToc label##_obj = ::gtsam::internal::AutoTicToc(label##_id_tic, #label)
|
||||
|
||||
// toc
|
||||
#define gttoc_(label) \
|
||||
label##_obj.stop()
|
||||
|
||||
// tic
|
||||
#define longtic_(label) \
|
||||
static const size_t label##_id_tic = ::gtsam::internal::getTicTocID(#label); \
|
||||
::gtsam::internal::ticInternal(label##_id_tic, #label)
|
||||
|
||||
// toc
|
||||
#define longtoc_(label) \
|
||||
static const size_t label##_id_toc = ::gtsam::internal::getTicTocID(#label); \
|
||||
::gtsam::internal::tocInternal(label##_id_toc, #label)
|
||||
|
||||
// indicate iteration is finished
|
||||
inline void tictoc_finishedIteration_() {
|
||||
internal::timingRoot->finishedIteration(); }
|
||||
|
||||
// print
|
||||
inline void tictoc_print_() {
|
||||
internal::timingRoot->print(); }
|
||||
/* print mean and standard deviation */
|
||||
|
||||
// print mean and standard deviation
|
||||
inline void tictoc_print2_() {
|
||||
internal::timingRoot->print2(); }
|
||||
|
||||
// get a node by label and assign it to variable
|
||||
#define tictoc_getNode(variable, label) \
|
||||
static const size_t label##_id_getnode = ::gtsam::internal::getTicTocID(#label); \
|
||||
const boost::shared_ptr<const internal::TimingOutline> variable = \
|
||||
internal::timingCurrent.lock()->child(label##_id_getnode, #label, internal::timingCurrent);
|
||||
|
||||
// reset
|
||||
inline void tictoc_reset_() {
|
||||
internal::timingRoot.reset(new internal::TimingOutline("Total", internal::getTicTocID("Total")));
|
||||
internal::timingCurrent = internal::timingRoot; }
|
||||
|
|
Loading…
Reference in New Issue