8#include <rclcpp/rclcpp.hpp>
29 ScopeTimerLogger(
const rclcpp::Node::SharedPtr& node,
const std::string& logfile,
const bool enable_logging =
true,
const int log_precision = 10);
50 return _logging_enabled_;
58 return _log_filepath_;
61 using chrono_tp = std::chrono::time_point<std::chrono::steady_clock>;
66 void log(
const std::string& scope,
const chrono_tp& time_start,
const chrono_tp& time_end);
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);
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_;
93 using chrono_tp = std::chrono::time_point<std::chrono::steady_clock>;
96 time_point(
const rclcpp::Node::SharedPtr& node,
const std::string& label) : chrono_time(std::chrono::steady_clock::now()), label(label)
98 ros_time = node->get_clock()->now();
101 time_point(
const rclcpp::Node::SharedPtr& node,
const std::string& label,
const rclcpp::Time& ros_time) : ros_time(ros_time), label(label)
105 using float_seconds = std::chrono::duration<float>;
106 using chrono_duration = std::chrono::steady_clock::duration;
109 const auto ros_now = node->get_clock()->now();
111 const auto chrono_now = std::chrono::steady_clock::now();
114 const auto ros_dt = ros_now - ros_time;
117 const auto chrono_dt = std::chrono::duration_cast<chrono_duration>(float_seconds(ros_dt.seconds()));
120 chrono_time = chrono_now - chrono_dt;
123 rclcpp::Time ros_time;
124 chrono_tp chrono_time;
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);
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);
146 ScopeTimer(
const rclcpp::Node::SharedPtr& node,
const std::string& label,
const std::shared_ptr<ScopeTimerLogger> scope_timer_logger,
147 const bool enable =
true);
167 rclcpp::Node::SharedPtr node_;
169 std::string _timer_label_;
170 bool _enable_print_or_log;
171 rclcpp::Duration _throttle_period_;
172 std::vector<time_point> checkpoints;
174 std::shared_ptr<ScopeTimerLogger> _logger_ =
nullptr;
176 static std::unordered_map<std::string, rclcpp::Time> last_print_times;
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