Skip to content

Commit

Permalink
Address comments on PR#83
Browse files Browse the repository at this point in the history
  • Loading branch information
victorreijgwart committed Nov 19, 2024
1 parent 5e353ce commit 5cb37ee
Show file tree
Hide file tree
Showing 6 changed files with 88 additions and 37 deletions.
11 changes: 4 additions & 7 deletions interfaces/ros1/wavemap_ros/app/rosbag_processor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
62 changes: 44 additions & 18 deletions library/cpp/include/wavemap/core/utils/profile/resource_monitor.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,8 @@
#define WAVEMAP_CORE_UTILS_PROFILE_RESOURCE_MONITOR_H_

#include <ctime>
#include <fstream>
#include <optional>
#include <sstream>
#include <string>

#include "wavemap/core/common.h"
#include "wavemap/core/utils/time/time.h"
Expand All @@ -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:
Expand All @@ -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();

Expand All @@ -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<size_t> 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<double>(last_episode_cpu_duration_);
Expand All @@ -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<double>(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.
*
Expand Down Expand Up @@ -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<size_t> getCurrentRamUsageInKB();
std::string getTotalResourceUsageStats() const;

/**
* @brief Resets the stopwatch to its initial state.
Expand Down
20 changes: 10 additions & 10 deletions library/cpp/include/wavemap/core/utils/time/stopwatch.h
Original file line number Diff line number Diff line change
Expand Up @@ -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();

Expand All @@ -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 {
Expand All @@ -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<double>(total_duration_);
Expand All @@ -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{}; }

Expand Down
30 changes: 29 additions & 1 deletion library/cpp/src/core/utils/profile/resource_monitor.cc
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
#include "wavemap/core/utils/profile/resource_monitor.h"

#include <string>
#include <fstream>
#include <iomanip>
#include <sstream>

namespace wavemap {
void ResourceMonitor::start() {
Expand Down Expand Up @@ -67,6 +69,32 @@ std::optional<size_t> 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) +
Expand Down
2 changes: 1 addition & 1 deletion library/cpp/test/src/core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit 5cb37ee

Please sign in to comment.