mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
scope_timer.h
Go to the documentation of this file.
1
5#ifndef SCOPE_TIMER_H
6#define SCOPE_TIMER_H
7
8#include <rclcpp/rclcpp.hpp>
9#include <chrono>
10#include <fstream>
11#include <mutex>
12/* #include <ctime> */
13
14namespace mrs_lib
15{
16
17 /*//{ ScopeTimerLogger class */
18
23 {
24
25 public:
29 ScopeTimerLogger(const rclcpp::Node::SharedPtr& node, const std::string& logfile, const bool enable_logging = true, const int log_precision = 10);
30
35
39 bool shouldLog()
40 {
41 return _should_log_;
42 }
43
49 {
50 return _logging_enabled_;
51 }
52
56 std::string getLogFilepath()
57 {
58 return _log_filepath_;
59 }
60
61 using chrono_tp = std::chrono::time_point<std::chrono::steady_clock>;
62
66 void log(const std::string& scope, const chrono_tp& time_start, const chrono_tp& time_end);
67
71 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);
72
73 private:
74 bool _logging_enabled_ = false;
75 bool _should_log_ = false;
76 std::string _log_filepath_;
77 std::ofstream _logstream_;
78 std::mutex _mutex_logstream_;
79 rclcpp::Node::SharedPtr node_;
80 };
81
82 /*//}*/
83
88 {
89 public:
90 /* time_point() helper struct //{ */
92 {
93 using chrono_tp = std::chrono::time_point<std::chrono::steady_clock>;
94
95 public:
96 time_point(const rclcpp::Node::SharedPtr& node, const std::string& label) : chrono_time(std::chrono::steady_clock::now()), label(label)
97 {
98 ros_time = node->get_clock()->now();
99 }
100
101 time_point(const rclcpp::Node::SharedPtr& node, const std::string& label, const rclcpp::Time& ros_time) : ros_time(ros_time), label(label)
102 {
103
104 // helper types to make the code slightly more readable
105 using float_seconds = std::chrono::duration<float>;
106 using chrono_duration = std::chrono::steady_clock::duration;
107
108 // prepare ros and chrono current times to minimize their difference
109 const auto ros_now = node->get_clock()->now();
110
111 const auto chrono_now = std::chrono::steady_clock::now();
112
113 // calculate how old is ros_time
114 const auto ros_dt = ros_now - ros_time;
115
116 // cast ros_dt to chrono type
117 const auto chrono_dt = std::chrono::duration_cast<chrono_duration>(float_seconds(ros_dt.seconds()));
118
119 // calculate ros_time in chrono time and set it to chrono_time
120 chrono_time = chrono_now - chrono_dt;
121 }
122
123 rclcpp::Time ros_time;
124 chrono_tp chrono_time;
125 std::string label;
126 };
127 //}
128
129 public:
133 ScopeTimer(const rclcpp::Node::SharedPtr& node, const std::string& label, const rclcpp::Duration& throttle_period = rclcpp::Duration(0, 0),
134 const bool enable = true, const std::shared_ptr<ScopeTimerLogger> scope_timer_logger = nullptr);
135
139 ScopeTimer(const rclcpp::Node::SharedPtr& node, const std::string& label, const time_point& tp0,
140 const rclcpp::Duration& throttle_period = rclcpp::Duration(0, 0), const bool enable = true,
141 const std::shared_ptr<ScopeTimerLogger> scope_timer_logger = nullptr);
142
146 ScopeTimer(const rclcpp::Node::SharedPtr& node, const std::string& label, const std::shared_ptr<ScopeTimerLogger> scope_timer_logger,
147 const bool enable = true);
148
152 void checkpoint(const std::string& label);
153
159 float getLifetime();
160
164 ~ScopeTimer();
165
166 private:
167 rclcpp::Node::SharedPtr node_;
168
169 std::string _timer_label_;
170 bool _enable_print_or_log;
171 rclcpp::Duration _throttle_period_;
172 std::vector<time_point> checkpoints;
173
174 std::shared_ptr<ScopeTimerLogger> _logger_ = nullptr;
175
176 static std::unordered_map<std::string, rclcpp::Time> last_print_times;
177 };
178
179} // namespace mrs_lib
180
181#endif
Simple file logger of scope timer and its checkpoints.
Definition scope_timer.h:23
~ScopeTimerLogger()
The basic destructor which closes the logging file.
Definition scope_timer.cpp:54
bool shouldLog()
Returns true if a non-empty path to a logger file was given by the user.
Definition scope_timer.h:39
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:65
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
std::string getLogFilepath()
Returns the path to the log.
Definition scope_timer.h:56
Simple timer which will time a duration of a scope and checkpoints inside the scope in ros time and s...
Definition scope_timer.h:88
~ScopeTimer()
The basic destructor which prints out or logs the scope times, if enabled.
Definition scope_timer.cpp:161
float getLifetime()
Getter for scope timer lifetime.
Definition scope_timer.cpp:151
void checkpoint(const std::string &label)
Checkpoint, prints the time passed until the point this function is called.
Definition scope_timer.cpp:138
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24
Definition scope_timer.h:92