Skip to content

Commit

Permalink
Document Stopwatch and ResourceMonitor classes and add tests
Browse files Browse the repository at this point in the history
  • Loading branch information
victorreijgwart committed Nov 19, 2024
1 parent 0c0e35d commit 3db5319
Show file tree
Hide file tree
Showing 5 changed files with 356 additions and 0 deletions.
108 changes: 108 additions & 0 deletions library/cpp/include/wavemap/core/utils/profile/resource_monitor.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,33 +9,141 @@
#include "wavemap/core/utils/time/time.h"

namespace wavemap {
/**
* @brief Monitors system resource usage, including CPU time, wall time,
* 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.
*/
class ResourceMonitor {
public:
/**
* @brief Starts a new CPU and wall time monitoring episode.
*
* Records the CPU and wall clock start times for the current episode.
* If monitoring is already running, calling `start()` has no effect.
*/
void start();

/**
* @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.
*/
void stop();

/**
* @brief Checks if the stopwatch is currently running.
*
* @return `true` if the stopwatch is running, `false` otherwise.
*/
bool isRunning() const { return running_; }

/**
* @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.
*/
double getLastEpisodeCpuTime() const {
return time::to_seconds<double>(last_episode_cpu_duration_);
}

/**
* @brief Gets the wall clock time duration of the last episode.
*
* @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.
*/
double getLastEpisodeWallTime() const {
return time::to_seconds<double>(last_episode_wall_duration_);
}

/**
* @brief Gets the total accumulated CPU time of all episodes.
*
* @return The total CPU time in seconds.
*
* The value represents the sum of the CPU times of all episodes that have
* been timed since the creation of the resource monitor or since it was last
* reset.
*/
double getTotalCpuTime() const {
return time::to_seconds<double>(total_cpu_duration_);
}

/**
* @brief Gets the total accumulated wall clock time of all episodes.
*
* @return The total wall time in seconds.
*
* The value represents the sum of the wall times of all episodes that have
* been timed since the creation of the resource monitor or since it was last
* reset.
*/
double getTotalWallTime() const {
return time::to_seconds<double>(total_wall_duration_);
}

/**
* @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 Resets the stopwatch to its initial state.
*
* This method resets all member variables by reassigning the object to a
* default-constructed instance.
*/
void reset() { *this = ResourceMonitor{}; }

private:
/// @brief Indicates whether resource monitoring is currently running.
bool running_ = false;

/// @brief Stores the CPU time at the start of the current episode.
timespec episode_start_cpu_time_{};

/// @brief Stores the wall clock time at the start of the current episode.
timespec episode_start_wall_time_{};

/// @brief Stores the CPU time duration of the last completed episode.
Duration last_episode_cpu_duration_{};

/// @brief Stores the wall clock time duration of the last completed episode.
Duration last_episode_wall_duration_{};

/// @brief Accumulates the total CPU time duration of all episodes.
Duration total_cpu_duration_{};

/// @brief Accumulates the total wall clock time duration of all episodes.
Duration total_wall_duration_{};

/**
* @brief Computes the duration between two POSIX timestamps.
*
* @param start The starting POSIX timestamp.
* @param stop The ending POSIX timestamp.
* @return The computed duration as a wavemap::Duration.
*/
static Duration computeDuration(const timespec& start, const timespec& stop);
};

} // namespace wavemap

#endif // WAVEMAP_CORE_UTILS_PROFILE_RESOURCE_MONITOR_H_
62 changes: 62 additions & 0 deletions library/cpp/include/wavemap/core/utils/time/stopwatch.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,23 +4,85 @@
#include "wavemap/core/utils/time/time.h"

namespace wavemap {
/**
* @brief A simple utility class for measuring elapsed time across episodes.
*
* The `Stopwatch` class allows tracking the duration of multiple timed
* episodes. It provides functionality to start, stop, and retrieve timing
* information for the last episode as well as the total duration of all
* episodes.
*/
class Stopwatch {
public:
/**
* @brief Starts the stopwatch for a new timing episode.
*
* Records the start time for the current episode. If the stopwatch is
* already running, calling `start()` has no effect.
*/
void start();

/**
* @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.
*/
void stop();

/**
* @brief Checks if the stopwatch is currently running.
*
* @return `true` if the stopwatch is running, `false` otherwise.
*/
bool isRunning() const { return running_; }

/**
* @brief Gets the duration of the last timing episode.
*
* @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,
* this returns 0.
*/
double getLastEpisodeDuration() const {
return time::to_seconds<double>(last_episode_duration_);
}

/**
* @brief Gets the total accumulated duration of all episodes.
*
* @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.
*/
double getTotalDuration() const {
return time::to_seconds<double>(total_duration_);
}

/**
* @brief Resets the stopwatch to its initial state.
*
* This method resets all member variables by reassigning
* the object to a default-constructed instance.
*/
void reset() { *this = Stopwatch{}; }

private:
/// @brief Indicates whether the stopwatch is currently running.
bool running_ = false;

/// @brief Stores the start time of the current episode.
Timestamp episode_start_time_{};

/// @brief Stores the duration of the last completed episode.
Duration last_episode_duration_{};

/// @brief Accumulates the total duration of all episodes.
Duration total_duration_{};
};
} // namespace wavemap
Expand Down
2 changes: 2 additions & 0 deletions library/cpp/test/src/core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,12 +34,14 @@ 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/query/test_classified_map.cc
utils/query/test_map_interpolator.cpp
utils/query/test_occupancy_classifier.cc
utils/query/test_probability_conversions.cc
utils/query/test_query_accelerator.cc
utils/sdf/test_sdf_generators.cc
utils/time/test_stopwatch.cc
utils/test_thread_pool.cc)

