Skip to content
This repository has been archived by the owner on Jun 10, 2021. It is now read-only.

Commit

Permalink
address PR comments
Browse files Browse the repository at this point in the history
  • Loading branch information
mm318 committed Jan 5, 2020
1 parent 5087457 commit 8332351
Show file tree
Hide file tree
Showing 4 changed files with 42 additions and 44 deletions.
Expand Up @@ -57,7 +57,7 @@ bool LinuxProcessCpuMeasurementNode::SetupStart()

double LinuxProcessCpuMeasurementNode::PeriodicMeasurement()
{
const ProcPidCpuData current_measurement = MeasurePidCpuTime();
const auto current_measurement = MeasurePidCpuTime();

const auto cpu_percentage = ComputePidCpuActivePercentage(last_measurement_, current_measurement);

Expand Down
Expand Up @@ -20,9 +20,9 @@
#include <string>
#include <tuple>

#include "../../src/system_metrics_collector/periodic_measurement_node.hpp"
#include "../../src/system_metrics_collector/proc_cpu_data.hpp"
#include "../../src/system_metrics_collector/utilities.hpp"
#include "periodic_measurement_node.hpp"
#include "proc_cpu_data.hpp"
#include "utilities.hpp"

#include "rclcpp/rclcpp.hpp"
#include "rcutils/logging_macros.h"
Expand Down
55 changes: 17 additions & 38 deletions system_metrics_collector/src/system_metrics_collector/main.cpp
Expand Up @@ -34,6 +34,17 @@ constexpr const std::chrono::seconds kDefaultCollectPeriod{1};
constexpr const std::chrono::minutes kDefaultPublishPeriod{1};
} // namespace

void set_node_to_debug(
const system_metrics_collector::PeriodicMeasurementNode * node,
const char * node_type)
{
const auto r = rcutils_logging_set_logger_level(node->get_name(), RCUTILS_LOG_SEVERITY_DEBUG);
if (r != 0) {
RCUTILS_LOG_ERROR_NAMED("main", "Unable to set debug logging for the %s node: %s\n", node_type,
rcutils_get_error_string().str);
}
}

/**
* This is current a "test" main in order to manually test the measurement nodes.
*
Expand Down Expand Up @@ -62,14 +73,14 @@ int main(int argc, char ** argv)
std::make_shared<system_metrics_collector::LinuxProcessCpuMeasurementNode>(
"linuxProcessCpuCollector",
kDefaultCollectPeriod,
"not_publishing_yet",
kStatisticsTopicName,
kDefaultPublishPeriod);

const auto process_mem_node =
std::make_shared<system_metrics_collector::LinuxProcessMemoryMeasurementNode>(
"linuxProcessMemoryCollector",
kDefaultCollectPeriod,
"not_publishing_yet",
kStatisticsTopicName,
kDefaultPublishPeriod);

rclcpp::executors::MultiThreadedExecutor ex;
Expand All @@ -78,42 +89,10 @@ int main(int argc, char ** argv)
process_cpu_node->Start();
process_mem_node->Start();

{
const auto r =
rcutils_logging_set_logger_level(cpu_node->get_name(), RCUTILS_LOG_SEVERITY_DEBUG);
if (r != 0) {
RCUTILS_LOG_ERROR_NAMED("main", "Unable to set debug logging for the cpu node: %s\n",
rcutils_get_error_string().str);
}
}
{
const auto r =
rcutils_logging_set_logger_level(mem_node->get_name(), RCUTILS_LOG_SEVERITY_DEBUG);
if (r != 0) {
RCUTILS_LOG_ERROR_NAMED("main", "Unable to set debug logging for the memory node: %s\n",
rcutils_get_error_string().str);
}
}
{
const auto r = rcutils_logging_set_logger_level(
process_cpu_node->get_name(), RCUTILS_LOG_SEVERITY_DEBUG);

if (r != 0) {
RCUTILS_LOG_ERROR_NAMED("main",
"Unable to set debug logging for the process cpu node: %s\n",
rcutils_get_error_string().str);
}
}
{
const auto r = rcutils_logging_set_logger_level(
process_mem_node->get_name(), RCUTILS_LOG_SEVERITY_DEBUG);

if (r != 0) {
RCUTILS_LOG_ERROR_NAMED("main",
"Unable to set debug logging for the process memory node: %s\n",
rcutils_get_error_string().str);
}
}
set_node_to_debug(cpu_node.get(), "cpu");
set_node_to_debug(mem_node.get(), "memory");
set_node_to_debug(process_cpu_node.get(), "process cpu");
set_node_to_debug(process_mem_node.get(), "process memory");

ex.add_node(cpu_node);
ex.add_node(mem_node);
Expand Down
Expand Up @@ -15,8 +15,8 @@
#include <gtest/gtest.h>

#include <cmath>
#include <memory>
#include <fstream>
#include <memory>
#include <string>
#include <tuple>
#include <unordered_map>
Expand Down Expand Up @@ -52,11 +52,23 @@ class TestLinuxProcessCpuMeasurementNode : public system_metrics_collector::
const std::chrono::milliseconds publish_period)
: LinuxProcessCpuMeasurementNode(name, measurement_period, topic, publish_period) {}

/**
* Exposes the protected member function for testing purposes.
* See description for LinuxProcessCpuMeasurementNode::PeriodicMeasurement().
*
* @return percentage of CPU this process used
*/
double PeriodicMeasurement() override
{
LinuxProcessCpuMeasurementNode::PeriodicMeasurement();
}

/**
* Exposes the protected member function for testing purposes.
* See description for LinuxProcessCpuMeasurementNode::GetMetricName().
*
* @return a string of the name for this measured metric
*/
std::string GetMetricName() const override
{
return LinuxProcessCpuMeasurementNode::GetMetricName();
Expand Down Expand Up @@ -84,13 +96,20 @@ class TestReceiveProcessCpuMeasurementNode : public rclcpp::Node
private:
void MetricsMessageCallback(const MetricsMessage & msg) const
{
// Given kPublishPeriod is 80 ms and kTestDuration is 250 ms, the expectation is:
// MetricsMessages are published/received at 80 ms, 160 ms, and 240 ms during the first round.
// The TestLinuxProcessCpuMeasurementNode is then stopped and restarted and again
// MetricsMessages are published/received at 80 ms, 160 ms, and 240 ms during the second round.
// This means that no more than 6 MetricsMessages are received.
ASSERT_GT(6, times_received_);

// check source names
EXPECT_EQ(kTestNodeName, msg.measurement_source_name);
EXPECT_EQ(expected_metric_name_, msg.metrics_source);

// check measurements
// Check measurements.
// There are five types of statistics:
// average, maximum, minimum, standard deviation, number of samples
EXPECT_EQ(5, msg.statistics.size());

for (const StatisticDataPoint & stat : msg.statistics) {
Expand Down

0 comments on commit 8332351

Please sign in to comment.