diff --git a/system_metrics_collector/CMakeLists.txt b/system_metrics_collector/CMakeLists.txt index 8691d936..5a358fe6 100644 --- a/system_metrics_collector/CMakeLists.txt +++ b/system_metrics_collector/CMakeLists.txt @@ -22,6 +22,10 @@ foreach(FLAG ${FLAGS}) endif() endforeach() +if(WIN32) + add_definitions(-DNOMINMAX) +endif() + # find dependencies find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) @@ -29,30 +33,42 @@ 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) diff --git a/system_metrics_collector/src/moving_average_statistics/moving_average.cpp b/system_metrics_collector/src/moving_average_statistics/moving_average.cpp index 2aa32d81..6a384783 100644 --- a/system_metrics_collector/src/moving_average_statistics/moving_average.cpp +++ b/system_metrics_collector/src/moving_average_statistics/moving_average.cpp @@ -77,13 +77,16 @@ void MovingAverageStatistics::reset() void MovingAverageStatistics::addMeasurement(const double item) { std::lock_guard 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 diff --git a/system_metrics_collector/src/moving_average_statistics/moving_average.hpp b/system_metrics_collector/src/moving_average_statistics/moving_average.hpp index 6c84b7ce..8859a308 100644 --- a/system_metrics_collector/src/moving_average_statistics/moving_average.hpp +++ b/system_metrics_collector/src/moving_average_statistics/moving_average.hpp @@ -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 **/ diff --git a/system_metrics_collector/src/moving_average_statistics/types.hpp b/system_metrics_collector/src/moving_average_statistics/types.hpp index 865ff68f..6567e75b 100644 --- a/system_metrics_collector/src/moving_average_statistics/types.hpp +++ b/system_metrics_collector/src/moving_average_statistics/types.hpp @@ -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) << diff --git a/system_metrics_collector/src/system_metrics_collector/linux_cpu_measurement_node.cpp b/system_metrics_collector/src/system_metrics_collector/linux_cpu_measurement_node.cpp new file mode 100644 index 00000000..698d73ef --- /dev/null +++ b/system_metrics_collector/src/system_metrics_collector/linux_cpu_measurement_node.cpp @@ -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 +#include + +#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(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(); +} diff --git a/system_metrics_collector/src/system_metrics_collector/linux_cpu_measurement_node.hpp b/system_metrics_collector/src/system_metrics_collector/linux_cpu_measurement_node.hpp new file mode 100644 index 00000000..39341a61 --- /dev/null +++ b/system_metrics_collector/src/system_metrics_collector/linux_cpu_measurement_node.hpp @@ -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 +#include +#include +#include + +#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_ diff --git a/system_metrics_collector/src/system_metrics_collector/main.cpp b/system_metrics_collector/src/system_metrics_collector/main.cpp new file mode 100644 index 00000000..0412265e --- /dev/null +++ b/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 + +#include +#include +#include + +#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( + "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; +} diff --git a/system_metrics_collector/src/system_metrics_collector/periodic_measurement_node.cpp b/system_metrics_collector/src/system_metrics_collector/periodic_measurement_node.cpp index 5e222cbe..eb21876e 100644 --- a/system_metrics_collector/src/system_metrics_collector/periodic_measurement_node.cpp +++ b/system_metrics_collector/src/system_metrics_collector/periodic_measurement_node.cpp @@ -20,29 +20,52 @@ #include "rclcpp/rclcpp.hpp" +/* static */ constexpr const std::chrono::milliseconds PeriodicMeasurementNode:: +DEFAULT_PUBLISH_WINDOW; PeriodicMeasurementNode::PeriodicMeasurementNode( const std::string & name, const std::chrono::milliseconds measurement_period, - const std::string & publishing_topic) + const std::string & publishing_topic, + const std::chrono::milliseconds & publish_period, + const bool clear_measurements_on_publish) : Node(name), measurement_period_(measurement_period), publishing_topic_(publishing_topic), - measurement_timer_(nullptr) + measurement_timer_(nullptr), + publish_timer_(nullptr), + publish_period_(publish_period), + clear_measurements_on_publish_(clear_measurements_on_publish) {} bool PeriodicMeasurementNode::setupStart() { if (!measurement_timer_) { - RCLCPP_DEBUG(this->get_logger(), "creating timer"); + RCLCPP_DEBUG(this->get_logger(), "setupStart: creating measurement_timer_"); measurement_timer_ = this->create_wall_timer( measurement_period_, - std::bind(&PeriodicMeasurementNode::periodicMeasurement, this)); + std::bind(&PeriodicMeasurementNode::performPeriodicMeasurement, this)); } else { RCLCPP_WARN(this->get_logger(), "setupStart: measurement_timer_ already exists!"); } + + if (!publish_timer_ && + publish_period_ != PeriodicMeasurementNode::DEFAULT_PUBLISH_WINDOW) + { + RCLCPP_DEBUG(this->get_logger(), "setupStart: creating publish_timer_"); + + publish_timer_ = this->create_wall_timer( + publish_period_, + std::bind(&Collector::clearCurrentMeasurements, this)); // todo fixme, bind to publish method + + } else { + if (publish_timer_) { + RCLCPP_WARN(this->get_logger(), "setupStart: publish_timer_ already exists!"); + } + } + return true; } @@ -61,6 +84,19 @@ std::string PeriodicMeasurementNode::getStatusString() const ss << "name=" << get_name() << ", measurement_period=" << std::to_string(measurement_period_.count()) << "ms" << ", publishing_topic=" << publishing_topic_ << + ", publish_period=" << + (publish_period_ != PeriodicMeasurementNode::DEFAULT_PUBLISH_WINDOW ? + std::to_string(publish_period_.count()) + "ms" : "None") << + ", clear_measurements_on_publish_=" << clear_measurements_on_publish_ << ", " << Collector::getStatusString(); return ss.str(); } + +void PeriodicMeasurementNode::performPeriodicMeasurement() +{ + const double measurement = periodicMeasurement(); + RCLCPP_DEBUG(this->get_logger(), "performPeriodicMeasurement: %f", measurement); + + acceptData(measurement); + RCLCPP_DEBUG(this->get_logger(), getStatusString()); +} diff --git a/system_metrics_collector/src/system_metrics_collector/periodic_measurement_node.hpp b/system_metrics_collector/src/system_metrics_collector/periodic_measurement_node.hpp index 7b583d16..f78bb332 100644 --- a/system_metrics_collector/src/system_metrics_collector/periodic_measurement_node.hpp +++ b/system_metrics_collector/src/system_metrics_collector/periodic_measurement_node.hpp @@ -29,17 +29,23 @@ class PeriodicMeasurementNode : public Collector, public rclcpp::Node { public: + static constexpr const std::chrono::milliseconds DEFAULT_PUBLISH_WINDOW = + std::chrono::milliseconds(0); /** * Construct a PeriodicMeasurementNode. * * @param name the name of this node * @param topic the topic for publishing data * @param measurement_period + * @param publish_period the window of active measurements. If specified all measurements + * will be cleared when the window has been exceeded. */ PeriodicMeasurementNode( const std::string & name, const std::chrono::milliseconds measurement_period, - const std::string & topic); // todo @dbbonnie think about a default topic + const std::string & topic, // todo @dbbonnie think about a default topic + const std::chrono::milliseconds & publish_period = DEFAULT_PUBLISH_WINDOW, + const bool clear_measurements_on_publish = true); virtual ~PeriodicMeasurementNode() = default; @@ -54,8 +60,16 @@ class PeriodicMeasurementNode : public Collector, public rclcpp::Node /** * Override this method to perform a single measurement. This is called via performPeriodicMeasurement * with the period defined in the constructor. + * + * @return the measurement made to be aggregated for statistics + */ + virtual double periodicMeasurement() = 0; + + /** + * Called via a ROS2 timer per the measurement_period_. This calls periodicMeasurement + * and adds the resulting output via Collector::acceptData(double data); */ - virtual void periodicMeasurement() = 0; + virtual void performPeriodicMeasurement(); /** * Creates a ROS2 timer with a period of measurement_period_. @@ -71,10 +85,27 @@ class PeriodicMeasurementNode : public Collector, public rclcpp::Node */ bool setupStop() override; - std::string publishing_topic_; - std::chrono::milliseconds measurement_period_; + // todo implement on publish timer callback, check if we need to clear the window + // todo this is part of the publishing interface + + /** + * Topic used for publishing + */ + const std::string publishing_topic_; + /** + * The period used to take a single measurement + */ + const std::chrono::milliseconds measurement_period_; + /** + * The period used to publish measurement data + */ + const std::chrono::milliseconds publish_period_; + /** + * If true, then measurements are cleared after publishing data + */ + const bool clear_measurements_on_publish_; rclcpp::TimerBase::SharedPtr measurement_timer_; + rclcpp::TimerBase::SharedPtr publish_timer_; }; - #endif // SYSTEM_METRICS_COLLECTOR__PERIODIC_MEASUREMENT_NODE_HPP_ diff --git a/system_metrics_collector/src/system_metrics_collector/proc_cpu_data.cpp b/system_metrics_collector/src/system_metrics_collector/proc_cpu_data.cpp new file mode 100644 index 00000000..8a2fc3e6 --- /dev/null +++ b/system_metrics_collector/src/system_metrics_collector/proc_cpu_data.cpp @@ -0,0 +1,56 @@ +// 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 +#include + +#include "proc_cpu_data.hpp" + +/*static*/ constexpr const char ProcCpuData::EMPTY_LABEL[]; + +size_t ProcCpuData::getIdleTime() const +{ + return times[static_cast(ProcCpuStates::kIdle)] + + times[static_cast(ProcCpuStates::kIOWait)]; +} + +size_t ProcCpuData::getActiveTime() const +{ + return times[static_cast(ProcCpuStates::kUser)] + + times[static_cast(ProcCpuStates::kNice)] + + times[static_cast(ProcCpuStates::kSystem)] + + times[static_cast(ProcCpuStates::kIrq)] + + times[static_cast(ProcCpuStates::kSoftIrq)] + + times[static_cast(ProcCpuStates::kSteal)]; +} + +std::string ProcCpuData::toString() const +{ + std::stringstream ss; + ss << "cpu_label=" << cpu_label << + ", user=" << times[static_cast(ProcCpuStates::kUser)] << + ", nice=" << times[static_cast(ProcCpuStates::kNice)] << + ", system=" << times[static_cast(ProcCpuStates::kSystem)] << + ", idle=" << times[static_cast(ProcCpuStates::kIdle)] << + ", iOWait=" << times[static_cast(ProcCpuStates::kIOWait)] << + ", irq=" << times[static_cast(ProcCpuStates::kIrq)] << + ", softIrq=" << times[static_cast(ProcCpuStates::kSoftIrq)] << + ", steal=" << times[static_cast(ProcCpuStates::kSteal)]; + return ss.str(); +} + +bool ProcCpuData::isMeasurementEmpty() const +{ + return cpu_label == ProcCpuData::EMPTY_LABEL; +} diff --git a/system_metrics_collector/src/system_metrics_collector/proc_cpu_data.hpp b/system_metrics_collector/src/system_metrics_collector/proc_cpu_data.hpp new file mode 100644 index 00000000..6c5bf269 --- /dev/null +++ b/system_metrics_collector/src/system_metrics_collector/proc_cpu_data.hpp @@ -0,0 +1,89 @@ +// 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__PROC_CPU_DATA_HPP_ +#define SYSTEM_METRICS_COLLECTOR__PROC_CPU_DATA_HPP_ + +#include +#include +#include + +/** + * Enum representing each item in a /proc/stat cpu line + */ +enum class ProcCpuStates +{ + kUser = 0, + kNice, + kSystem, + kIdle, + kIOWait, + kIrq, + kSoftIrq, + kSteal, + kNumProcCpuStates +}; + +/** + * Struct containing data parsed from a /proc/stat cpu line + */ +class ProcCpuData +{ +public: + ProcCpuData() = default; + virtual ~ProcCpuData() = default; + + static constexpr const char EMPTY_LABEL[] = "empty"; + + /** + * Return the idle time + * @return the idle time for this data set + */ + size_t getIdleTime() const; + + /** + * Return the active time + * @return the active time for this data set + */ + size_t getActiveTime() const; + + /** + * Return a pretty printed string of the ProcCpuData struct. + * + * @param data the struct to print + * @return a formatted string of the input struct + */ + std::string toString() const; + + /** + * Return true if the struct is not populated with any useful data. + * This indicates a parsing error. + * + * @return true if empty (no valid data), false otherwise. + */ + bool isMeasurementEmpty() const; + + /** + * The cpu label of the line parsed + */ + std::string cpu_label{EMPTY_LABEL}; + + /** + * Array contained the parsed CPU data, where each index + * of ProcCpuStates contains its labeled data. + */ + std::array(ProcCpuStates::kNumProcCpuStates)> times{}; +}; + +#endif // SYSTEM_METRICS_COLLECTOR__PROC_CPU_DATA_HPP_ diff --git a/system_metrics_collector/test/moving_average_statistics/test_moving_average_statistics.cpp b/system_metrics_collector/test/moving_average_statistics/test_moving_average_statistics.cpp index 81f5b89b..69fed385 100644 --- a/system_metrics_collector/test/moving_average_statistics/test_moving_average_statistics.cpp +++ b/system_metrics_collector/test/moving_average_statistics/test_moving_average_statistics.cpp @@ -21,14 +21,17 @@ #include "../../src/moving_average_statistics/moving_average.hpp" +namespace +{ // Useful testing constants -static constexpr const uint64_t EXPECTED_SIZE = 9; -static constexpr const std::array TEST_DATA{-3.5, -2.1, -1.1, 0.0, 4.7, 5.0, +constexpr const uint64_t EXPECTED_SIZE = 9; +constexpr const std::array TEST_DATA{-3.5, -2.1, -1.1, 0.0, 4.7, 5.0, 6.7, 9.9, 11.0}; -static constexpr const double EXPECTED_AVG = 3.4; -static constexpr const double EXPECTED_MIN = -3.5; -static constexpr const double EXPECTED_MAX = 11.0; -static constexpr const double EXPECTED_STD = 4.997999599839919955173; +constexpr const double EXPECTED_AVG = 3.4; +constexpr const double EXPECTED_MIN = -3.5; +constexpr const double EXPECTED_MAX = 11.0; +constexpr const double EXPECTED_STD = 4.997999599839919955173; +} // namespace /** * Test fixture @@ -57,6 +60,13 @@ class MovingAverageStatisticsTestFixture : public ::testing::Test int expected_count = 0; }; +TEST_F(MovingAverageStatisticsTestFixture, test_add_nan_ignore) { + auto stats1 = statisticsDataToString(moving_average_statistics->getStatistics()); + moving_average_statistics->addMeasurement(std::nan("")); + auto stats2 = statisticsDataToString(moving_average_statistics->getStatistics()); + ASSERT_EQ(stats1, stats2); +} + TEST_F(MovingAverageStatisticsTestFixture, sanity) { ASSERT_NE(moving_average_statistics, nullptr); } diff --git a/system_metrics_collector/test/system_metrics_collector/test_linux_cpu_measurement.cpp b/system_metrics_collector/test/system_metrics_collector/test_linux_cpu_measurement.cpp new file mode 100644 index 00000000..e6c8c3b5 --- /dev/null +++ b/system_metrics_collector/test/system_metrics_collector/test_linux_cpu_measurement.cpp @@ -0,0 +1,146 @@ +// 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 + +#include +#include +#include +#include +#include + +#include "../../src/system_metrics_collector/linux_cpu_measurement_node.hpp" +#include "../../src/system_metrics_collector/proc_cpu_data.hpp" + +namespace +{ +const char proc_sample_1[] = + "cpu 22451232 118653 7348045 934943300 5378119 0 419114 0 0 0\n"; +const char proc_sample_2[] = + "cpu 22451360 118653 7348080 934949227 5378120 0 419117 0 0 0\n"; +constexpr const std::chrono::milliseconds TEST_PERIOD = + std::chrono::milliseconds(50); +constexpr const double CPU_ACTIVE_PERCENTAGE = 2.8002699055330633; +} // namespace + +class TestLinuxCpuMeasurementNode : public LinuxCpuMeasurementNode +{ +public: + TestLinuxCpuMeasurementNode( + const std::string & name, + const std::chrono::milliseconds measurement_period, + const std::string & publishing_topic) + : LinuxCpuMeasurementNode(name, measurement_period, publishing_topic, + PeriodicMeasurementNode::DEFAULT_PUBLISH_WINDOW) + {} + virtual ~TestLinuxCpuMeasurementNode() = default; + + double periodicMeasurement() override + { + LinuxCpuMeasurementNode::periodicMeasurement(); + } + +private: + ProcCpuData makeSingleMeasurement() override + { + first = !first; + + if (first) { + return processLine(proc_sample_1); + } else { + return processLine(proc_sample_2); + } + } + + bool first{false}; +}; + +class LinuxCpuMeasurementTestFixture : public ::testing::Test +{ +public: + void SetUp() override + { + rclcpp::init(0, nullptr); + + test_measure_linux_cpu = std::make_shared("test_periodic_node", + TEST_PERIOD, "test_topic"); + + ASSERT_FALSE(test_measure_linux_cpu->isStarted()); + + const StatisticData data = test_measure_linux_cpu->getStatisticsResults(); + ASSERT_TRUE(std::isnan(data.average)); + ASSERT_TRUE(std::isnan(data.min)); + ASSERT_TRUE(std::isnan(data.max)); + ASSERT_TRUE(std::isnan(data.standard_deviation)); + ASSERT_EQ(0, data.sample_count); + } + + void TearDown() override + { + test_measure_linux_cpu->stop(); + test_measure_linux_cpu.reset(); + rclcpp::shutdown(); + } + +protected: + std::shared_ptr test_measure_linux_cpu; +}; + +TEST_F(LinuxCpuMeasurementTestFixture, testManualMeasurement) { + // first measurement caches + double cpu_active_percentage = test_measure_linux_cpu->periodicMeasurement(); + ASSERT_TRUE(std::isnan(cpu_active_percentage)); + // second measurement compares current and cached + cpu_active_percentage = test_measure_linux_cpu->periodicMeasurement(); + ASSERT_DOUBLE_EQ(CPU_ACTIVE_PERCENTAGE, cpu_active_percentage); +} + +TEST(LinuxCpuMeasurementTest, testParseProcLine) +{ + auto parsed_data = processLine(proc_sample_1); + + ASSERT_EQ("cpu", parsed_data.cpu_label); + ASSERT_EQ(22451232, parsed_data.times[0]); + ASSERT_EQ(118653, parsed_data.times[1]); + ASSERT_EQ(7348045, parsed_data.times[2]); + ASSERT_EQ(934943300, parsed_data.times[3]); + ASSERT_EQ(5378119, parsed_data.times[4]); + ASSERT_EQ(0, parsed_data.times[5]); + ASSERT_EQ(419114, parsed_data.times[6]); + ASSERT_EQ(0, parsed_data.times[7]); + + ASSERT_EQ( + "cpu_label=cpu, user=22451232, nice=118653, system=7348045, idle=934943300," + " iOWait=5378119, irq=0, softIrq=419114, steal=0", + parsed_data.toString()); +} + +TEST(LinuxCpuMeasurementTest, testCalculateCpuActivePercentage) +{ + auto parsed_data1 = processLine(proc_sample_1); + auto parsed_data2 = processLine(proc_sample_2); + + auto p = computeCpuActivePercentage(parsed_data1, parsed_data2); + ASSERT_DOUBLE_EQ(CPU_ACTIVE_PERCENTAGE, p); +} + +TEST(LinuxCpuMeasurementTest, testEmptyProcCpuData) +{ + ProcCpuData empty; + ASSERT_EQ(ProcCpuData::EMPTY_LABEL, empty.cpu_label); + + for (int i = 0; i < static_cast(ProcCpuStates::kNumProcCpuStates); i++) { + ASSERT_EQ(0, empty.times[i]); + } +} diff --git a/system_metrics_collector/test/system_metrics_collector/test_periodic_measurement_node.cpp b/system_metrics_collector/test/system_metrics_collector/test_periodic_measurement_node.cpp index 25562f0b..d8c20b12 100644 --- a/system_metrics_collector/test/system_metrics_collector/test_periodic_measurement_node.cpp +++ b/system_metrics_collector/test/system_metrics_collector/test_periodic_measurement_node.cpp @@ -15,6 +15,7 @@ #include +#include #include #include #include @@ -27,11 +28,11 @@ namespace { -static constexpr const std::chrono::milliseconds TEST_LENGTH = +constexpr const std::chrono::milliseconds TEST_LENGTH = std::chrono::milliseconds(250); -static constexpr const std::chrono::milliseconds TEST_PERIOD = +constexpr const std::chrono::milliseconds TEST_PERIOD = std::chrono::milliseconds(50); -} +} // namespace /** * Simple extension to test basic functionality @@ -42,19 +43,25 @@ class TestPeriodicMeasurementNode : public PeriodicMeasurementNode TestPeriodicMeasurementNode( const std::string & name, const std::chrono::milliseconds measurement_period, - const std::string & publishing_topic) - : PeriodicMeasurementNode(name, measurement_period, publishing_topic) + const std::string & publishing_topic, + const std::chrono::milliseconds publish_period = + PeriodicMeasurementNode::DEFAULT_PUBLISH_WINDOW) + : PeriodicMeasurementNode(name, measurement_period, publishing_topic, publish_period) {} virtual ~TestPeriodicMeasurementNode() = default; - // made public to manually test - void periodicMeasurement() override +private: + /** + * Test measurement for the fixture. + * + * @return + */ + double periodicMeasurement() override { sum += 1; - acceptData(static_cast(sum.load())); + return static_cast(sum.load()); } -private: std::atomic sum{0}; }; @@ -66,8 +73,7 @@ class PeriodicMeasurementTestFixure : public ::testing::Test public: void SetUp() override { - const char * const argv = "d"; - rclcpp::init(1, &argv); + rclcpp::init(0, nullptr); test_periodic_measurer = std::make_shared("test_periodic_node", TEST_PERIOD, "test_topic"); @@ -95,24 +101,13 @@ class PeriodicMeasurementTestFixure : public ::testing::Test TEST_F(PeriodicMeasurementTestFixure, sanity) { ASSERT_NE(test_periodic_measurer, nullptr); - ASSERT_EQ("name=test_periodic_node, measurement_period=50ms, publishing_topic=test_topic," - " started=false, avg=nan, min=nan, max=nan, std_dev=nan, count=0", + ASSERT_EQ("name=test_periodic_node, measurement_period=50ms," + " publishing_topic=test_topic, publish_period=None," + " clear_measurements_on_publish_=1, started=false," + " avg=nan, min=nan, max=nan, std_dev=nan, count=0", test_periodic_measurer->getStatusString()); } -TEST_F(PeriodicMeasurementTestFixure, test_measurement_manually) { - ASSERT_NE(test_periodic_measurer, nullptr); - - test_periodic_measurer->periodicMeasurement(); - - StatisticData data = test_periodic_measurer->getStatisticsResults(); - ASSERT_FALSE(std::isnan(data.average)); - ASSERT_FALSE(std::isnan(data.min)); - ASSERT_FALSE(std::isnan(data.max)); - ASSERT_FALSE(std::isnan(data.standard_deviation)); - ASSERT_EQ(1, data.sample_count); -} - TEST_F(PeriodicMeasurementTestFixure, test_start_and_stop) { ASSERT_TRUE(true); ASSERT_NE(test_periodic_measurer, nullptr);