set_wavemap_target_properties(test_wavemap_core)
Expand Down
99 changes: 99 additions & 0 deletions library/cpp/test/src/core/utils/profile/test_usage_monitor.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
#include <thread>

#include <gtest/gtest.h>

#include "wavemap/core/utils/profile/resource_monitor.h"

namespace wavemap {
class ResourceMonitorTest : public ::testing::Test {
protected:
ResourceMonitor resource_monitor;
};

TEST_F(ResourceMonitorTest, InitialState) {
EXPECT_FALSE(resource_monitor.isRunning());
EXPECT_EQ(resource_monitor.getLastEpisodeCpuTime(), 0.0);
EXPECT_EQ(resource_monitor.getLastEpisodeWallTime(), 0.0);
EXPECT_EQ(resource_monitor.getTotalCpuTime(), 0.0);
EXPECT_EQ(resource_monitor.getTotalWallTime(), 0.0);
}

TEST_F(ResourceMonitorTest, Start) {
resource_monitor.start();
EXPECT_TRUE(resource_monitor.isRunning());
}

TEST_F(ResourceMonitorTest, Stop) {
resource_monitor.start();
resource_monitor.stop();
EXPECT_FALSE(resource_monitor.isRunning());
}

TEST_F(ResourceMonitorTest, Reset) {
resource_monitor.start();
std::this_thread::sleep_for(std::chrono::milliseconds(1));
resource_monitor.stop();

resource_monitor.reset();
EXPECT_FALSE(resource_monitor.isRunning());
EXPECT_EQ(resource_monitor.getLastEpisodeCpuTime(), 0.0);
EXPECT_EQ(resource_monitor.getLastEpisodeWallTime(), 0.0);
EXPECT_EQ(resource_monitor.getTotalCpuTime(), 0.0);
EXPECT_EQ(resource_monitor.getTotalWallTime(), 0.0);
}

TEST_F(ResourceMonitorTest, DurationTracking) {
resource_monitor.start();
std::this_thread::sleep_for(std::chrono::milliseconds(100));
resource_monitor.stop();

const double first_wall_time = resource_monitor.getLastEpisodeWallTime();
EXPECT_GT(first_wall_time, 0.09); // Allow for small timing inaccuracies
EXPECT_LT(first_wall_time, 0.11); // Tolerance of ±10ms

const double first_cpu_time = resource_monitor.getLastEpisodeCpuTime();
EXPECT_GT(first_cpu_time, 0.0); // CPU time should be non-zero

EXPECT_EQ(resource_monitor.getTotalWallTime(), first_wall_time);
EXPECT_EQ(resource_monitor.getTotalCpuTime(), first_cpu_time);

resource_monitor.start();
std::this_thread::sleep_for(std::chrono::milliseconds(50));
resource_monitor.stop();

const double second_wall_time = resource_monitor.getLastEpisodeWallTime();
EXPECT_GT(second_wall_time, 0.04); // Allow for small timing inaccuracies
EXPECT_LT(second_wall_time, 0.06); // Tolerance of ±10ms

const double second_cpu_time = resource_monitor.getLastEpisodeCpuTime();
EXPECT_DOUBLE_EQ(resource_monitor.getTotalWallTime(),
first_wall_time + second_wall_time);
EXPECT_DOUBLE_EQ(resource_monitor.getTotalCpuTime(),
first_cpu_time + second_cpu_time);
}

TEST_F(ResourceMonitorTest, StopWithoutStart) {
resource_monitor.stop();
EXPECT_FALSE(resource_monitor.isRunning());
EXPECT_EQ(resource_monitor.getLastEpisodeCpuTime(), 0.0);
EXPECT_EQ(resource_monitor.getLastEpisodeWallTime(), 0.0);
}

TEST_F(ResourceMonitorTest, MultipleStarts) {
resource_monitor.start();
std::this_thread::sleep_for(std::chrono::milliseconds(100));
resource_monitor.start(); // Should have no effect
std::this_thread::sleep_for(std::chrono::milliseconds(50));
resource_monitor.stop();

const double wall_time = resource_monitor.getLastEpisodeWallTime();
EXPECT_GT(wall_time, 0.14); // Combined duration
EXPECT_LT(wall_time, 0.16); // Tolerance of ±10ms
}

TEST_F(ResourceMonitorTest, RamUsage) {
const auto ram_usage = ResourceMonitor::getCurrentRamUsageInKB();
ASSERT_TRUE(ram_usage.has_value()); // Check if the optional contains a value
EXPECT_GT(ram_usage.value(), 0); // RAM usage should be a positive value
}
} // namespace wavemap
Loading

0 comments on commit 3db5319

Please sign in to comment.