From 5cb37ee3559b7a6776c9a9a877d3398eacdc5d42 Mon Sep 17 00:00:00 2001 From: Victor Reijgwart Date: Tue, 19 Nov 2024 20:39:01 +0100 Subject: [PATCH] Address comments on PR#83 --- .../ros1/wavemap_ros/app/rosbag_processor.cc | 11 ++-- .../core/utils/profile/resource_monitor.h | 62 +++++++++++++------ .../wavemap/core/utils/time/stopwatch.h | 20 +++--- .../core/utils/profile/resource_monitor.cc | 30 ++++++++- library/cpp/test/src/core/CMakeLists.txt | 2 +- ...ge_monitor.cc => test_resource_monitor.cc} | 0 6 files changed, 88 insertions(+), 37 deletions(-) rename library/cpp/test/src/core/utils/profile/{test_usage_monitor.cc => test_resource_monitor.cc} (100%) diff --git a/interfaces/ros1/wavemap_ros/app/rosbag_processor.cc b/interfaces/ros1/wavemap_ros/app/rosbag_processor.cc index 6c0da7d50..c7a809a43 100644 --- a/interfaces/ros1/wavemap_ros/app/rosbag_processor.cc +++ b/interfaces/ros1/wavemap_ros/app/rosbag_processor.cc @@ -91,13 +91,10 @@ int main(int argc, char** argv) { // Report the resource usage resource_monitor.stop(); - LOG(INFO) << "Processing complete.\nResource usage:\n* RAM total: " - << ResourceMonitor::getCurrentRamUsageInKB().value_or(0u) - << " kB\n* Map size: " - << wavemap_server.getMap()->getMemoryUsage() / 1000 - << " kB\n* CPU time: " << resource_monitor.getLastEpisodeCpuTime() - << " s\n* Wall time: " << resource_monitor.getLastEpisodeWallTime() - << " s\n"; + LOG(INFO) << "Processing complete.\nResource usage:\n" + << resource_monitor.getLastEpisodeResourceUsageStats() + << "\n* Map size: " + << wavemap_server.getMap()->getMemoryUsage() / 1024 << " kB\n"; if (nh_private.param("keep_alive", false)) { ros::spin(); diff --git a/library/cpp/include/wavemap/core/utils/profile/resource_monitor.h b/library/cpp/include/wavemap/core/utils/profile/resource_monitor.h index 8885973af..9929ef65e 100644 --- a/library/cpp/include/wavemap/core/utils/profile/resource_monitor.h +++ b/library/cpp/include/wavemap/core/utils/profile/resource_monitor.h @@ -2,9 +2,8 @@ #define WAVEMAP_CORE_UTILS_PROFILE_RESOURCE_MONITOR_H_ #include -#include #include -#include +#include #include "wavemap/core/common.h" #include "wavemap/core/utils/time/time.h" @@ -15,8 +14,8 @@ namespace wavemap { * and RAM usage. * * The `ResourceMonitor` class tracks CPU and wall clock time over timed - * episodes, much like wavemap's Stopwatch class. It also provides functionality - * to retrieve the total RAM usage of the current process. + * episodes, much like wavemap's Stopwatch class. It also provides + * functionality to retrieve the total RAM usage of the current process. */ class ResourceMonitor { public: @@ -31,9 +30,9 @@ class ResourceMonitor { /** * @brief Stops timing the current episode. * - * Records the end CPU and wall clock times for the current episode, - * updating the last episode duration and total accumulated duration. - * If monitoring is not running, calling `stop()` has no effect. + * Records the end CPU and wall clock times for the current episode, updating + * the last episode duration and total accumulated duration. If no episode is + * in progress, calling `stop()` has no effect. */ void stop(); @@ -44,14 +43,23 @@ class ResourceMonitor { */ bool isRunning() const { return running_; } + /** + * @brief Gets the current RAM usage of the application. + * + * @return The current RAM usage in kilobytes, or `std::nullopt` (an empty + * optional) if retrieving RAM usage is not supported on the given + * platform. + */ + static std::optional getCurrentRamUsageInKB(); + /** * @brief Gets the CPU time duration of the last episode. * * @return The CPU time duration of the last episode in seconds. * - * The value represents the CPU time elapsed between the most recent - * `start()` and `stop()` calls. If no episode has been monitored, this - * returns 0. + * The value represents the CPU time elapsed during the most recently + * completed pair of `start()` and `stop()` calls. If no episode has been + * completed, this returns 0. */ double getLastEpisodeCpuTime() const { return time::to_seconds(last_episode_cpu_duration_); @@ -62,14 +70,27 @@ class ResourceMonitor { * * @return The wall clock time duration of the last episode in seconds. * - * The value represents the real-world time elapsed between the most recent - * `start()` and `stop()` calls. If no episode has been monitored, this - * returns 0. + * The value represents the real-world time elapsed during the most recently + * completed pair of `start()` and `stop()` calls. If no episode has been + * completed, this returns 0. */ double getLastEpisodeWallTime() const { return time::to_seconds(last_episode_wall_duration_); } + /** + * @brief Get the last episode's resource usage stats formatted as a string. + * + * @return A string with the CPU time, wall time, and RAM usage statistics. + * + * The returned string provides a human-readable summary of the resource + * usage for the most recently completed episode. CPU and wall times are + * displayed in seconds with two decimal places, while RAM usage is reported + * in kilobytes. If RAM usage information is unavailable, it will be labeled + * as "Unknown". Each statistic is printed on a new line, with a leading `*`. + */ + std::string getLastEpisodeResourceUsageStats() const; + /** * @brief Gets the total accumulated CPU time of all episodes. * @@ -97,13 +118,18 @@ class ResourceMonitor { } /** - * @brief Gets the current RAM usage of the application. + * @brief Get the total accumulated resource usage stats formatted as a + * string. * - * @return The current RAM usage in kilobytes, or `std::nullopt` (an empty - * optional) if retrieving RAM usage is not supported on the given - * platform. + * @return A string with the CPU time, wall time, and RAM usage statistics. + * + * The returned string provides a human-readable summary of the total resource + * usage for all episodes. CPU and wall times are displayed in seconds with + * two decimal places, while RAM usage is reported in kilobytes. If RAM usage + * information is unavailable, it will be labeled as "Unknown". Each statistic + * is printed on a new line, with a leading `*`. */ - static std::optional getCurrentRamUsageInKB(); + std::string getTotalResourceUsageStats() const; /** * @brief Resets the stopwatch to its initial state. diff --git a/library/cpp/include/wavemap/core/utils/time/stopwatch.h b/library/cpp/include/wavemap/core/utils/time/stopwatch.h index f554e1812..ffbdb0690 100644 --- a/library/cpp/include/wavemap/core/utils/time/stopwatch.h +++ b/library/cpp/include/wavemap/core/utils/time/stopwatch.h @@ -25,9 +25,9 @@ class Stopwatch { /** * @brief Stops the stopwatch for the current timing episode. * - * Records the end time for the current episode and updates the - * total accumulated duration. If the stopwatch is not running, - * calling `stop()` has no effect. + * Records the end time for the current episode and updates the total + * accumulated duration. If the stopwatch is not running, calling `stop()` + * has no effect. */ void stop(); @@ -43,8 +43,8 @@ class Stopwatch { * * @return The duration of the last episode in seconds as a `double`. * - * The value represents the time elapsed between the most recent - * `start()` and `stop()` calls. If no episode has been timed, + * The value represents the time elapsed during the most recently completed + * pair of `start()` and `stop()` calls. If no episode has been completed, * this returns 0. */ double getLastEpisodeDuration() const { @@ -56,9 +56,9 @@ class Stopwatch { * * @return The total duration in seconds as a `double`. * - * The value represents the sum of the durations of all episodes - * that have been timed since the creation of the stopwatch or - * since it was last reset. + * The value represents the sum of the durations of all episodes that have + * been completed since the creation of the stopwatch or since it was last + * reset. */ double getTotalDuration() const { return time::to_seconds(total_duration_); @@ -67,8 +67,8 @@ class Stopwatch { /** * @brief Resets the stopwatch to its initial state. * - * This method resets all member variables by reassigning - * the object to a default-constructed instance. + * This method resets all member variables by reassigning the object to a + * default-constructed instance. */ void reset() { *this = Stopwatch{}; } diff --git a/library/cpp/src/core/utils/profile/resource_monitor.cc b/library/cpp/src/core/utils/profile/resource_monitor.cc index 4df8171a8..de2fe606c 100644 --- a/library/cpp/src/core/utils/profile/resource_monitor.cc +++ b/library/cpp/src/core/utils/profile/resource_monitor.cc @@ -1,6 +1,8 @@ #include "wavemap/core/utils/profile/resource_monitor.h" -#include +#include +#include +#include namespace wavemap { void ResourceMonitor::start() { @@ -67,6 +69,32 @@ std::optional ResourceMonitor::getCurrentRamUsageInKB() { return ram_usage; } +std::string ResourceMonitor::getLastEpisodeResourceUsageStats() const { + std::ostringstream oss; + oss << std::fixed << std::setprecision(2); // Print with two decimals + oss << "* CPU time: " << getLastEpisodeCpuTime() << " s\n" + << "* Wall time: " << getLastEpisodeWallTime() << " s\n"; + if (const auto ram_usage = getCurrentRamUsageInKB(); ram_usage) { + oss << "* RAM total: " << *ram_usage << " kB"; + } else { + oss << "* RAM total: Unknown"; + } + return oss.str(); +} + +std::string ResourceMonitor::getTotalResourceUsageStats() const { + std::ostringstream oss; + oss << std::fixed << std::setprecision(2); // Print with two decimals + oss << "* CPU time: " << getTotalCpuTime() << " s\n" + << "* Wall time: " << getTotalWallTime() << " s\n"; + if (const auto ram_usage = getCurrentRamUsageInKB(); ram_usage) { + oss << "* RAM total: " << *ram_usage << " kB"; + } else { + oss << "* RAM total: Unknown"; + } + return oss.str(); +} + Duration ResourceMonitor::computeDuration(const timespec& start, const timespec& stop) { return std::chrono::seconds(stop.tv_sec - start.tv_sec) + diff --git a/library/cpp/test/src/core/CMakeLists.txt b/library/cpp/test/src/core/CMakeLists.txt index 57d38b435..cb246e0ec 100644 --- a/library/cpp/test/src/core/CMakeLists.txt +++ b/library/cpp/test/src/core/CMakeLists.txt @@ -34,7 +34,7 @@ target_sources(test_wavemap_core PRIVATE utils/neighbors/test_grid_adjacency.cc utils/neighbors/test_grid_neighborhood.cc utils/neighbors/test_ndtree_adjacency.cc - utils/profile/test_usage_monitor.cc + utils/profile/test_resource_monitor.cc utils/query/test_classified_map.cc utils/query/test_map_interpolator.cpp utils/query/test_occupancy_classifier.cc diff --git a/library/cpp/test/src/core/utils/profile/test_usage_monitor.cc b/library/cpp/test/src/core/utils/profile/test_resource_monitor.cc similarity index 100% rename from library/cpp/test/src/core/utils/profile/test_usage_monitor.cc rename to library/cpp/test/src/core/utils/profile/test_resource_monitor.cc