From bf375a568bb37245e579ebdb68ba459cbc76a77d Mon Sep 17 00:00:00 2001 From: Emerson Knapp <537409+emersonknapp@users.noreply.github.com> Date: Tue, 1 Dec 2020 21:33:39 -0800 Subject: [PATCH] Bump action-ros-ci to 0.1.0 (#186) * Upgrade CI actions to latest version to fix build * upgrade tests to match foxy api * rewrite e2e tests as launch tests to remove process management logic Signed-off-by: Emerson Knapp --- .github/workflows/e2e_test.yml | 20 -- .github/workflows/lint.yml | 1 - .github/workflows/test.yml | 10 +- .gitignore | 1 + system_metrics_collector/CMakeLists.txt | 11 + system_metrics_collector/package.xml | 10 +- .../examples/dummy_talker.launch.py | 2 +- ...and_memory_configuration_example.launch.py | 4 +- .../talker_listener_example.launch.py | 10 +- .../examples/topic_statistics_node.launch.py | 4 +- .../dummy_talker.cpp | 2 +- .../test/base_metrics_test.py | 108 +++++++++ .../test/test_system_metrics_e2e.py | 64 ++++++ .../test/test_topic_statistics_e2e.py | 58 +++++ test/run_e2e_test.sh | 16 -- test/statistics_listener.py | 97 -------- test/system_metrics_e2e_test.py | 99 --------- test/test_helpers.py | 208 ------------------ test/topic_statistics_e2e_test.py | 103 --------- 19 files changed, 263 insertions(+), 565 deletions(-) delete mode 100644 .github/workflows/e2e_test.yml create mode 100644 .gitignore create mode 100644 system_metrics_collector/test/base_metrics_test.py create mode 100644 system_metrics_collector/test/test_system_metrics_e2e.py create mode 100644 system_metrics_collector/test/test_topic_statistics_e2e.py delete mode 100755 test/run_e2e_test.sh delete mode 100644 test/statistics_listener.py delete mode 100644 test/system_metrics_e2e_test.py delete mode 100644 test/test_helpers.py delete mode 100644 test/topic_statistics_e2e_test.py diff --git a/.github/workflows/e2e_test.yml b/.github/workflows/e2e_test.yml deleted file mode 100644 index f7f41a97..00000000 --- a/.github/workflows/e2e_test.yml +++ /dev/null @@ -1,20 +0,0 @@ -name: End-to-end Testing (Nightly) -on: - pull_request: - # Running on pull requests to catch breaking changes as early as possible. - # Waiting for this test to pass is recommended, but contributors can use their discretion whether they want to or not. - schedule: - # Run every morning Pacific Time. Random hour and minute to avoid creating excess traffic during popular times. - - cron: '17 17 * * *' - -jobs: - build_and_test: - runs-on: ubuntu-18.04 - steps: - - uses: actions/checkout@v2 - - uses: ros-tooling/setup-ros@0.0.26 - - uses: ros-tooling/action-ros-ci@0.0.17 - with: - package-name: system_metrics_collector - - name: Run end-to-end test - run: ./test/run_e2e_test.sh diff --git a/.github/workflows/lint.yml b/.github/workflows/lint.yml index b825a4c4..a862f89f 100644 --- a/.github/workflows/lint.yml +++ b/.github/workflows/lint.yml @@ -12,7 +12,6 @@ jobs: matrix: linter: [copyright, cppcheck, cpplint, flake8, pep257, uncrustify, xmllint] steps: - - run: sudo chown -R rosbuild:rosbuild "$HOME" . - uses: actions/checkout@v2 - uses: ros-tooling/action-ros-lint@0.0.6 with: diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 3a3b1f38..734fec3d 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -15,13 +15,12 @@ jobs: container: image: rostooling/setup-ros-docker:ubuntu-focal-latest steps: - # TODO(setup-ros-docker#7): calling chown is necessary for now - - run: sudo chown -R rosbuild:rosbuild "$HOME" . - - uses: ros-tooling/action-ros-ci@0.0.17 + - uses: ros-tooling/action-ros-ci@0.1.0 with: package-name: system_metrics_collector colcon-mixin-name: coverage-gcc colcon-mixin-repository: https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml + target-ros2-distro: foxy - uses: codecov/codecov-action@v1.0.14 with: token: ${{ secrets.CODECOV_TOKEN }} @@ -40,13 +39,12 @@ jobs: container: image: rostooling/setup-ros-docker:ubuntu-focal-latest steps: - # TODO(setup-ros-docker#7): calling chown is necessary for now - - run: sudo chown -R rosbuild:rosbuild "$HOME" . - - uses: ros-tooling/action-ros-ci@0.0.17 + - uses: ros-tooling/action-ros-ci@0.1.0 with: colcon-mixin-name: asan colcon-mixin-repository: https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml package-name: system_metrics_collector + target-ros2-distro: foxy - uses: actions/upload-artifact@v1 with: name: colcon-logs-ubuntu-asan diff --git a/.gitignore b/.gitignore new file mode 100644 index 00000000..c18dd8d8 --- /dev/null +++ b/.gitignore @@ -0,0 +1 @@ +__pycache__/ diff --git a/system_metrics_collector/CMakeLists.txt b/system_metrics_collector/CMakeLists.txt index 0f75e62e..7b531e0e 100644 --- a/system_metrics_collector/CMakeLists.txt +++ b/system_metrics_collector/CMakeLists.txt @@ -99,6 +99,7 @@ ament_target_dependencies(topic_statistics_node) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) find_package(ament_cmake_gtest REQUIRED) + find_package(launch_testing_ament_cmake REQUIRED) find_package(class_loader REQUIRED) find_package(lifecycle_msgs REQUIRED) @@ -149,6 +150,16 @@ if(BUILD_TESTING) ament_target_dependencies(test_subscriber_topic_statistics rcl rclcpp) rosidl_target_interfaces(test_subscriber_topic_statistics system_metrics_collector_test_msgs "rosidl_typesupport_cpp") + + add_launch_test( + test/test_system_metrics_e2e.py + TARGET test_system_metrics_e2e + TIMEOUT 60) + + add_launch_test( + test/test_topic_statistics_e2e.py + TARGET test_topic_statistics_e2e + TIMEOUT 60) endif() # To enable use of dummy_message.hpp in executables diff --git a/system_metrics_collector/package.xml b/system_metrics_collector/package.xml index c728284f..ed27acbb 100644 --- a/system_metrics_collector/package.xml +++ b/system_metrics_collector/package.xml @@ -24,19 +24,19 @@ demo_nodes_cpp + rosidl_default_runtime + std_msgs ament_cmake_gtest + launch_testing_ament_cmake ament_lint_auto ament_lint_common class_loader + launch_testing lifecycle_msgs - rosidl_default_runtime - std_msgs - - python3-retrying rclpy - ros2launch + ros2node ros2lifecycle ros2topic diff --git a/system_metrics_collector/share/system_metrics_collector/examples/dummy_talker.launch.py b/system_metrics_collector/share/system_metrics_collector/examples/dummy_talker.launch.py index 841672fc..c533cdd0 100644 --- a/system_metrics_collector/share/system_metrics_collector/examples/dummy_talker.launch.py +++ b/system_metrics_collector/share/system_metrics_collector/examples/dummy_talker.launch.py @@ -22,6 +22,6 @@ def generate_launch_description(): return LaunchDescription([ launch_ros.actions.Node( package='system_metrics_collector', - node_executable='dummy_talker', + executable='dummy_talker', output='screen'), ]) diff --git a/system_metrics_collector/share/system_metrics_collector/examples/system_cpu_and_memory_configuration_example.launch.py b/system_metrics_collector/share/system_metrics_collector/examples/system_cpu_and_memory_configuration_example.launch.py index 96beed21..46d56b1f 100644 --- a/system_metrics_collector/share/system_metrics_collector/examples/system_cpu_and_memory_configuration_example.launch.py +++ b/system_metrics_collector/share/system_metrics_collector/examples/system_cpu_and_memory_configuration_example.launch.py @@ -76,7 +76,7 @@ def generate_launch_description(): ld.add_action( Node( package='system_metrics_collector', - node_executable='linux_cpu_collector', + executable='linux_cpu_collector', name=LaunchConfiguration(CPU_NODE_NAME), parameters=node_parameters, remappings=[('system_metrics', LaunchConfiguration(PUBLISH_TOPIC))], @@ -84,7 +84,7 @@ def generate_launch_description(): ld.add_action( Node( package='system_metrics_collector', - node_executable='linux_memory_collector', + executable='linux_memory_collector', name=LaunchConfiguration(MEMORY_NODE_NAME), parameters=node_parameters, remappings=[('system_metrics', LaunchConfiguration(PUBLISH_TOPIC))], diff --git a/system_metrics_collector/share/system_metrics_collector/examples/talker_listener_example.launch.py b/system_metrics_collector/share/system_metrics_collector/examples/talker_listener_example.launch.py index 302e9ff0..6f6b8959 100644 --- a/system_metrics_collector/share/system_metrics_collector/examples/talker_listener_example.launch.py +++ b/system_metrics_collector/share/system_metrics_collector/examples/talker_listener_example.launch.py @@ -53,18 +53,20 @@ def generate_launch_description(): # Collect, aggregate, and measure system CPU % used system_cpu_node = LifecycleNode( + executable='linux_cpu_collector', package='system_metrics_collector', name='linux_system_cpu_collector', - node_executable='linux_cpu_collector', + namespace='', output='screen', parameters=node_parameters, ) # Collect, aggregate, and measure system memory % used system_memory_node = LifecycleNode( + executable='linux_memory_collector', package='system_metrics_collector', name='linux_system_memory_collector', - node_executable='linux_memory_collector', + namespace='', output='screen', parameters=node_parameters, ) @@ -74,7 +76,7 @@ def generate_launch_description(): name='listener_container', namespace='', package='rclcpp_components', - node_executable='component_container', + executable='component_container', composable_node_descriptions=[ ComposableNode( package='demo_nodes_cpp', @@ -101,7 +103,7 @@ def generate_launch_description(): name='talker_container', namespace='', package='rclcpp_components', - node_executable='component_container', + executable='component_container', composable_node_descriptions=[ ComposableNode( package='demo_nodes_cpp', diff --git a/system_metrics_collector/share/system_metrics_collector/examples/topic_statistics_node.launch.py b/system_metrics_collector/share/system_metrics_collector/examples/topic_statistics_node.launch.py index c652e9d9..ffe38ede 100644 --- a/system_metrics_collector/share/system_metrics_collector/examples/topic_statistics_node.launch.py +++ b/system_metrics_collector/share/system_metrics_collector/examples/topic_statistics_node.launch.py @@ -33,7 +33,7 @@ # Default argument values DEFAULT_COLLECTOR_NODE_NAME = 'topic_stats_collector' DEFAULT_MONITORED_TOPIC_NAME = ['dummy_topic'] -DEFAULT_PUBLISH_PERIOD_IN_MS = '30000' +DEFAULT_PUBLISH_PERIOD_IN_MS = '1000' DEFAULT_PUBLISH_TOPIC = 'system_metrics' @@ -68,7 +68,7 @@ def generate_launch_description(): ld.add_action( Node( package='system_metrics_collector', - node_executable='topic_statistics_node', + executable='topic_statistics_node', name=LaunchConfiguration(COLLECTOR_NODE_NAME), parameters=node_parameters, remappings=[('system_metrics', LaunchConfiguration(PUBLISH_TOPIC_NAME))], diff --git a/system_metrics_collector/src/topic_statistics_collector/dummy_talker.cpp b/system_metrics_collector/src/topic_statistics_collector/dummy_talker.cpp index 5576dbf9..16813428 100644 --- a/system_metrics_collector/src/topic_statistics_collector/dummy_talker.cpp +++ b/system_metrics_collector/src/topic_statistics_collector/dummy_talker.cpp @@ -49,7 +49,7 @@ class DummyTalker : public rclcpp::Node publisher_ = this->create_publisher( "dummy_data", 10 /* QoS history_depth */); - timer_ = this->create_wall_timer(1s, publish_lambda); + timer_ = this->create_wall_timer(100ms, publish_lambda); } private: diff --git a/system_metrics_collector/test/base_metrics_test.py b/system_metrics_collector/test/base_metrics_test.py new file mode 100644 index 00000000..7a1ebe16 --- /dev/null +++ b/system_metrics_collector/test/base_metrics_test.py @@ -0,0 +1,108 @@ +# Copyright 2020 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. +from collections import Counter +from pathlib import Path +from threading import Lock +from typing import Iterable +from typing import Set +import unittest + +from ament_index_python.packages import get_package_share_directory +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from lifecycle_msgs.msg import State +import rclpy +from rclpy.task import Future +import retrying +import ros2lifecycle.api +import ros2node.api +from statistics_msgs.msg import MetricsMessage + + +def include_python_launch_file(package: str, launchfile: str) -> IncludeLaunchDescription: + package_dir = Path(get_package_share_directory(package)) + launchfile_path = str(package_dir / launchfile) + return IncludeLaunchDescription(PythonLaunchDescriptionSource(launchfile_path)) + + +class TestMetricsBase(unittest.TestCase): + + @classmethod + def setUpClass(cls): + rclpy.init() + cls.node = rclpy.create_node('test_system_metrics_nodes') + + @classmethod + def tearDownClass(cls): + cls.node.destroy_node() + rclpy.shutdown() + + @retrying.retry( + stop_max_attempt_number=10, + wait_exponential_multiplier=1000, + wait_exponential_max=10000) + def _test_nodes_exist(self, expected_nodes: Set[str]): + node_names = ros2node.api.get_node_names(node=self.node) + full_names = {n.full_name for n in node_names} + self.assertTrue(expected_nodes.issubset(full_names)) + + @retrying.retry( + stop_max_attempt_number=10, + wait_exponential_multiplier=1000, + wait_exponential_max=10000) + def _test_lifecycle_nodes_exist(self, expected_nodes: Set[str]) -> None: + node_names = ros2lifecycle.api.get_node_names(node=self.node) + full_names = {n.full_name for n in node_names} + self.assertTrue(expected_nodes.issubset(full_names)) + + def _test_lifecycle_nodes_active(self, expected_lifecycle_nodes: Iterable[str]) -> None: + states = ros2lifecycle.api.call_get_states( + node=self.node, + node_names=expected_lifecycle_nodes) + self.assertTrue(all(s.id == State.PRIMARY_STATE_ACTIVE for s in states.values())) + + def _test_topic_exists(self, topic_name: str) -> None: + topics_and_types = self.node.get_topic_names_and_types() + found = False + for name, types in topics_and_types: + if name == topic_name: + found = True + assert all(t == 'statistics_msgs/msg/MetricsMessage' for t in types) + self.assertTrue(found, f'No topic named {topic_name}') + + def _test_statistic_publication(self, topic_name: str, expected_nodes: Iterable[str]): + future = Future() + message_counter = Counter() + lock = Lock() + # arbitrary choice, just tells if it's working for a little while + expected_messages_per_node = 3 + # we are receiving stats every 10 seconds, so this should pass in 30s + timeout_sec = 180 + + def message_callback(msg): + node_name = '/' + msg.measurement_source_name + with lock: + message_counter[node_name] += 1 + if all( + message_counter[node] >= expected_messages_per_node + for node in expected_nodes + ): + print('Successfully received all expected messages') + future.set_result(True) + + sub = self.node.create_subscription( + MetricsMessage, topic_name, message_callback, qos_profile=10) + rclpy.spin_until_future_complete(self.node, future, timeout_sec=timeout_sec) + self.assertTrue(future.done(), f'Timed out, received message count: {message_counter}') + self.node.destroy_subscription(sub) diff --git a/system_metrics_collector/test/test_system_metrics_e2e.py b/system_metrics_collector/test/test_system_metrics_e2e.py new file mode 100644 index 00000000..6c08db6e --- /dev/null +++ b/system_metrics_collector/test/test_system_metrics_e2e.py @@ -0,0 +1,64 @@ +# Copyright 2020 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. +import os +import sys + +from launch import LaunchDescription +import launch_testing +import pytest + +# Allow relative import even though we are not in a real module +sys.path.insert(0, os.path.dirname(os.path.abspath(__file__))) +from base_metrics_test import include_python_launch_file, TestMetricsBase # noqa: E402, I100 + + +EXPECTED_LIFECYCLE_NODES = { + '/linux_system_cpu_collector', + '/linux_system_memory_collector', + '/listener_process_cpu_node', + '/listener_process_memory_node', + '/talker_process_cpu_node', + '/talker_process_memory_node', +} +EXPECTED_REGULAR_NODES = { + '/listener', + '/talker', +} + + +@pytest.mark.launch_test +def generate_test_description(): + return LaunchDescription([ + include_python_launch_file( + 'system_metrics_collector', 'examples/talker_listener_example.launch.py'), + launch_testing.actions.ReadyToTest(), + ]) + + +class TestSystemMetricsLaunch(TestMetricsBase): + + def test_nodes_exist(self): + return self._test_nodes_exist(EXPECTED_LIFECYCLE_NODES.union(EXPECTED_REGULAR_NODES)) + + def test_lifecycle_nodes_exist(self): + return self._test_lifecycle_nodes_exist(EXPECTED_LIFECYCLE_NODES) + + def test_lifecycle_nodes_active(self): + return self._test_lifecycle_nodes_active(EXPECTED_LIFECYCLE_NODES) + + def test_topics_exist(self): + return self._test_topic_exists('/system_metrics') + + def test_statistic_publication(self): + return self._test_statistic_publication('/system_metrics', EXPECTED_LIFECYCLE_NODES) diff --git a/system_metrics_collector/test/test_topic_statistics_e2e.py b/system_metrics_collector/test/test_topic_statistics_e2e.py new file mode 100644 index 00000000..5a0b3b25 --- /dev/null +++ b/system_metrics_collector/test/test_topic_statistics_e2e.py @@ -0,0 +1,58 @@ +# Copyright 2020 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. +import os +import sys + +from launch import LaunchDescription +import launch_testing +import pytest + +# Allow relative import even though we are not in a real module +sys.path.insert(0, os.path.dirname(os.path.abspath(__file__))) +from base_metrics_test import include_python_launch_file, TestMetricsBase # noqa: E402, I100 + + +EXPECTED_LIFECYCLE_NODES = {'/topic_stats_collector'} +EXPECTED_REGULAR_NODES = {'/dummy_talker'} + + +@pytest.mark.launch_test +def generate_test_description(): + return LaunchDescription([ + include_python_launch_file( + 'system_metrics_collector', + 'examples/dummy_talker.launch.py'), + include_python_launch_file( + 'system_metrics_collector', + 'examples/topic_statistics_node.launch.py'), + launch_testing.actions.ReadyToTest(), + ]) + + +class TestTopicStatisticsLaunch(TestMetricsBase): + + def test_nodes_exist(self): + return self._test_nodes_exist(EXPECTED_LIFECYCLE_NODES.union(EXPECTED_REGULAR_NODES)) + + def test_lifecycle_nodes_exist(self): + return self._test_lifecycle_nodes_exist(EXPECTED_LIFECYCLE_NODES) + + def test_lifecycle_nodes_active(self): + return self._test_lifecycle_nodes_active(EXPECTED_LIFECYCLE_NODES) + + def test_topics_exist(self): + return self._test_topic_exists('/system_metrics') + + def test_statistic_publication(self): + return self._test_statistic_publication('/system_metrics', EXPECTED_LIFECYCLE_NODES) diff --git a/test/run_e2e_test.sh b/test/run_e2e_test.sh deleted file mode 100755 index c29c83b0..00000000 --- a/test/run_e2e_test.sh +++ /dev/null @@ -1,16 +0,0 @@ -#!/bin/bash -# This script sources the built ROS2 workspace and executes the python end to end tests -# for the system_metrics_collector package. -# -# The goal of this script is to independently run end to end tests, as a canary, -# on the master branch and ultimately released APT packages. - -ROS_WS_DIR=ros_ws/install -TEST_DIR=ros_ws/src/system_metrics_collector/test - -# source the ROS2 installation -source "$ROS_WS_DIR/setup.bash" && source "$ROS_WS_DIR/local_setup.bash" - -# run the e2e tests -python3 "$TEST_DIR/system_metrics_e2e_test.py" -python3 "$TEST_DIR/topic_statistics_e2e_test.py" diff --git a/test/statistics_listener.py b/test/statistics_listener.py deleted file mode 100644 index bdc2a6f5..00000000 --- a/test/statistics_listener.py +++ /dev/null @@ -1,97 +0,0 @@ -# Copyright 2020 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. - -from collections import Counter -import logging -from threading import Lock -from typing import List - -from statistics_msgs.msg import MetricsMessage - -from rclpy.node import Node -from rclpy.task import Future - -# QoS history_depth to use for listener node -QOS_DEPTH = 10 - -""" -Helper class for running system meterics end-to-end tests. - -This class is a Node that subscribes to the topic to which MetricsMessages are published -and checks that all expected messages are received. -""" - - -class StatisticsListener(Node): - """Listen for MetricsMessages published on the /system_metrics topic.""" - - def __init__(self, future: Future, expected_lifecycle_nodes: List, - expected_number_of_messages_to_receive: int, subscription_topic: str): - super().__init__('statisticsListener') - - self.sub = self.create_subscription(MetricsMessage, - subscription_topic, - self.listener_callback, - QOS_DEPTH) - # set up logging - self._logger = logging.getLogger() - - # used to stop spinning upon success - self._future = future - # key is node name, value is expected number of messages to receive - self.lifecycle_nodes_message_counter = Counter() - for node in expected_lifecycle_nodes: - self.lifecycle_nodes_message_counter[node] = expected_number_of_messages_to_receive - self._lock = Lock() - - def listener_callback(self, msg) -> None: - """ - Handle published MetricsMessages. - - Checks each received message measurement_source_name against a dict of - expected_lifecycle_nodes, decrements each entry for its message received, - and marks the future field as done if all sources have been observed. - :param msg: received message - :return: None - """ - node_name = '/' + msg.measurement_source_name - - if node_name in self.lifecycle_nodes_message_counter: - self._logger.debug('received message from %s', node_name) - received_all_msgs_for_node = False - with self._lock: - self.lifecycle_nodes_message_counter[node_name] -= 1 - if self.lifecycle_nodes_message_counter[node_name] == 0: - received_all_msgs_for_node = True - del self.lifecycle_nodes_message_counter[node_name] - - if received_all_msgs_for_node: - # don't lock on a logging statement - self._logger.debug('received all messages from %s', node_name) - - if self.received_all_expected_messages(): - self._logger.debug('received all expected messages') - self._future.set_result(True) - else: - self._logger.debug( - 'messages left to receive %s', self.lifecycle_nodes_message_counter) - - def received_all_expected_messages(self) -> bool: - """ - Check and return if all expected messages have been received. - - :return: true if all expected messages have been received, specifically - if the node's received count is not greater than 0, false otherwise. - """ - return (len(self.lifecycle_nodes_message_counter) == 0) diff --git a/test/system_metrics_e2e_test.py b/test/system_metrics_e2e_test.py deleted file mode 100644 index 6328fdb9..00000000 --- a/test/system_metrics_e2e_test.py +++ /dev/null @@ -1,99 +0,0 @@ -# Copyright 2020 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. - -""" -End to end tests for the system_metrics_collector ROS2 package. - -These tests launch the talker_listener_example and use ROS2 to inspect if the -expected nodes are active and publishing data. To run these tests ensure that -ROS2 is installed, with the system_metrics_collector package the relevant -setup.bash has been sourced. -""" - -import logging -import signal -import subprocess -import sys - -import rclpy - -import test_helpers - - -# Expected outputs -EXPECTED_LIFECYCLE_NODES = frozenset(['/linux_system_cpu_collector', - '/linux_system_memory_collector', - '/listener_process_cpu_node', - '/listener_process_memory_node', - '/talker_process_cpu_node', - '/talker_process_memory_node']) -EXPECTED_REGULAR_NODES = frozenset(['/listener', '/talker']) -EXPECTED_LIFECYCLE_STATE = 'active [3]' -EXPECTED_TOPIC = '/system_metrics' -# Commands to execute -LAUNCH_COMMAND = 'ros2 launch system_metrics_collector talker_listener_example.launch.py' -# Test constants -TIMEOUT_SECONDS = 30 -RETURN_VALUE_FAILURE = 1 -RETURN_VALUE_SUCCESS = 0 -EXPECTED_NUMBER_OF_MESSAGES_TO_RECEIVE = 5 - - -def main(args=None) -> int: - """ - Run all the e2e tests. This exits on the first failure encountered. - - :param args: - :return: 0 if all tests pass, 1 if any fail - """ - try: - rclpy.init() - - return_value = RETURN_VALUE_FAILURE - split_command = LAUNCH_COMMAND.split() - logging.debug('Executing: %s', split_command) - process = subprocess.Popen(split_command) - - logging.info('====Starting tests====') - test_helpers.check_for_expected_nodes( - list(EXPECTED_REGULAR_NODES) + list(EXPECTED_LIFECYCLE_NODES)) - test_helpers.check_lifecycle_node_enumeration(EXPECTED_LIFECYCLE_NODES) - test_helpers.check_lifecycle_node_state(EXPECTED_LIFECYCLE_NODES, EXPECTED_LIFECYCLE_STATE) - test_helpers.check_for_expected_topic(EXPECTED_TOPIC) - test_helpers.check_for_statistic_publications( - EXPECTED_LIFECYCLE_NODES, EXPECTED_NUMBER_OF_MESSAGES_TO_RECEIVE, EXPECTED_TOPIC) - logging.info('====All tests succeeded====') - - return_value = RETURN_VALUE_SUCCESS - - except test_helpers.SystemMetricsEnd2EndTestException: - logging.error('Test failure: ', exc_info=True) - - except Exception: - logging.error('Caught unrelated exception: ', exc_info=True) - - finally: - logging.debug('Finished tests. Sending SIGINT') - process.send_signal(signal.SIGINT) - process.wait(timeout=TIMEOUT_SECONDS) - rclpy.shutdown() - - return return_value - - -if __name__ == '__main__': - test_helpers.setup_logger() - test_output = main() - logging.debug('exiting with test_output=%s', test_output) - sys.exit(test_output) diff --git a/test/test_helpers.py b/test/test_helpers.py deleted file mode 100644 index a54fa34e..00000000 --- a/test/test_helpers.py +++ /dev/null @@ -1,208 +0,0 @@ -# Copyright 2020 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. - -""" -Helper functions for end to end tests for system_metrics_collector ROS2 package. - -These functions are used to assert lifecycle node states. -""" - -import logging -import subprocess -import sys -from typing import List - -import rclpy -from rclpy.task import Future - -from retrying import retry -from statistics_listener import StatisticsListener - -# Commands to execute -LIST_NODES_COMMAND = 'ros2 node list' -LIST_SERVICES_COMMAND = 'ros2 service list' -LIST_LIFECYCLE_NODES_COMMAND = 'ros2 lifecycle nodes' -GET_LIFECYCLE_STATE_COMMAND = 'ros2 lifecycle get ' -TOPIC_LIST_COMMAND = 'ros2 topic list' -# Test constants -TIMEOUT_SECONDS = 30 -PUBLICATION_TEST_TIMEOUT_SECONDS = 180 -# Test retry constants -DEFAULT_MAX_ATTEMPTS = 10 -DEFAULT_WAIT_EXPONENTIAL_MULTIPLIER = 1000 -DEFAULT_MAX_EXPONENTIAL_WAIT_MILLISECONDS = 60000 -# This is longer than PUBLICATION_TEST_TIMEOUT_SECONDS in order to let the spin -# timout complete -DEFAULT_FIXED_WAIT_MILLISECONDS = (PUBLICATION_TEST_TIMEOUT_SECONDS + TIMEOUT_SECONDS) * 1000 - - -class SystemMetricsEnd2EndTestException(Exception): - """Exception used to denote end to end test failures.""" - - pass - - -def setup_logger() -> None: - """Format and setup the logger.""" - logger = logging.getLogger() - # setting to debug for end to end test soak - logger.setLevel(logging.DEBUG) - - handler = logging.StreamHandler(sys.stdout) - handler.setLevel(logging.DEBUG) - formatter = logging.Formatter('[%(module)s] [%(levelname)s] [%(asctime)s]: %(message)s') - handler.setFormatter(formatter) - logger.addHandler(handler) - - -def execute_command(command_list: List[str], timeout=TIMEOUT_SECONDS) -> List[str]: - """ - Execute a command and return its output. - - This uses subprocess.check_output to raise a CalledProcessError for any non-zero command - return. - - :param command_list: input command to execute - :param timeout: raise subprocess.TimeoutExpired if the input command exceeds the timeout - :return: List[str] of the command output - """ - logging.debug('execute_command: %s', command_list) - return (subprocess.check_output(command_list, timeout=timeout) - .decode(sys.stdout.encoding).splitlines()) - - -@retry(stop_max_attempt_number=DEFAULT_MAX_ATTEMPTS, - wait_exponential_multiplier=DEFAULT_WAIT_EXPONENTIAL_MULTIPLIER, - wait_exponential_max=DEFAULT_MAX_EXPONENTIAL_WAIT_MILLISECONDS) -def check_for_expected_nodes(expected_nodes: List) -> None: - """ - Check that all expected nodes can be found. - - Raise a SystemMetricsEnd2EndTestException if the attempts have been exceeded - :param args: - """ - logging.debug('starting test check_for_expected_nodes') - - expected_nodes = list(expected_nodes) - observed_nodes = execute_command(LIST_NODES_COMMAND.split(' ')) - logging.debug( - 'check_for_expected_nodes=%s observed_nodes=%s', str(expected_nodes), str(observed_nodes)) - - if set(expected_nodes).issubset(set(observed_nodes)): - logging.debug('check_for_expected_nodes success') - return - - raise SystemMetricsEnd2EndTestException('Failed to enumerate expected nodes.' - ' Observed: ' + str(observed_nodes)) - - -@retry(stop_max_attempt_number=DEFAULT_MAX_ATTEMPTS, - wait_exponential_multiplier=DEFAULT_WAIT_EXPONENTIAL_MULTIPLIER, - wait_exponential_max=DEFAULT_MAX_EXPONENTIAL_WAIT_MILLISECONDS) -def check_lifecycle_node_enumeration(expected_nodes: List) -> None: - """ - Check that all lifecycle nodes exist. - - This requires the ros2lifecycle dependency. - """ - logging.debug('starting test check_lifecycle_node_enumeration') - - output = execute_command(LIST_LIFECYCLE_NODES_COMMAND.split(' ')) - - if output.sort() == list(expected_nodes).sort(): - logging.info('check_lifecycle_node_enumeration success') - else: - raise SystemMetricsEnd2EndTestException('check_lifecycle_node_enumeration failed: ' - + str(output)) - - -@retry(stop_max_attempt_number=DEFAULT_MAX_ATTEMPTS, - wait_exponential_multiplier=DEFAULT_WAIT_EXPONENTIAL_MULTIPLIER, - wait_exponential_max=DEFAULT_MAX_EXPONENTIAL_WAIT_MILLISECONDS) -def check_lifecycle_node_state(expected_nodes: List, expected_state: str) -> None: - """ - Check that each lifecycle node is active. - - This requires the ros2lifecycle dependency. - """ - logging.debug('starting test check_lifecycle_node_state') - - for lifecycle_node in expected_nodes: - - output = execute_command((GET_LIFECYCLE_STATE_COMMAND - + str(lifecycle_node)).split(' ')) - - if not output: - raise SystemMetricsEnd2EndTestException('check_lifecycle_node_state: Unexpected output' - ' for node: ' + lifecycle_node) - - if output[0] == expected_state: - logging.debug('%s in expected state', lifecycle_node) - - else: - raise SystemMetricsEnd2EndTestException('check_lifecycle_node_state:' - + lifecycle_node + - ' not in expected state: ' - + str(output)) - - logging.info('check_lifecycle_node_state success') - - -@retry(stop_max_attempt_number=DEFAULT_MAX_ATTEMPTS, - wait_exponential_multiplier=DEFAULT_WAIT_EXPONENTIAL_MULTIPLIER, - wait_exponential_max=DEFAULT_MAX_EXPONENTIAL_WAIT_MILLISECONDS) -def check_for_expected_topic(expected_topic: str) -> None: - """ - Check if the expected_topic exists. - - :param expected_topic: - """ - logging.debug('starting test check_for_expected_topic') - - output = execute_command(TOPIC_LIST_COMMAND.split(' ')) - - if expected_topic in output: - logging.info('check_for_expected_topic success') - else: - raise SystemMetricsEnd2EndTestException('Unable to find expected topic: ' + str(output)) - - -@retry(stop_max_attempt_number=DEFAULT_MAX_ATTEMPTS, wait_fixed=DEFAULT_FIXED_WAIT_MILLISECONDS) -def check_for_statistic_publications( - expected_nodes: List, - num_msgs: int, - expected_topic: str) -> None: - """ - Check that all nodes publish a statistics message. - - This will suceed fast if all expected messages were published, otherwise - timeout (default TIMEOUT_SECONDS) if any publishers have not been observed. - :param args: - """ - logging.debug('starting test check_for_statistic_publications') - try: - future = Future() - node = StatisticsListener(future, list(expected_nodes), num_msgs, expected_topic) - rclpy.spin_until_future_complete(node, - future, - timeout_sec=PUBLICATION_TEST_TIMEOUT_SECONDS) - - if node.received_all_expected_messages(): - logging.info('check_for_statistic_publications success') - else: - raise SystemMetricsEnd2EndTestException('check_for_statistic_publications failed.' - ' Absent publisher(s): ' - + str(node.lifecycle_nodes_message_counter)) - finally: - node.destroy_node() diff --git a/test/topic_statistics_e2e_test.py b/test/topic_statistics_e2e_test.py deleted file mode 100644 index 41ecf3fa..00000000 --- a/test/topic_statistics_e2e_test.py +++ /dev/null @@ -1,103 +0,0 @@ -# Copyright 2020 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. - -""" -End to end tests for the topic statistics collection. - -These tests launch the dummy_talker and topic_statistics_node nodes and use -ROS2 commands to inspect if the expected nodes are active and publishing data. - -To run these tests ensure that ROS2 is installed, with the -system_metrics_collector package the relevant setup.bash has been sourced. -""" - -import logging -import signal -import subprocess -import sys - -import rclpy - -import test_helpers - - -# Expected outputs -EXPECTED_LIFECYCLE_NODES = frozenset(['/topic_stats_collector']) -EXPECTED_REGULAR_NODES = frozenset(['/dummy_talker']) -EXPECTED_LIFECYCLE_STATE = 'active [3]' -EXPECTED_TOPIC = '/system_metrics' -# Commands to execute -LAUNCH_TALKER = 'ros2 launch system_metrics_collector dummy_talker.launch.py' -LAUNCH_COLLECTOR = 'ros2 launch system_metrics_collector topic_statistics_node.launch.py' -# Test constants -TIMEOUT_SECONDS = 30 -RETURN_VALUE_FAILURE = 1 -RETURN_VALUE_SUCCESS = 0 -EXPECTED_NUMBER_OF_MESSAGES_TO_RECEIVE = 5 - - -def main(args=None) -> int: - """ - Run the topic statistics collector e2e tests. This exits on the first failure encountered. - - :param args: - :return: 0 if all tests pass, 1 if any fail - """ - try: - rclpy.init() - - return_value = RETURN_VALUE_FAILURE - - split_command = LAUNCH_TALKER.split() - logging.debug('Executing: %s', split_command) - talker_process = subprocess.Popen(split_command) - - split_command = LAUNCH_COLLECTOR.split() - logging.debug('Executing: %s', split_command) - listener_process = subprocess.Popen(split_command) - - logging.info('====Starting tests====') - test_helpers.check_for_expected_nodes( - list(EXPECTED_REGULAR_NODES) + list(EXPECTED_LIFECYCLE_NODES)) - test_helpers.check_lifecycle_node_enumeration(EXPECTED_LIFECYCLE_NODES) - test_helpers.check_lifecycle_node_state(EXPECTED_LIFECYCLE_NODES, EXPECTED_LIFECYCLE_STATE) - test_helpers.check_for_expected_topic(EXPECTED_TOPIC) - test_helpers.check_for_statistic_publications( - EXPECTED_LIFECYCLE_NODES, EXPECTED_NUMBER_OF_MESSAGES_TO_RECEIVE, EXPECTED_TOPIC) - logging.info('====All tests succeeded====') - - return_value = RETURN_VALUE_SUCCESS - - except test_helpers.SystemMetricsEnd2EndTestException: - logging.error('Test failure: ', exc_info=True) - - except Exception: - logging.error('Caught unrelated exception: ', exc_info=True) - - finally: - logging.debug('Finished tests. Sending SIGINT') - talker_process.send_signal(signal.SIGINT) - listener_process.send_signal(signal.SIGINT) - talker_process.wait(timeout=TIMEOUT_SECONDS) - listener_process.wait(timeout=TIMEOUT_SECONDS) - rclpy.shutdown() - - return return_value - - -if __name__ == '__main__': - test_helpers.setup_logger() - test_output = main() - logging.debug('exiting with test_output=%s', test_output) - sys.exit(test_output)