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

Commit

Permalink
Measure linux cpu active percentage (#11)
Browse files Browse the repository at this point in the history
* Add linux cpu measurement node
* Add API improvements

* Split linux cpu measurement header and implementation
* Test improvements
* Cleanups

* Add main used for manual testing

* Split cpu_data header and implementation

* Add missing implementation file

* Address review comments

* Address review comments

* Rename files to reflect class name
  • Loading branch information
dabonnie committed Nov 14, 2019
1 parent 8ee4948 commit 16fe1f0
Show file tree
Hide file tree
Showing 14 changed files with 683 additions and 56 deletions.
30 changes: 23 additions & 7 deletions system_metrics_collector/CMakeLists.txt
Expand Up @@ -22,37 +22,53 @@ foreach(FLAG ${FLAGS})
endif()
endforeach()

if(WIN32)
add_definitions(-DNOMINMAX)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rcutils REQUIRED)
find_package(metrics_statistics_msgs REQUIRED)

add_library(system_metrics_collector SHARED
src/system_metrics_collector/collector.cpp
src/system_metrics_collector/linux_cpu_measurement_node.cpp
src/system_metrics_collector/periodic_measurement_node.cpp
src/system_metrics_collector/proc_cpu_data.cpp
src/moving_average_statistics/moving_average.cpp
src/moving_average_statistics/types.hpp
src/system_metrics_collector/collector.cpp
src/system_metrics_collector/periodic_measurement_node.cpp)
)

ament_target_dependencies(system_metrics_collector rclcpp rcpputils)
ament_export_libraries(system_metrics_collector)

add_executable(main src/system_metrics_collector/main.cpp)
target_link_libraries(main system_metrics_collector)
ament_target_dependencies(main)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
find_package(ament_cmake_gtest REQUIRED)

ament_lint_auto_find_test_dependencies()

ament_add_gtest(test_moving_average_statistics
test/moving_average_statistics/test_moving_average_statistics.cpp)
target_link_libraries(test_moving_average_statistics system_metrics_collector)
ament_target_dependencies(test_moving_average_statistics rclcpp)

ament_add_gtest(test_collector
test/system_metrics_collector/test_collector.cpp)
target_link_libraries(test_collector system_metrics_collector)
ament_target_dependencies(test_collector rclcpp)

ament_add_gtest(test_linux_cpu_measurement_node
test/system_metrics_collector/test_linux_cpu_measurement.cpp)
target_link_libraries(test_linux_cpu_measurement_node system_metrics_collector)
ament_target_dependencies(test_linux_cpu_measurement_node rclcpp)

ament_add_gtest(test_moving_average_statistics
test/moving_average_statistics/test_moving_average_statistics.cpp)
target_link_libraries(test_moving_average_statistics system_metrics_collector)
ament_target_dependencies(test_moving_average_statistics rclcpp)

ament_add_gtest(test_periodic_measurement_node
test/system_metrics_collector/test_periodic_measurement_node.cpp)
target_link_libraries(test_periodic_measurement_node system_metrics_collector)
Expand Down
Expand Up @@ -77,13 +77,16 @@ void MovingAverageStatistics::reset()
void MovingAverageStatistics::addMeasurement(const double item)
{
std::lock_guard<std::mutex> guard(mutex);
count_++;
const double previous_average_ = average_;
average_ = previous_average_ + (item - previous_average_) / count_;
min_ = std::min(min_, item);
max_ = std::max(max_, item);
sum_of_square_diff_from_mean_ = sum_of_square_diff_from_mean_ + (item - previous_average_) *
(item - average_);

if (!std::isnan(item)) {
count_++;
const double previous_average_ = average_;
average_ = previous_average_ + (item - previous_average_) / count_;
min_ = std::min(min_, item);
max_ = std::max(max_, item);
sum_of_square_diff_from_mean_ = sum_of_square_diff_from_mean_ + (item - previous_average_) *
(item - average_);
}
}

uint64_t MovingAverageStatistics::getCount() const
Expand Down
Expand Up @@ -93,6 +93,7 @@ class MovingAverageStatistics

