mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
scope_timer.h
Go to the documentation of this file.
1 
5 #ifndef SCOPE_TIMER_H
6 #define SCOPE_TIMER_H
7 
8 #include <ros/ros.h>
9 #include <chrono>
10 #include <iostream>
11 #include <fstream>
12 #include <iomanip>
13 #include <mutex>
14 /* #include <ctime> */
15 
16 namespace mrs_lib
17 {
18 
19 /*//{ ScopeTimerLogger class */
20 
25 
26 public:
30  ScopeTimerLogger(const std::string& logfile, const bool enable_logging = true, const int log_precision = 10);
31 
36 
40  bool shouldLog() {
41  return _should_log_;
42  }
43 
48  bool loggingEnabled() {
49  return _logging_enabled_;
50  }
51 
55  std::string getLogFilepath() {
56  return _log_filepath_;
57  }
58 
59  using chrono_tp = std::chrono::time_point<std::chrono::steady_clock>;
60 
64  void log(const std::string& scope, const chrono_tp& time_start, const chrono_tp& time_end);
65 
69  void log(const std::string& scope, const std::string& label_from, const std::string& label_to, const chrono_tp& time_start, const chrono_tp& time_end);
70 
71 private:
72  bool _logging_enabled_ = false;
73  bool _should_log_ = false;
74  std::string _log_filepath_;
75  std::ofstream _logstream_;
76  std::mutex _mutex_logstream_;
77 };
78 
79 /*//}*/
80 
84 class ScopeTimer {
85 public:
86  /* time_point() helper struct //{ */
87  struct time_point
88  {
89  using chrono_tp = std::chrono::time_point<std::chrono::steady_clock>;
90 
91  public:
92  time_point(const std::string& label) : ros_time(ros::Time::now()), chrono_time(std::chrono::steady_clock::now()), label(label) {
93  }
94 
95  time_point(const std::string& label, const ros::Time& ros_time) : ros_time(ros_time), label(label) {
96  // helper types to make the code slightly more readable
97  using float_seconds = std::chrono::duration<float>;
98  using chrono_duration = std::chrono::steady_clock::duration;
99  // prepare ros and chrono current times to minimize their difference
100  const auto ros_now = ros::Time::now();
101  const auto chrono_now = std::chrono::steady_clock::now();
102  // calculate how old is ros_time
103  const auto ros_dt = ros_now - ros_time;
104  // cast ros_dt to chrono type
105  const auto chrono_dt = std::chrono::duration_cast<chrono_duration>(float_seconds(ros_dt.toSec()));
106  // calculate ros_time in chrono time and set it to chrono_time
107  chrono_time = chrono_now - chrono_dt;
108  }
109 
110  ros::Time ros_time;
111  chrono_tp chrono_time;
112  std::string label;
113  };
114  //}
115 
116 public:
120  ScopeTimer(const std::string& label, const ros::Duration& throttle_period = ros::Duration(0), const bool enable = true,
121  const std::shared_ptr<ScopeTimerLogger> scope_timer_logger = nullptr);
122 
126  ScopeTimer(const std::string& label, const time_point& tp0, const ros::Duration& throttle_period = ros::Duration(0), const bool enable = true,
127  const std::shared_ptr<ScopeTimerLogger> scope_timer_logger = nullptr);
128 
132  ScopeTimer(const std::string& label, const std::shared_ptr<ScopeTimerLogger> scope_timer_logger, const bool enable = true);
133 
137  void checkpoint(const std::string& label);
138 
144  float getLifetime();
145 
149  ~ScopeTimer();
150 
151 private:
152  std::string _timer_label_;
153  bool _enable_print_or_log;
154  ros::Duration _throttle_period_;
155  std::vector<time_point> checkpoints;
156 
157  std::shared_ptr<ScopeTimerLogger> _logger_ = nullptr;
158 
159  static std::unordered_map<std::string, ros::Time> last_print_times;
160 };
161 
162 } // namespace mrs_lib
163 
164 #endif
mrs_lib::ScopeTimerLogger::ScopeTimerLogger
ScopeTimerLogger(const std::string &logfile, const bool enable_logging=true, const int log_precision=10)
The basic constructor with a user-defined path to the logger file, enable flag and float-logging prec...
Definition: scope_timer.cpp:9
mrs_lib::ScopeTimer::getLifetime
float getLifetime()
Getter for scope timer lifetime.
Definition: scope_timer.cpp:126
mrs_lib::ScopeTimerLogger::getLogFilepath
std::string getLogFilepath()
Returns the path to the log.
Definition: scope_timer.h:55
mrs_lib::ScopeTimer
Simple timer which will time a duration of a scope and checkpoints inside the scope in ros time and s...
Definition: scope_timer.h:84
mrs_lib::ScopeTimer::~ScopeTimer
~ScopeTimer()
The basic destructor which prints out or logs the scope times, if enabled.
Definition: scope_timer.cpp:135
mrs_lib::ScopeTimerLogger
Simple file logger of scope timer and its checkpoints.
Definition: scope_timer.h:24
mrs_lib::ScopeTimer::ScopeTimer
ScopeTimer(const std::string &label, const ros::Duration &throttle_period=ros::Duration(0), const bool enable=true, const std::shared_ptr< ScopeTimerLogger > scope_timer_logger=nullptr)
The basic constructor with a user-defined label of the timer, throttled period and file logger.
Definition: scope_timer.cpp:84
mrs_lib::ScopeTimer::checkpoint
void checkpoint(const std::string &label)
Checkpoint, prints the time passed until the point this function is called.
Definition: scope_timer.cpp:115
mrs_lib
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition: attitude_converter.h:29
mrs_lib::ScopeTimerLogger::log
void log(const std::string &scope, const chrono_tp &time_start, const chrono_tp &time_end)
Writes the time data of the given scope and empty checkpoints into the logger stream.
Definition: scope_timer.cpp:55
mrs_lib::ScopeTimerLogger::shouldLog
bool shouldLog()
Returns true if a non-empty path to a logger file was given by the user.
Definition: scope_timer.h:40
mrs_lib::ScopeTimerLogger::~ScopeTimerLogger
~ScopeTimerLogger()
The basic destructor which closes the logging file.
Definition: scope_timer.cpp:46
mrs_lib::ScopeTimerLogger::loggingEnabled
bool loggingEnabled()
Returns true if the enable flag was set to true, a non-empty path to a logger file was given by the u...
Definition: scope_timer.h:48
mrs_lib::ScopeTimer::time_point
Definition: scope_timer.h:87