|
mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
Go to the documentation of this file.
30 ScopeTimerLogger(
const std::string& logfile,
const bool enable_logging =
true,
const int log_precision = 10);
49 return _logging_enabled_;
56 return _log_filepath_;
59 using chrono_tp = std::chrono::time_point<std::chrono::steady_clock>;
64 void log(
const std::string& scope,
const chrono_tp& time_start,
const chrono_tp& time_end);
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);
72 bool _logging_enabled_ =
false;
73 bool _should_log_ =
false;
74 std::string _log_filepath_;
75 std::ofstream _logstream_;
76 std::mutex _mutex_logstream_;
89 using chrono_tp = std::chrono::time_point<std::chrono::steady_clock>;
92 time_point(
const std::string& label) : ros_time(ros::Time::now()), chrono_time(std::chrono::steady_clock::now()), label(label) {
95 time_point(
const std::string& label,
const ros::Time& ros_time) : ros_time(ros_time), label(label) {
97 using float_seconds = std::chrono::duration<float>;
98 using chrono_duration = std::chrono::steady_clock::duration;
100 const auto ros_now = ros::Time::now();
101 const auto chrono_now = std::chrono::steady_clock::now();
103 const auto ros_dt = ros_now - ros_time;
105 const auto chrono_dt = std::chrono::duration_cast<chrono_duration>(float_seconds(ros_dt.toSec()));
107 chrono_time = chrono_now - chrono_dt;
111 chrono_tp chrono_time;
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);
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);
132 ScopeTimer(
const std::string& label,
const std::shared_ptr<ScopeTimerLogger> scope_timer_logger,
const bool enable =
true);
152 std::string _timer_label_;
153 bool _enable_print_or_log;
154 ros::Duration _throttle_period_;
155 std::vector<time_point> checkpoints;
157 std::shared_ptr<ScopeTimerLogger> _logger_ =
nullptr;
159 static std::unordered_map<std::string, ros::Time> last_print_times;
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
float getLifetime()
Getter for scope timer lifetime.
Definition: scope_timer.cpp:126
std::string getLogFilepath()
Returns the path to the log.
Definition: scope_timer.h:55
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
~ScopeTimer()
The basic destructor which prints out or logs the scope times, if enabled.
Definition: scope_timer.cpp:135
Simple file logger of scope timer and its checkpoints.
Definition: scope_timer.h:24
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
void checkpoint(const std::string &label)
Checkpoint, prints the time passed until the point this function is called.
Definition: scope_timer.cpp:115
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition: attitude_converter.h:29
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
bool shouldLog()
Returns true if a non-empty path to a logger file was given by the user.
Definition: scope_timer.h:40
~ScopeTimerLogger()
The basic destructor which closes the logging file.
Definition: scope_timer.cpp:46
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
Definition: scope_timer.h:87