/**
* Observe a sample for the given window. The input item is used to calculate statistics.
* Note: any input values of NaN will be discarded and not added as a measurement.
*
* @param item The item that was observed
**/
Expand Down
Expand Up @@ -37,7 +37,7 @@ struct StatisticData
* @return std::string formatted struct contents in an easily readable format, e.g.,
* /"avg=1, min=2, max=3, std_dev=4, count=5/"
*/
static std::string statisticsDataToString(StatisticData results)
static std::string statisticsDataToString(const StatisticData & results)
{
std::stringstream ss;
ss << "avg=" << std::to_string(results.average) << ", min=" << std::to_string(results.min) <<
Expand Down
@@ -0,0 +1,97 @@
// Copyright 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <chrono>
#include <string>

#include "linux_cpu_measurement_node.hpp"

namespace
{
constexpr const char PROC_STAT_FILE[] = "/proc/stat";
constexpr const char CPU_LABEL[] = "cpu";
constexpr const size_t CPU_LABEL_LENGTH = 3;
} // namespace

ProcCpuData processLine(const std::string & stat_cpu_line)
{
ProcCpuData parsed_data;

if (!stat_cpu_line.empty()) {
if (!stat_cpu_line.compare(0, CPU_LABEL_LENGTH, CPU_LABEL)) {
std::istringstream ss(stat_cpu_line);

if (!ss.good()) {
return ProcCpuData();
}
ss >> parsed_data.cpu_label;

for (int i = 0; i < static_cast<int>(ProcCpuStates::kNumProcCpuStates); ++i) {
if (!ss.good()) {
return ProcCpuData();
}
ss >> parsed_data.times[i];
}

return parsed_data;
}
}
return parsed_data;
}

double computeCpuActivePercentage(
const ProcCpuData & measurement1,
const ProcCpuData & measurement2)
{
if (measurement1.isMeasurementEmpty() || measurement2.isMeasurementEmpty()) {
return std::nan("");
}

const double active_time = measurement2.getActiveTime() - measurement1.getActiveTime();
const double total_time = (measurement2.getIdleTime() + measurement2.getActiveTime()) -
(measurement1.getIdleTime() + measurement2.getActiveTime());

return 100.0 * active_time / total_time;
}

LinuxCpuMeasurementNode::LinuxCpuMeasurementNode(
const std::string & name,
const std::chrono::milliseconds measurement_period,
const std::string & topic,
const std::chrono::milliseconds & publish_period)
: PeriodicMeasurementNode(name, measurement_period, topic, publish_period),
last_measurement_()
{}

double LinuxCpuMeasurementNode::periodicMeasurement()
{
ProcCpuData current_measurement = makeSingleMeasurement();

const double cpu_percentage = computeCpuActivePercentage(
last_measurement_,
current_measurement);

last_measurement_ = current_measurement;

return cpu_percentage;
}

ProcCpuData LinuxCpuMeasurementNode::makeSingleMeasurement()
{
std::ifstream stat_file(PROC_STAT_FILE);
std::string line;
std::getline(stat_file, line);

return stat_file.good() ? processLine(line) : ProcCpuData();
}
@@ -0,0 +1,86 @@
// Copyright 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef SYSTEM_METRICS_COLLECTOR__LINUX_CPU_MEASUREMENT_NODE_HPP_
#define SYSTEM_METRICS_COLLECTOR__LINUX_CPU_MEASUREMENT_NODE_HPP_

#include <fstream>
#include <iostream>
#include <sstream>
#include <string>

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

/**
* Parse a line read from /proc/stat
*
* @param stat_cpu_line a line from /proc/stat
* @return ProcCpuData struct populated if parsed, otherwise empty
*/
ProcCpuData processLine(const std::string & stat_cpu_line);

/**
* Compute the percentage of CPU active.
*
* @param measurement1 the first measurement
* @param measurement2 the second measurement (made after the first)
* @return percentage of CPU active
*/
double computeCpuActivePercentage(
const ProcCpuData & measurement1,
const ProcCpuData & measurement2);

/**
* Node that periodically calculates the % of active CPU by
* reading /proc/stat.
*/
class LinuxCpuMeasurementNode : public PeriodicMeasurementNode
{
public:
/**
*
* @param name
* @param measurement_period
* @param topic
*/
LinuxCpuMeasurementNode(
const std::string & name,
const std::chrono::milliseconds measurement_period,
const std::string & topic,
const std::chrono::milliseconds & publish_period =
PeriodicMeasurementNode::DEFAULT_PUBLISH_WINDOW);

virtual ~LinuxCpuMeasurementNode() = default;

protected:
/**
* Perform a periodic measurement calculating the percentage of CPU active.
*
* @return percentage of CPU active
*/
double periodicMeasurement() override;

private:
/**
* Perform a single measurement of cpu data by reading /proc/stat.
*
* @return ProcCpuData the measurement made
*/
virtual ProcCpuData makeSingleMeasurement();

ProcCpuData last_measurement_;
};

#endif // SYSTEM_METRICS_COLLECTOR__LINUX_CPU_MEASUREMENT_NODE_HPP_
61 changes: 61 additions & 0 deletions system_metrics_collector/src/system_metrics_collector/main.cpp
@@ -0,0 +1,61 @@
// Copyright 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.


#include <functional>

#include <chrono>
#include <memory>
#include <string>

#include "rclcpp/rclcpp.hpp"

#include "../../src/system_metrics_collector/linux_cpu_measurement_node.hpp"

/**
* This is current a "test" main in order to manually test the measurement nodes.
*
* @param argc
* @param argv
* @return
*/
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);

auto node = std::make_shared<LinuxCpuMeasurementNode>(
"linuxCpuCollector",
std::chrono::milliseconds(1000),
"not_publishing_yet",
std::chrono::milliseconds(1000 * 60));

rclcpp::executors::SingleThreadedExecutor ex;
node->start();

int code = 0;
auto r = rcutils_logging_set_logger_level(node->get_name(), RCUTILS_LOG_SEVERITY_DEBUG);

if (r != 0) {
std::cout << "Unabled to set debug logging!" << std::endl;
code = 1;
} else {
ex.add_node(node);
ex.spin();
}


rclcpp::shutdown();
node->stop();
return code;
}

0 comments on commit 16fe1f0

Please sign in to comment.