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
24public:
28 ScopeTimerLogger(const rclcpp::Node::SharedPtr& node, const std::string& logfile, const bool enable_logging = true, const int log_precision = 10);
29
34
38 bool shouldLog() {
39 return _should_log_;
40 }
41
47 return _logging_enabled_;
48 }
49
53 std::string getLogFilepath() {
54 return _log_filepath_;
55 }
56
57 using chrono_tp = std::chrono::time_point<std::chrono::steady_clock>;
58
62 void log(const std::string& scope, const chrono_tp& time_start, const chrono_tp& time_end);
63
67 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);
68
69private:
70 bool _logging_enabled_ = false;
71 bool _should_log_ = false;
72 std::string _log_filepath_;
73 std::ofstream _logstream_;
74 std::mutex _mutex_logstream_;
75 rclcpp::Node::SharedPtr node_;
76};
77
78/*//}*/
79
84public:
85 /* time_point() helper struct //{ */
87 {
88 using chrono_tp = std::chrono::time_point<std::chrono::steady_clock>;
89
90 public:
91 time_point(const rclcpp::Node::SharedPtr& node, const std::string& label) : chrono_time(std::chrono::steady_clock::now()), label(label) {
92 ros_time = node->get_clock()->now();
93 }
94
95 time_point(const rclcpp::Node::SharedPtr& node, const std::string& label, const rclcpp::Time& ros_time) : ros_time(ros_time), label(label) {
96
97 // helper types to make the code slightly more readable
98 using float_seconds = std::chrono::duration<float>;
99 using chrono_duration = std::chrono::steady_clock::duration;
100
101 // prepare ros and chrono current times to minimize their difference
102 const auto ros_now = node->get_clock()->now();
103
104 const auto chrono_now = std::chrono::steady_clock::now();
105
106 // calculate how old is ros_time
107 const auto ros_dt = ros_now - ros_time;
108
109 // cast ros_dt to chrono type
110 const auto chrono_dt = std::chrono::duration_cast<chrono_duration>(float_seconds(ros_dt.seconds()));
111
112 // calculate ros_time in chrono time and set it to chrono_time
113 chrono_time = chrono_now - chrono_dt;
114 }
115
116 rclcpp::Time ros_time;
117 chrono_tp chrono_time;
118 std::string label;
119 };
120 //}
121
122public:
126 ScopeTimer(const rclcpp::Node::SharedPtr& node, const std::string& label, const rclcpp::Duration& throttle_period = rclcpp::Duration(0, 0),
127 const bool enable = true, const std::shared_ptr<ScopeTimerLogger> scope_timer_logger = nullptr);
128
132 ScopeTimer(const rclcpp::Node::SharedPtr& node, const std::string& label, const time_point& tp0,
133 const rclcpp::Duration& throttle_period = rclcpp::Duration(0, 0), const bool enable = true,
134 const std::shared_ptr<ScopeTimerLogger> scope_timer_logger = nullptr);
135
139 ScopeTimer(const rclcpp::Node::SharedPtr& node, const std::string& label, const std::shared_ptr<ScopeTimerLogger> scope_timer_logger,
140 const bool enable = true);
141
145 void checkpoint(const std::string& label);
146
152 float getLifetime();
153
157 ~ScopeTimer();
158
159private:
160 rclcpp::Node::SharedPtr node_;
161
162 std::string _timer_label_;
163 bool _enable_print_or_log;
164 rclcpp::Duration _throttle_period_;
165 std::vector<time_point> checkpoints;
166
167 std::shared_ptr<ScopeTimerLogger> _logger_ = nullptr;
168
169 static std::unordered_map<std::string, rclcpp::Time> last_print_times;
170};
171
172} // namespace mrs_lib
173
174#endif
Simple file logger of scope timer and its checkpoints.
Definition scope_timer.h:22
~ScopeTimerLogger()
The basic destructor which closes the logging file.
Definition scope_timer.cpp:48
bool shouldLog()
Returns true if a non-empty path to a logger file was given by the user.
Definition scope_timer.h:38
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:57
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:46
std::string getLogFilepath()
Returns the path to the log.
Definition scope_timer.h:53
Simple timer which will time a duration of a scope and checkpoints inside the scope in ros time and s...
Definition scope_timer.h:83
~ScopeTimer()
The basic destructor which prints out or logs the scope times, if enabled.
Definition scope_timer.cpp:144
float getLifetime()
Getter for scope timer lifetime.
Definition scope_timer.cpp:135
void checkpoint(const std::string &label)
Checkpoint, prints the time passed until the point this function is called.
Definition scope_timer.cpp:124
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24
Definition scope_timer.h:87