From dcfb8e8b2fcee7a9359c24c2c7e8677ba73804ef Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 4 Jun 2018 17:42:31 -0700 Subject: [PATCH 01/16] Add test_cli package with params yaml test --- test_cli/CMakeLists.txt | 35 ++++ test_cli/package.xml | 28 ++++ test_cli/test/__init__.py | 0 test_cli/test/initial_params.cpp | 32 ++++ test_cli/test/test_params_yaml.py | 268 ++++++++++++++++++++++++++++++ test_cli/test/utils.py | 68 ++++++++ 6 files changed, 431 insertions(+) create mode 100644 test_cli/CMakeLists.txt create mode 100644 test_cli/package.xml create mode 100644 test_cli/test/__init__.py create mode 100644 test_cli/test/initial_params.cpp create mode 100644 test_cli/test/test_params_yaml.py create mode 100644 test_cli/test/utils.py diff --git a/test_cli/CMakeLists.txt b/test_cli/CMakeLists.txt new file mode 100644 index 00000000..079dc4cf --- /dev/null +++ b/test_cli/CMakeLists.txt @@ -0,0 +1,35 @@ +cmake_minimum_required(VERSION 3.5) + +project(test_cli) + +find_package(ament_cmake_auto REQUIRED) + +if(BUILD_TESTING) + # Default to C++14 + if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) + endif() + + find_package(ament_cmake REQUIRED) + find_package(ament_lint_auto REQUIRED) + find_package(ament_cmake_pytest REQUIRED) + find_package(rclcpp REQUIRED) + + ament_lint_auto_find_test_dependencies() + + add_executable(initial_params_rclcpp + test/initial_params.cpp) + ament_target_dependencies(initial_params_rclcpp + "rclcpp") + + ament_add_pytest_test(test_params_yaml + test/test_params_yaml.py + ENV + INITIAL_PARAMS_RCLCPP=$ + TIMEOUT 120) + set_tests_properties(test_params_yaml + PROPERTIES DEPENDS + initial_params_rclcpp) +endif() + +ament_auto_package() diff --git a/test_cli/package.xml b/test_cli/package.xml new file mode 100644 index 00000000..7b280394 --- /dev/null +++ b/test_cli/package.xml @@ -0,0 +1,28 @@ + + + + test_cli + 0.4.0 + + Test command line arguments passed to ros2 executables. + + Shane Loretz + Apache License 2.0 + + ament_cmake_auto + + ament_cmake + + ament_cmake_pytest + ament_lint_auto + ament_lint_common + launch + rclcpp + rcl_interfaces + ros2param + rclpy + + + ament_cmake + + diff --git a/test_cli/test/__init__.py b/test_cli/test/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/test_cli/test/initial_params.cpp b/test_cli/test/initial_params.cpp new file mode 100644 index 00000000..8c001c73 --- /dev/null +++ b/test_cli/test/initial_params.cpp @@ -0,0 +1,32 @@ +// Copyright 2018 Open Source Robotics Foundation, Inc. +// +// 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 "rclcpp/rclcpp.hpp" + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + + std::string node_name = "initial_params_node"; + std::string namespace_ = "/"; + auto node = rclcpp::Node::make_shared(node_name, namespace_); + + rclcpp::spin(node); + + rclcpp::shutdown(); + return 0; +} diff --git a/test_cli/test/test_params_yaml.py b/test_cli/test/test_params_yaml.py new file mode 100644 index 00000000..87213e8d --- /dev/null +++ b/test_cli/test/test_params_yaml.py @@ -0,0 +1,268 @@ +# Copyright 2018 Open Source Robotics Foundation, Inc. +# +# 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 tempfile + +import pytest +from rcl_interfaces.msg import ParameterType +import rclpy +from ros2param.api import call_get_parameters + +from .utils import launch_process_and_coroutine +from .utils import make_coroutine_test +from .utils import require_environment_variable + + +CLIENT_LIBRARY_EXECUTABLES = ( + require_environment_variable('INITIAL_PARAMS_RCLCPP'), +) + + +@pytest.fixture(scope='module', params=CLIENT_LIBRARY_EXECUTABLES) +def node_fixture(request): + """Create a fixture with a node and helper executable.""" + rclpy.init() + node = rclpy.create_node('tests_yaml') + try: + yield { + 'node': node, + 'executable': request.param, + } + finally: + node.destroy_node() + rclpy.shutdown() + + +def get_params(node, param_names): + return call_get_parameters( + node=node, node_name='initial_params_node', parameter_names=param_names) + + +def test_bool_params(node_fixture): + def check_params(): + nonlocal node_fixture + resp = get_params(node_fixture['node'], ('b1', 'b2')) + if 2 == len(resp.values): + assert ParameterType.PARAMETER_BOOL == resp.values[0].type + assert ParameterType.PARAMETER_BOOL == resp.values[1].type + assert not resp.values[0].bool_value + assert resp.values[1].bool_value + return True + print(resp) + return False + + with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + yaml_file.write(""" +initial_params_node: + ros__parameters: + b1: False + b2: True +""") + yaml_file.flush() + + command = (node_fixture['executable'], '__params:=' + yaml_file.name) + actual_test = make_coroutine_test(check_func=check_params) + assert 0 == launch_process_and_coroutine(command, actual_test) + + +def test_integer_params(node_fixture): + def check_params(): + nonlocal node_fixture + resp = get_params(node_fixture['node'], ('i1', 'i2')) + if 2 == len(resp.values): + assert ParameterType.PARAMETER_INTEGER == resp.values[0].type + assert ParameterType.PARAMETER_INTEGER == resp.values[1].type + assert 42 == resp.values[0].integer_value + assert -27 == resp.values[1].integer_value + return True + print(resp) + return False + + with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + yaml_file.write(""" +initial_params_node: + ros__parameters: + i1: 42 + i2: -27 +""") + yaml_file.flush() + + command = (node_fixture['executable'], '__params:=' + yaml_file.name) + actual_test = make_coroutine_test(check_func=check_params) + assert 0 == launch_process_and_coroutine(command, actual_test) + + +def test_double_params(node_fixture): + def check_params(): + nonlocal node_fixture + resp = get_params(node_fixture['node'], ('d1', 'd2')) + if 2 == len(resp.values): + assert ParameterType.PARAMETER_DOUBLE == resp.values[0].type + assert ParameterType.PARAMETER_DOUBLE == resp.values[1].type + assert pytest.approx(3.14) == resp.values[0].double_value + assert pytest.approx(2.718) == resp.values[1].double_value + return True + print(resp) + return False + + with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + yaml_file.write(""" +initial_params_node: + ros__parameters: + d1: 3.14 + d2: 2.718 +""") + yaml_file.flush() + + command = (node_fixture['executable'], '__params:=' + yaml_file.name) + actual_test = make_coroutine_test(check_func=check_params) + assert 0 == launch_process_and_coroutine(command, actual_test) + + +def test_string_params(node_fixture): + def check_params(): + nonlocal node_fixture + resp = get_params(node_fixture['node'], ('s1', 's2')) + if 2 == len(resp.values): + assert ParameterType.PARAMETER_STRING == resp.values[0].type + assert ParameterType.PARAMETER_STRING == resp.values[1].type + assert resp.values[0].string_value == 'hello' + assert resp.values[1].string_value == 'world' + return True + print(resp) + return False + + with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + yaml_file.write(""" +initial_params_node: + ros__parameters: + s1: hello + s2: world +""") + yaml_file.flush() + + command = (node_fixture['executable'], '__params:=' + yaml_file.name) + actual_test = make_coroutine_test(check_func=check_params) + assert 0 == launch_process_and_coroutine(command, actual_test) + + +# TODO(sloretz) PARAMETER_BYTE_ARRAY when rcl_yaml_param_parser supports it + + +def test_bool_array_params(node_fixture): + def check_params(): + nonlocal node_fixture + resp = get_params(node_fixture['node'], ('ba1', 'ba2')) + if 2 == len(resp.values): + assert ParameterType.PARAMETER_BOOL_ARRAY == resp.values[0].type + assert ParameterType.PARAMETER_BOOL_ARRAY == resp.values[1].type + assert resp.values[0].bool_array_value == [True, False] + assert resp.values[1].bool_array_value == [False, True] + return True + print(resp) + return False + + with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + yaml_file.write(""" +initial_params_node: + ros__parameters: + ba1: [true, false] + ba2: [false, true] +""") + yaml_file.flush() + + command = (node_fixture['executable'], '__params:=' + yaml_file.name) + actual_test = make_coroutine_test(check_func=check_params) + assert 0 == launch_process_and_coroutine(command, actual_test) + + +def test_integer_array_params(node_fixture): + def check_params(): + nonlocal node_fixture + resp = get_params(node_fixture['node'], ('ia1', 'ia2')) + if 2 == len(resp.values): + assert ParameterType.PARAMETER_INTEGER_ARRAY == resp.values[0].type + assert ParameterType.PARAMETER_INTEGER_ARRAY == resp.values[1].type + assert resp.values[0].integer_array_value == [42, -27] + assert resp.values[1].integer_array_value == [1234, 5678] + return True + print(resp) + return False + + with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + yaml_file.write(""" +initial_params_node: + ros__parameters: + ia1: [42, -27] + ia2: [1234, 5678] +""") + yaml_file.flush() + + command = (node_fixture['executable'], '__params:=' + yaml_file.name) + actual_test = make_coroutine_test(check_func=check_params) + assert 0 == launch_process_and_coroutine(command, actual_test) + + +def test_double_array_params(node_fixture): + def check_params(): + nonlocal node_fixture + resp = get_params(node_fixture['node'], ('da1', 'da2')) + if 2 == len(resp.values): + assert ParameterType.PARAMETER_DOUBLE_ARRAY == resp.values[0].type + assert ParameterType.PARAMETER_DOUBLE_ARRAY == resp.values[1].type + assert resp.values[0].double_array_value == pytest.approx([3.14, 2.718]) + assert resp.values[1].double_array_value == pytest.approx([1234.5, 9999.0]) + return True + print(resp) + return False + + with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + yaml_file.write(""" +initial_params_node: + ros__parameters: + da1: [3.14, 2.718] + da2: [1234.5, 9999.0] +""") + yaml_file.flush() + + command = (node_fixture['executable'], '__params:=' + yaml_file.name) + actual_test = make_coroutine_test(check_func=check_params) + assert 0 == launch_process_and_coroutine(command, actual_test) + + +def test_string_array_params(node_fixture): + def check_params(): + nonlocal node_fixture + resp = get_params(node_fixture['node'], ('sa1', 'sa2')) + if 2 == len(resp.values): + assert ParameterType.PARAMETER_STRING_ARRAY == resp.values[0].type + assert ParameterType.PARAMETER_STRING_ARRAY == resp.values[1].type + assert resp.values[0].string_array_value == ['Four', 'score'] + assert resp.values[1].string_array_value == ['and', 'seven'] + return True + print(resp) + return False + + with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + yaml_file.write(""" +initial_params_node: + ros__parameters: + sa1: ['Four', 'score'] + sa2: ['and', 'seven'] +""") + yaml_file.flush() + + command = (node_fixture['executable'], '__params:=' + yaml_file.name) + actual_test = make_coroutine_test(check_func=check_params) + assert 0 == launch_process_and_coroutine(command, actual_test) diff --git a/test_cli/test/utils.py b/test_cli/test/utils.py new file mode 100644 index 00000000..e683f287 --- /dev/null +++ b/test_cli/test/utils.py @@ -0,0 +1,68 @@ +# Copyright 2018 Open Source Robotics Foundation, Inc. +# +# 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 asyncio +import os +import sys + +from launch import LaunchDescriptor +from launch.exit_handler import primary_exit_handler +from launch.launcher import DefaultLauncher + + +def require_environment_variable(name): + """Get environment variable or raise if it does not exist.""" + path = os.getenv(name) + if not path: + raise EnvironmentError('Missing environment variable "%s"' % name) + return path + + +def launch_process_and_coroutine(command, coroutine): + """Execute a command and coroutine in parallel.""" + # Execute python files using same python used to start this test + env = dict(os.environ) + if command[0][-3:] == '.py': + command.insert(0, sys.executable) + env['PYTHONUNBUFFERED'] = '1' + + ld = LaunchDescriptor() + ld.add_process( + cmd=command, + name='helper_for_' + coroutine.__name__, + env=env + ) + ld.add_coroutine( + coroutine(), + name=coroutine.__name__, + exit_handler=primary_exit_handler + ) + launcher = DefaultLauncher() + launcher.add_launch_descriptor(ld) + return_code = launcher.launch() + return return_code + + +def make_coroutine_test(*, check_func, attempts=10, time_between_attempts=1.0): + """Make a test that succeeds when check_func() returns True.""" + async def coroutine_test(): + for attempt in range(attempts): + if check_func(): + # Test passed + return + await asyncio.sleep(time_between_attempts) + # final attempt to check condition + assert check_func() + + return coroutine_test From 5c7e72be7f894dca74e1fb702b5a648b318171c6 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Mon, 4 Jun 2018 17:58:07 -0700 Subject: [PATCH 02/16] test multiple parameter files via CLI --- test_cli/test/test_params_yaml.py | 41 +++++++++++++++++++++++++++++++ 1 file changed, 41 insertions(+) diff --git a/test_cli/test/test_params_yaml.py b/test_cli/test/test_params_yaml.py index 87213e8d..795035bd 100644 --- a/test_cli/test/test_params_yaml.py +++ b/test_cli/test/test_params_yaml.py @@ -266,3 +266,44 @@ def check_params(): command = (node_fixture['executable'], '__params:=' + yaml_file.name) actual_test = make_coroutine_test(check_func=check_params) assert 0 == launch_process_and_coroutine(command, actual_test) + + +def test_multiple_parameter_files(node_fixture): + def check_params(): + nonlocal node_fixture + resp = get_params(node_fixture['node'], ('i1', 'i2', 'i3')) + if 3 == len(resp.values): + assert ParameterType.PARAMETER_INTEGER == resp.values[0].type + assert ParameterType.PARAMETER_INTEGER == resp.values[1].type + assert ParameterType.PARAMETER_INTEGER == resp.values[2].type + assert 42 == resp.values[0].integer_value + assert 12345 == resp.values[1].integer_value + assert -27 == resp.values[2].integer_value + return True + print(resp) + return False + + with tempfile.NamedTemporaryFile(mode='w') as first_yaml_file: + first_yaml_file.write(""" +initial_params_node: + ros__parameters: + i1: 42 + i2: -27 +""") + first_yaml_file.flush() + with tempfile.NamedTemporaryFile(mode='w') as second_yaml_file: + second_yaml_file.write(""" +initial_params_node: + ros__parameters: + i2: 12345 + i3: -27 +""") + second_yaml_file.flush() + + command = ( + node_fixture['executable'], + '__params:=' + first_yaml_file.name, + '__params:=' + second_yaml_file.name + ) + actual_test = make_coroutine_test(check_func=check_params) + assert 0 == launch_process_and_coroutine(command, actual_test) From 85921864064553d2e415c3af1336a63ebaa23aac Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 5 Jun 2018 13:43:57 -0700 Subject: [PATCH 03/16] Check explicitly if variable is not None --- test_cli/test/utils.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test_cli/test/utils.py b/test_cli/test/utils.py index e683f287..0c33c7b8 100644 --- a/test_cli/test/utils.py +++ b/test_cli/test/utils.py @@ -24,7 +24,7 @@ def require_environment_variable(name): """Get environment variable or raise if it does not exist.""" path = os.getenv(name) - if not path: + if path is not None: raise EnvironmentError('Missing environment variable "%s"' % name) return path From 28610d60407868bbbafd92ed0cc62f62ca30965e Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 5 Jun 2018 16:01:48 -0700 Subject: [PATCH 04/16] Fix inverted logic --- test_cli/test/utils.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/test_cli/test/utils.py b/test_cli/test/utils.py index 0c33c7b8..3130b949 100644 --- a/test_cli/test/utils.py +++ b/test_cli/test/utils.py @@ -23,10 +23,10 @@ def require_environment_variable(name): """Get environment variable or raise if it does not exist.""" - path = os.getenv(name) - if path is not None: + env = os.getenv(name) + if env is None: raise EnvironmentError('Missing environment variable "%s"' % name) - return path + return env def launch_process_and_coroutine(command, coroutine): From 41a5dcca6be4928e77cca50b7081abfbb56f899d Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Wed, 6 Jun 2018 10:53:24 +0200 Subject: [PATCH 05/16] launch -> launch.legacy --- test_cli/test/utils.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/test_cli/test/utils.py b/test_cli/test/utils.py index 3130b949..0e812180 100644 --- a/test_cli/test/utils.py +++ b/test_cli/test/utils.py @@ -16,9 +16,9 @@ import os import sys -from launch import LaunchDescriptor -from launch.exit_handler import primary_exit_handler -from launch.launcher import DefaultLauncher +from launch.legacy import LaunchDescriptor +from launch.legacy.exit_handler import primary_exit_handler +from launch.legacy.launcher import DefaultLauncher def require_environment_variable(name): From a3687e2015c266f4834a4d79cf71e1812a058aa8 Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Wed, 6 Jun 2018 11:14:30 +0200 Subject: [PATCH 06/16] dependencies in alphabetical order --- test_cli/package.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/test_cli/package.xml b/test_cli/package.xml index 7b280394..64fc08f1 100644 --- a/test_cli/package.xml +++ b/test_cli/package.xml @@ -17,10 +17,10 @@ ament_lint_auto ament_lint_common launch - rclcpp rcl_interfaces - ros2param + rclcpp rclpy + ros2param ament_cmake From f36e85d10df212dc141a4010647fc32c0f40640e Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Wed, 6 Jun 2018 11:14:44 +0200 Subject: [PATCH 07/16] unused include --- test_cli/test/initial_params.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/test_cli/test/initial_params.cpp b/test_cli/test/initial_params.cpp index 8c001c73..7a2c5694 100644 --- a/test_cli/test/initial_params.cpp +++ b/test_cli/test/initial_params.cpp @@ -13,7 +13,6 @@ // limitations under the License. #include -#include #include "rclcpp/rclcpp.hpp" From d2b7b76194f11b5e6c59d0903e1c5546949257f4 Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Wed, 6 Jun 2018 11:17:30 +0200 Subject: [PATCH 08/16] make it explicit that loop control variable is unused --- test_cli/test/utils.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test_cli/test/utils.py b/test_cli/test/utils.py index 0e812180..55d137ce 100644 --- a/test_cli/test/utils.py +++ b/test_cli/test/utils.py @@ -57,7 +57,7 @@ def launch_process_and_coroutine(command, coroutine): def make_coroutine_test(*, check_func, attempts=10, time_between_attempts=1.0): """Make a test that succeeds when check_func() returns True.""" async def coroutine_test(): - for attempt in range(attempts): + for _ in range(attempts): if check_func(): # Test passed return From 4b8c8864f2edec274c77d09271d7ec4f6d9a4134 Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Wed, 6 Jun 2018 11:18:46 +0200 Subject: [PATCH 09/16] use default test timeout --- test_cli/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test_cli/CMakeLists.txt b/test_cli/CMakeLists.txt index 079dc4cf..e37acb97 100644 --- a/test_cli/CMakeLists.txt +++ b/test_cli/CMakeLists.txt @@ -26,7 +26,7 @@ if(BUILD_TESTING) test/test_params_yaml.py ENV INITIAL_PARAMS_RCLCPP=$ - TIMEOUT 120) + ) set_tests_properties(test_params_yaml PROPERTIES DEPENDS initial_params_rclcpp) From 568a6d1198cc877e80c3fe90a4cceb65ab83cefd Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Wed, 6 Jun 2018 11:21:37 +0200 Subject: [PATCH 10/16] test some negative double values as well --- test_cli/test/test_params_yaml.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/test_cli/test/test_params_yaml.py b/test_cli/test/test_params_yaml.py index 795035bd..9bde0882 100644 --- a/test_cli/test/test_params_yaml.py +++ b/test_cli/test/test_params_yaml.py @@ -111,7 +111,7 @@ def check_params(): assert ParameterType.PARAMETER_DOUBLE == resp.values[0].type assert ParameterType.PARAMETER_DOUBLE == resp.values[1].type assert pytest.approx(3.14) == resp.values[0].double_value - assert pytest.approx(2.718) == resp.values[1].double_value + assert pytest.approx(-2.718) == resp.values[1].double_value return True print(resp) return False @@ -121,7 +121,7 @@ def check_params(): initial_params_node: ros__parameters: d1: 3.14 - d2: 2.718 + d2: -2.718 """) yaml_file.flush() @@ -221,8 +221,8 @@ def check_params(): if 2 == len(resp.values): assert ParameterType.PARAMETER_DOUBLE_ARRAY == resp.values[0].type assert ParameterType.PARAMETER_DOUBLE_ARRAY == resp.values[1].type - assert resp.values[0].double_array_value == pytest.approx([3.14, 2.718]) - assert resp.values[1].double_array_value == pytest.approx([1234.5, 9999.0]) + assert resp.values[0].double_array_value == pytest.approx([3.14, -2.718]) + assert resp.values[1].double_array_value == pytest.approx([1234.5, -9999.0]) return True print(resp) return False @@ -231,8 +231,8 @@ def check_params(): yaml_file.write(""" initial_params_node: ros__parameters: - da1: [3.14, 2.718] - da2: [1234.5, 9999.0] + da1: [3.14, -2.718] + da2: [1234.5, -9999.0] """) yaml_file.flush() From cd83f0f8c5443158aad309786e5aff617a3971e8 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 6 Jun 2018 13:46:45 -0700 Subject: [PATCH 11/16] Workaround windows temporary file issue --- test_cli/test/test_params_yaml.py | 34 ++++++++++++++++++++----------- test_cli/test/utils.py | 19 +++++++++++++++++ 2 files changed, 41 insertions(+), 12 deletions(-) diff --git a/test_cli/test/test_params_yaml.py b/test_cli/test/test_params_yaml.py index 9bde0882..2613cbfe 100644 --- a/test_cli/test/test_params_yaml.py +++ b/test_cli/test/test_params_yaml.py @@ -12,8 +12,6 @@ # See the License for the specific language governing permissions and # limitations under the License. -import tempfile - import pytest from rcl_interfaces.msg import ParameterType import rclpy @@ -21,6 +19,7 @@ from .utils import launch_process_and_coroutine from .utils import make_coroutine_test +from .utils import NamedTemporaryFile from .utils import require_environment_variable @@ -62,7 +61,7 @@ def check_params(): print(resp) return False - with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + with NamedTemporaryFile() as yaml_file: yaml_file.write(""" initial_params_node: ros__parameters: @@ -70,6 +69,8 @@ def check_params(): b2: True """) yaml_file.flush() + # close so it can be opened again on windows + yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) actual_test = make_coroutine_test(check_func=check_params) @@ -89,7 +90,7 @@ def check_params(): print(resp) return False - with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + with NamedTemporaryFile() as yaml_file: yaml_file.write(""" initial_params_node: ros__parameters: @@ -97,6 +98,7 @@ def check_params(): i2: -27 """) yaml_file.flush() + yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) actual_test = make_coroutine_test(check_func=check_params) @@ -116,7 +118,7 @@ def check_params(): print(resp) return False - with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + with NamedTemporaryFile() as yaml_file: yaml_file.write(""" initial_params_node: ros__parameters: @@ -124,6 +126,7 @@ def check_params(): d2: -2.718 """) yaml_file.flush() + yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) actual_test = make_coroutine_test(check_func=check_params) @@ -143,7 +146,7 @@ def check_params(): print(resp) return False - with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + with NamedTemporaryFile() as yaml_file: yaml_file.write(""" initial_params_node: ros__parameters: @@ -151,6 +154,7 @@ def check_params(): s2: world """) yaml_file.flush() + yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) actual_test = make_coroutine_test(check_func=check_params) @@ -173,7 +177,7 @@ def check_params(): print(resp) return False - with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + with NamedTemporaryFile() as yaml_file: yaml_file.write(""" initial_params_node: ros__parameters: @@ -181,6 +185,7 @@ def check_params(): ba2: [false, true] """) yaml_file.flush() + yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) actual_test = make_coroutine_test(check_func=check_params) @@ -200,7 +205,7 @@ def check_params(): print(resp) return False - with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + with NamedTemporaryFile() as yaml_file: yaml_file.write(""" initial_params_node: ros__parameters: @@ -208,6 +213,7 @@ def check_params(): ia2: [1234, 5678] """) yaml_file.flush() + yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) actual_test = make_coroutine_test(check_func=check_params) @@ -227,7 +233,7 @@ def check_params(): print(resp) return False - with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + with NamedTemporaryFile() as yaml_file: yaml_file.write(""" initial_params_node: ros__parameters: @@ -235,6 +241,7 @@ def check_params(): da2: [1234.5, -9999.0] """) yaml_file.flush() + yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) actual_test = make_coroutine_test(check_func=check_params) @@ -254,7 +261,7 @@ def check_params(): print(resp) return False - with tempfile.NamedTemporaryFile(mode='w') as yaml_file: + with NamedTemporaryFile() as yaml_file: yaml_file.write(""" initial_params_node: ros__parameters: @@ -262,6 +269,7 @@ def check_params(): sa2: ['and', 'seven'] """) yaml_file.flush() + yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) actual_test = make_coroutine_test(check_func=check_params) @@ -283,7 +291,7 @@ def check_params(): print(resp) return False - with tempfile.NamedTemporaryFile(mode='w') as first_yaml_file: + with NamedTemporaryFile() as first_yaml_file: first_yaml_file.write(""" initial_params_node: ros__parameters: @@ -291,7 +299,8 @@ def check_params(): i2: -27 """) first_yaml_file.flush() - with tempfile.NamedTemporaryFile(mode='w') as second_yaml_file: + first_yaml_file.close() + with NamedTemporaryFile() as second_yaml_file: second_yaml_file.write(""" initial_params_node: ros__parameters: @@ -299,6 +308,7 @@ def check_params(): i3: -27 """) second_yaml_file.flush() + second_yaml_file.close() command = ( node_fixture['executable'], diff --git a/test_cli/test/utils.py b/test_cli/test/utils.py index 55d137ce..3f289167 100644 --- a/test_cli/test/utils.py +++ b/test_cli/test/utils.py @@ -15,6 +15,7 @@ import asyncio import os import sys +import tempfile from launch.legacy import LaunchDescriptor from launch.legacy.exit_handler import primary_exit_handler @@ -66,3 +67,21 @@ async def coroutine_test(): assert check_func() return coroutine_test + + +class NamedTemporaryFile: + """ + Create a named temporary file. + + This allows the file to be closed to allow opening by other processes on windows. + """ + + def __init__(self): + self._tempfile = tempfile.NamedTemporaryFile(mode='w', delete=False) + + def __enter__(self): + return self._tempfile + + def __exit__(self, t, v, tb): + os.unlink(self._tempfile.name) + return self._tempfile.__exit__(t, v, tb) From 004b64ddb6791e882442f851775a93a1f0a983c2 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Wed, 6 Jun 2018 16:49:27 -0700 Subject: [PATCH 12/16] Fix timeout on windows Re-implement get_params without blocking when service is not ready --- test_cli/package.xml | 1 - test_cli/test/test_params_yaml.py | 19 ++++++++++++++++--- test_cli/test/utils.py | 16 +++++++++++----- 3 files changed, 27 insertions(+), 9 deletions(-) diff --git a/test_cli/package.xml b/test_cli/package.xml index 64fc08f1..a1901a62 100644 --- a/test_cli/package.xml +++ b/test_cli/package.xml @@ -20,7 +20,6 @@ rcl_interfaces rclcpp rclpy - ros2param ament_cmake diff --git a/test_cli/test/test_params_yaml.py b/test_cli/test/test_params_yaml.py index 2613cbfe..9df11059 100644 --- a/test_cli/test/test_params_yaml.py +++ b/test_cli/test/test_params_yaml.py @@ -14,8 +14,8 @@ import pytest from rcl_interfaces.msg import ParameterType +from rcl_interfaces.srv import GetParameters import rclpy -from ros2param.api import call_get_parameters from .utils import launch_process_and_coroutine from .utils import make_coroutine_test @@ -44,8 +44,21 @@ def node_fixture(request): def get_params(node, param_names): - return call_get_parameters( - node=node, node_name='initial_params_node', parameter_names=param_names) + client = node.create_client(GetParameters, '/initial_params_node/get_parameters') + + if not client.service_is_ready(): + return GetParameters.Response() + + request = GetParameters.Request() + request.names = param_names + future = client.call_async(request) + rclpy.spin_until_future_complete(node, future) + + # handle response + response = future.result() + if response is None: + raise future.exception() + return response def test_bool_params(node_fixture): diff --git a/test_cli/test/utils.py b/test_cli/test/utils.py index 3f289167..233422be 100644 --- a/test_cli/test/utils.py +++ b/test_cli/test/utils.py @@ -14,6 +14,7 @@ import asyncio import os +import random import sys import tempfile @@ -76,12 +77,17 @@ class NamedTemporaryFile: This allows the file to be closed to allow opening by other processes on windows. """ - def __init__(self): - self._tempfile = tempfile.NamedTemporaryFile(mode='w', delete=False) + def __init__(self, mode='w'): + self._tempdir = tempfile.TemporaryDirectory(prefix='test_cli_') + self._mode = mode def __enter__(self): - return self._tempfile + directory = self._tempdir.__enter__() + name = ''.join(random.choice('abcdefghijklmnopqrstuvwxyz') for _ in range(10)) + self._filename = os.path.join(directory, name) + self._file = open(self._filename, mode=self._mode) + return self._file def __exit__(self, t, v, tb): - os.unlink(self._tempfile.name) - return self._tempfile.__exit__(t, v, tb) + self._file.close() + self._tempdir.__exit__(t, v, tb) From 2c46cdb5d5393cf61b41548bfcf799f01d405a5a Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 7 Jun 2018 08:58:54 -0700 Subject: [PATCH 13/16] Asyncronously get parameters --- test_cli/test/test_params_yaml.py | 213 ++++++++++++++---------------- test_cli/test/utils.py | 15 --- 2 files changed, 98 insertions(+), 130 deletions(-) diff --git a/test_cli/test/test_params_yaml.py b/test_cli/test/test_params_yaml.py index 9df11059..64f0de4c 100644 --- a/test_cli/test/test_params_yaml.py +++ b/test_cli/test/test_params_yaml.py @@ -12,13 +12,14 @@ # See the License for the specific language governing permissions and # limitations under the License. +import asyncio + import pytest from rcl_interfaces.msg import ParameterType from rcl_interfaces.srv import GetParameters import rclpy from .utils import launch_process_and_coroutine -from .utils import make_coroutine_test from .utils import NamedTemporaryFile from .utils import require_environment_variable @@ -43,36 +44,50 @@ def node_fixture(request): rclpy.shutdown() -def get_params(node, param_names): - client = node.create_client(GetParameters, '/initial_params_node/get_parameters') +def get_params_test(node, check_func, param_names, *, attempts=10, time_between_attempts=1.0): + """Make a test that gets params and calls check_func(results).""" + async def coroutine_test(): + nonlocal node + nonlocal check_func + nonlocal param_names + nonlocal attempts + nonlocal time_between_attempts + # wait for service to be ready + client = node.create_client(GetParameters, '/initial_params_node/get_parameters') + while not client.service_is_ready() and attempts > 0: + attempts -= 1 + await asyncio.sleep(time_between_attempts) + + assert attempts > 0 + + # Call the service and get the results + request = GetParameters.Request() + request.names = param_names + future = client.call_async(request) + for _ in range(attempts): + if future.done(): + break + rclpy.spin_once(node) + await asyncio.sleep(time_between_attempts) + if future.exception(): + raise future.exception() - if not client.service_is_ready(): - return GetParameters.Response() + assert attempts > 0 - request = GetParameters.Request() - request.names = param_names - future = client.call_async(request) - rclpy.spin_until_future_complete(node, future) + # see if the result looks ok + check_func(future.result()) - # handle response - response = future.result() - if response is None: - raise future.exception() - return response + return coroutine_test def test_bool_params(node_fixture): - def check_params(): + def check_params(resp): nonlocal node_fixture - resp = get_params(node_fixture['node'], ('b1', 'b2')) - if 2 == len(resp.values): - assert ParameterType.PARAMETER_BOOL == resp.values[0].type - assert ParameterType.PARAMETER_BOOL == resp.values[1].type - assert not resp.values[0].bool_value - assert resp.values[1].bool_value - return True - print(resp) - return False + assert 2 == len(resp.values) + assert ParameterType.PARAMETER_BOOL == resp.values[0].type + assert ParameterType.PARAMETER_BOOL == resp.values[1].type + assert not resp.values[0].bool_value + assert resp.values[1].bool_value with NamedTemporaryFile() as yaml_file: yaml_file.write(""" @@ -86,22 +101,18 @@ def check_params(): yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = make_coroutine_test(check_func=check_params) + actual_test = get_params_test(node_fixture['node'], check_params, ('b1', 'b2')) assert 0 == launch_process_and_coroutine(command, actual_test) def test_integer_params(node_fixture): - def check_params(): + def check_params(resp): nonlocal node_fixture - resp = get_params(node_fixture['node'], ('i1', 'i2')) - if 2 == len(resp.values): - assert ParameterType.PARAMETER_INTEGER == resp.values[0].type - assert ParameterType.PARAMETER_INTEGER == resp.values[1].type - assert 42 == resp.values[0].integer_value - assert -27 == resp.values[1].integer_value - return True - print(resp) - return False + assert 2 == len(resp.values) + assert ParameterType.PARAMETER_INTEGER == resp.values[0].type + assert ParameterType.PARAMETER_INTEGER == resp.values[1].type + assert 42 == resp.values[0].integer_value + assert -27 == resp.values[1].integer_value with NamedTemporaryFile() as yaml_file: yaml_file.write(""" @@ -114,22 +125,18 @@ def check_params(): yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = make_coroutine_test(check_func=check_params) + actual_test = get_params_test(node_fixture['node'], check_params, ('i1', 'i2')) assert 0 == launch_process_and_coroutine(command, actual_test) def test_double_params(node_fixture): - def check_params(): + def check_params(resp): nonlocal node_fixture - resp = get_params(node_fixture['node'], ('d1', 'd2')) - if 2 == len(resp.values): - assert ParameterType.PARAMETER_DOUBLE == resp.values[0].type - assert ParameterType.PARAMETER_DOUBLE == resp.values[1].type - assert pytest.approx(3.14) == resp.values[0].double_value - assert pytest.approx(-2.718) == resp.values[1].double_value - return True - print(resp) - return False + assert 2 == len(resp.values) + assert ParameterType.PARAMETER_DOUBLE == resp.values[0].type + assert ParameterType.PARAMETER_DOUBLE == resp.values[1].type + assert pytest.approx(3.14) == resp.values[0].double_value + assert pytest.approx(-2.718) == resp.values[1].double_value with NamedTemporaryFile() as yaml_file: yaml_file.write(""" @@ -142,22 +149,18 @@ def check_params(): yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = make_coroutine_test(check_func=check_params) + actual_test = get_params_test(node_fixture['node'], check_params, ('d1', 'd2')) assert 0 == launch_process_and_coroutine(command, actual_test) def test_string_params(node_fixture): - def check_params(): + def check_params(resp): nonlocal node_fixture - resp = get_params(node_fixture['node'], ('s1', 's2')) - if 2 == len(resp.values): - assert ParameterType.PARAMETER_STRING == resp.values[0].type - assert ParameterType.PARAMETER_STRING == resp.values[1].type - assert resp.values[0].string_value == 'hello' - assert resp.values[1].string_value == 'world' - return True - print(resp) - return False + assert 2 == len(resp.values) + assert ParameterType.PARAMETER_STRING == resp.values[0].type + assert ParameterType.PARAMETER_STRING == resp.values[1].type + assert resp.values[0].string_value == 'hello' + assert resp.values[1].string_value == 'world' with NamedTemporaryFile() as yaml_file: yaml_file.write(""" @@ -170,7 +173,7 @@ def check_params(): yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = make_coroutine_test(check_func=check_params) + actual_test = get_params_test(node_fixture['node'], check_params, ('s1', 's2')) assert 0 == launch_process_and_coroutine(command, actual_test) @@ -178,17 +181,13 @@ def check_params(): def test_bool_array_params(node_fixture): - def check_params(): + def check_params(resp): nonlocal node_fixture - resp = get_params(node_fixture['node'], ('ba1', 'ba2')) - if 2 == len(resp.values): - assert ParameterType.PARAMETER_BOOL_ARRAY == resp.values[0].type - assert ParameterType.PARAMETER_BOOL_ARRAY == resp.values[1].type - assert resp.values[0].bool_array_value == [True, False] - assert resp.values[1].bool_array_value == [False, True] - return True - print(resp) - return False + assert 2 == len(resp.values) + assert ParameterType.PARAMETER_BOOL_ARRAY == resp.values[0].type + assert ParameterType.PARAMETER_BOOL_ARRAY == resp.values[1].type + assert resp.values[0].bool_array_value == [True, False] + assert resp.values[1].bool_array_value == [False, True] with NamedTemporaryFile() as yaml_file: yaml_file.write(""" @@ -201,22 +200,18 @@ def check_params(): yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = make_coroutine_test(check_func=check_params) + actual_test = get_params_test(node_fixture['node'], check_params, ('ba1', 'ba2')) assert 0 == launch_process_and_coroutine(command, actual_test) def test_integer_array_params(node_fixture): - def check_params(): + def check_params(resp): nonlocal node_fixture - resp = get_params(node_fixture['node'], ('ia1', 'ia2')) - if 2 == len(resp.values): - assert ParameterType.PARAMETER_INTEGER_ARRAY == resp.values[0].type - assert ParameterType.PARAMETER_INTEGER_ARRAY == resp.values[1].type - assert resp.values[0].integer_array_value == [42, -27] - assert resp.values[1].integer_array_value == [1234, 5678] - return True - print(resp) - return False + assert 2 == len(resp.values) + assert ParameterType.PARAMETER_INTEGER_ARRAY == resp.values[0].type + assert ParameterType.PARAMETER_INTEGER_ARRAY == resp.values[1].type + assert resp.values[0].integer_array_value == [42, -27] + assert resp.values[1].integer_array_value == [1234, 5678] with NamedTemporaryFile() as yaml_file: yaml_file.write(""" @@ -229,22 +224,18 @@ def check_params(): yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = make_coroutine_test(check_func=check_params) + actual_test = get_params_test(node_fixture['node'], check_params, ('ia1', 'ia2')) assert 0 == launch_process_and_coroutine(command, actual_test) def test_double_array_params(node_fixture): - def check_params(): + def check_params(resp): nonlocal node_fixture - resp = get_params(node_fixture['node'], ('da1', 'da2')) - if 2 == len(resp.values): - assert ParameterType.PARAMETER_DOUBLE_ARRAY == resp.values[0].type - assert ParameterType.PARAMETER_DOUBLE_ARRAY == resp.values[1].type - assert resp.values[0].double_array_value == pytest.approx([3.14, -2.718]) - assert resp.values[1].double_array_value == pytest.approx([1234.5, -9999.0]) - return True - print(resp) - return False + assert 2 == len(resp.values) + assert ParameterType.PARAMETER_DOUBLE_ARRAY == resp.values[0].type + assert ParameterType.PARAMETER_DOUBLE_ARRAY == resp.values[1].type + assert resp.values[0].double_array_value == pytest.approx([3.14, -2.718]) + assert resp.values[1].double_array_value == pytest.approx([1234.5, -9999.0]) with NamedTemporaryFile() as yaml_file: yaml_file.write(""" @@ -257,22 +248,18 @@ def check_params(): yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = make_coroutine_test(check_func=check_params) + actual_test = get_params_test(node_fixture['node'], check_params, ('da1', 'da2')) assert 0 == launch_process_and_coroutine(command, actual_test) def test_string_array_params(node_fixture): - def check_params(): + def check_params(resp): nonlocal node_fixture - resp = get_params(node_fixture['node'], ('sa1', 'sa2')) - if 2 == len(resp.values): - assert ParameterType.PARAMETER_STRING_ARRAY == resp.values[0].type - assert ParameterType.PARAMETER_STRING_ARRAY == resp.values[1].type - assert resp.values[0].string_array_value == ['Four', 'score'] - assert resp.values[1].string_array_value == ['and', 'seven'] - return True - print(resp) - return False + assert 2 == len(resp.values) + assert ParameterType.PARAMETER_STRING_ARRAY == resp.values[0].type + assert ParameterType.PARAMETER_STRING_ARRAY == resp.values[1].type + assert resp.values[0].string_array_value == ['Four', 'score'] + assert resp.values[1].string_array_value == ['and', 'seven'] with NamedTemporaryFile() as yaml_file: yaml_file.write(""" @@ -285,24 +272,20 @@ def check_params(): yaml_file.close() command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = make_coroutine_test(check_func=check_params) + actual_test = get_params_test(node_fixture['node'], check_params, ('sa1', 'sa2')) assert 0 == launch_process_and_coroutine(command, actual_test) def test_multiple_parameter_files(node_fixture): - def check_params(): + def check_params(resp): nonlocal node_fixture - resp = get_params(node_fixture['node'], ('i1', 'i2', 'i3')) - if 3 == len(resp.values): - assert ParameterType.PARAMETER_INTEGER == resp.values[0].type - assert ParameterType.PARAMETER_INTEGER == resp.values[1].type - assert ParameterType.PARAMETER_INTEGER == resp.values[2].type - assert 42 == resp.values[0].integer_value - assert 12345 == resp.values[1].integer_value - assert -27 == resp.values[2].integer_value - return True - print(resp) - return False + assert 3 == len(resp.values) + assert ParameterType.PARAMETER_INTEGER == resp.values[0].type + assert ParameterType.PARAMETER_INTEGER == resp.values[1].type + assert ParameterType.PARAMETER_INTEGER == resp.values[2].type + assert 42 == resp.values[0].integer_value + assert 12345 == resp.values[1].integer_value + assert -27 == resp.values[2].integer_value with NamedTemporaryFile() as first_yaml_file: first_yaml_file.write(""" @@ -328,5 +311,5 @@ def check_params(): '__params:=' + first_yaml_file.name, '__params:=' + second_yaml_file.name ) - actual_test = make_coroutine_test(check_func=check_params) + actual_test = get_params_test(node_fixture['node'], check_params, ('i1', 'i2', 'i3')) assert 0 == launch_process_and_coroutine(command, actual_test) diff --git a/test_cli/test/utils.py b/test_cli/test/utils.py index 233422be..0533b9dd 100644 --- a/test_cli/test/utils.py +++ b/test_cli/test/utils.py @@ -12,7 +12,6 @@ # See the License for the specific language governing permissions and # limitations under the License. -import asyncio import os import random import sys @@ -56,20 +55,6 @@ def launch_process_and_coroutine(command, coroutine): return return_code -def make_coroutine_test(*, check_func, attempts=10, time_between_attempts=1.0): - """Make a test that succeeds when check_func() returns True.""" - async def coroutine_test(): - for _ in range(attempts): - if check_func(): - # Test passed - return - await asyncio.sleep(time_between_attempts) - # final attempt to check condition - assert check_func() - - return coroutine_test - - class NamedTemporaryFile: """ Create a named temporary file. From 4441214e9751f6ffbab0e55be105ddcbfbb34a19 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 7 Jun 2018 14:28:47 -0700 Subject: [PATCH 14/16] Use threading instead of asyncio --- test_cli/test/test_params_yaml.py | 302 ++++++++++++------------------ test_cli/test/utils.py | 88 +++++---- 2 files changed, 171 insertions(+), 219 deletions(-) diff --git a/test_cli/test/test_params_yaml.py b/test_cli/test/test_params_yaml.py index 64f0de4c..f9cce848 100644 --- a/test_cli/test/test_params_yaml.py +++ b/test_cli/test/test_params_yaml.py @@ -12,14 +12,13 @@ # See the License for the specific language governing permissions and # limitations under the License. -import asyncio - import pytest from rcl_interfaces.msg import ParameterType from rcl_interfaces.srv import GetParameters import rclpy -from .utils import launch_process_and_coroutine +from .utils import BackgroundExecutor +from .utils import HelperCommand from .utils import NamedTemporaryFile from .utils import require_environment_variable @@ -44,272 +43,209 @@ def node_fixture(request): rclpy.shutdown() -def get_params_test(node, check_func, param_names, *, attempts=10, time_between_attempts=1.0): - """Make a test that gets params and calls check_func(results).""" - async def coroutine_test(): - nonlocal node - nonlocal check_func - nonlocal param_names - nonlocal attempts - nonlocal time_between_attempts - # wait for service to be ready - client = node.create_client(GetParameters, '/initial_params_node/get_parameters') - while not client.service_is_ready() and attempts > 0: - attempts -= 1 - await asyncio.sleep(time_between_attempts) - - assert attempts > 0 - - # Call the service and get the results +def get_params(node, node_name, param_names, wfs_timeout=5.0): + with BackgroundExecutor(node): + client = node.create_client(GetParameters, '/{name}/get_parameters'.format(name=node_name)) + assert client.wait_for_service(timeout_sec=wfs_timeout) request = GetParameters.Request() request.names = param_names - future = client.call_async(request) - for _ in range(attempts): - if future.done(): - break - rclpy.spin_once(node) - await asyncio.sleep(time_between_attempts) - if future.exception(): - raise future.exception() + resp = client.call(request) + node.destroy_client(client) + return resp - assert attempts > 0 - # see if the result looks ok - check_func(future.result()) - - return coroutine_test +def test_bool_params(node_fixture): + param_file_content = """ +bool_params: + ros__parameters: + b1: False + b2: True +""" + with NamedTemporaryFile(param_file_content) as yaml_file: + command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=bool_params') + with HelperCommand(command): + resp = get_params(node_fixture['node'], 'bool_params', ['b1', 'b2']) -def test_bool_params(node_fixture): - def check_params(resp): - nonlocal node_fixture assert 2 == len(resp.values) assert ParameterType.PARAMETER_BOOL == resp.values[0].type assert ParameterType.PARAMETER_BOOL == resp.values[1].type assert not resp.values[0].bool_value assert resp.values[1].bool_value - with NamedTemporaryFile() as yaml_file: - yaml_file.write(""" -initial_params_node: - ros__parameters: - b1: False - b2: True -""") - yaml_file.flush() - # close so it can be opened again on windows - yaml_file.close() - command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = get_params_test(node_fixture['node'], check_params, ('b1', 'b2')) - assert 0 == launch_process_and_coroutine(command, actual_test) +def test_integer_params(node_fixture): + param_file_content = """ +int_params: + ros__parameters: + i1: 42 + i2: -27 +""" + with NamedTemporaryFile(param_file_content) as yaml_file: + command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=int_params') + with HelperCommand(command): + resp = get_params(node_fixture['node'], 'int_params', ['i1', 'i2']) -def test_integer_params(node_fixture): - def check_params(resp): - nonlocal node_fixture assert 2 == len(resp.values) assert ParameterType.PARAMETER_INTEGER == resp.values[0].type assert ParameterType.PARAMETER_INTEGER == resp.values[1].type assert 42 == resp.values[0].integer_value assert -27 == resp.values[1].integer_value - with NamedTemporaryFile() as yaml_file: - yaml_file.write(""" -initial_params_node: - ros__parameters: - i1: 42 - i2: -27 -""") - yaml_file.flush() - yaml_file.close() - command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = get_params_test(node_fixture['node'], check_params, ('i1', 'i2')) - assert 0 == launch_process_and_coroutine(command, actual_test) +def test_double_params(node_fixture): + param_file_content = """ +double_params: + ros__parameters: + d1: 3.14 + d2: -2.718 +""" + with NamedTemporaryFile(param_file_content) as yaml_file: + command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=double_params') + with HelperCommand(command): + resp = get_params(node_fixture['node'], 'double_params', ['d1', 'd2']) -def test_double_params(node_fixture): - def check_params(resp): - nonlocal node_fixture assert 2 == len(resp.values) assert ParameterType.PARAMETER_DOUBLE == resp.values[0].type assert ParameterType.PARAMETER_DOUBLE == resp.values[1].type assert pytest.approx(3.14) == resp.values[0].double_value assert pytest.approx(-2.718) == resp.values[1].double_value - with NamedTemporaryFile() as yaml_file: - yaml_file.write(""" -initial_params_node: - ros__parameters: - d1: 3.14 - d2: -2.718 -""") - yaml_file.flush() - yaml_file.close() - command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = get_params_test(node_fixture['node'], check_params, ('d1', 'd2')) - assert 0 == launch_process_and_coroutine(command, actual_test) +def test_string_params(node_fixture): + param_file_content = """ +str_params: + ros__parameters: + s1: hello + s2: world +""" + with NamedTemporaryFile(param_file_content) as yaml_file: + command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=str_params') + with HelperCommand(command): + resp = get_params(node_fixture['node'], 'str_params', ['s1', 's2']) -def test_string_params(node_fixture): - def check_params(resp): - nonlocal node_fixture assert 2 == len(resp.values) assert ParameterType.PARAMETER_STRING == resp.values[0].type assert ParameterType.PARAMETER_STRING == resp.values[1].type assert resp.values[0].string_value == 'hello' assert resp.values[1].string_value == 'world' - with NamedTemporaryFile() as yaml_file: - yaml_file.write(""" -initial_params_node: - ros__parameters: - s1: hello - s2: world -""") - yaml_file.flush() - yaml_file.close() - - command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = get_params_test(node_fixture['node'], check_params, ('s1', 's2')) - assert 0 == launch_process_and_coroutine(command, actual_test) - # TODO(sloretz) PARAMETER_BYTE_ARRAY when rcl_yaml_param_parser supports it def test_bool_array_params(node_fixture): - def check_params(resp): - nonlocal node_fixture + param_file_content = """ +ba_params: + ros__parameters: + ba1: [true, false] + ba2: [false, true] +""" + with NamedTemporaryFile(param_file_content) as yaml_file: + command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=ba_params') + + with HelperCommand(command): + resp = get_params(node_fixture['node'], 'ba_params', ['ba1', 'ba2']) + assert 2 == len(resp.values) assert ParameterType.PARAMETER_BOOL_ARRAY == resp.values[0].type assert ParameterType.PARAMETER_BOOL_ARRAY == resp.values[1].type assert resp.values[0].bool_array_value == [True, False] assert resp.values[1].bool_array_value == [False, True] - with NamedTemporaryFile() as yaml_file: - yaml_file.write(""" -initial_params_node: - ros__parameters: - ba1: [true, false] - ba2: [false, true] -""") - yaml_file.flush() - yaml_file.close() - command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = get_params_test(node_fixture['node'], check_params, ('ba1', 'ba2')) - assert 0 == launch_process_and_coroutine(command, actual_test) +def test_integer_array_params(node_fixture): + param_file_content = """ +ia_params: + ros__parameters: + ia1: [42, -27] + ia2: [1234, 5678] +""" + with NamedTemporaryFile(param_file_content) as yaml_file: + command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=ia_params') + with HelperCommand(command): + resp = get_params(node_fixture['node'], 'ia_params', ['ia1', 'ia2']) -def test_integer_array_params(node_fixture): - def check_params(resp): - nonlocal node_fixture assert 2 == len(resp.values) assert ParameterType.PARAMETER_INTEGER_ARRAY == resp.values[0].type assert ParameterType.PARAMETER_INTEGER_ARRAY == resp.values[1].type assert resp.values[0].integer_array_value == [42, -27] assert resp.values[1].integer_array_value == [1234, 5678] - with NamedTemporaryFile() as yaml_file: - yaml_file.write(""" -initial_params_node: - ros__parameters: - ia1: [42, -27] - ia2: [1234, 5678] -""") - yaml_file.flush() - yaml_file.close() - command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = get_params_test(node_fixture['node'], check_params, ('ia1', 'ia2')) - assert 0 == launch_process_and_coroutine(command, actual_test) +def test_double_array_params(node_fixture): + param_file_content = """ +da_params: + ros__parameters: + da1: [3.14, -2.718] + da2: [1234.5, -9999.0] +""" + with NamedTemporaryFile(param_file_content) as yaml_file: + command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=da_params') + with HelperCommand(command): + resp = get_params(node_fixture['node'], 'da_params', ['da1', 'da2']) -def test_double_array_params(node_fixture): - def check_params(resp): - nonlocal node_fixture assert 2 == len(resp.values) assert ParameterType.PARAMETER_DOUBLE_ARRAY == resp.values[0].type assert ParameterType.PARAMETER_DOUBLE_ARRAY == resp.values[1].type assert resp.values[0].double_array_value == pytest.approx([3.14, -2.718]) assert resp.values[1].double_array_value == pytest.approx([1234.5, -9999.0]) - with NamedTemporaryFile() as yaml_file: - yaml_file.write(""" -initial_params_node: - ros__parameters: - da1: [3.14, -2.718] - da2: [1234.5, -9999.0] -""") - yaml_file.flush() - yaml_file.close() - command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = get_params_test(node_fixture['node'], check_params, ('da1', 'da2')) - assert 0 == launch_process_and_coroutine(command, actual_test) +def test_string_array_params(node_fixture): + param_file_content = """ +sa_params: + ros__parameters: + sa1: ['Four', 'score'] + sa2: ['and', 'seven'] +""" + with NamedTemporaryFile(param_file_content) as yaml_file: + command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=sa_params') + with HelperCommand(command): + resp = get_params(node_fixture['node'], 'sa_params', ['sa1', 'sa2']) -def test_string_array_params(node_fixture): - def check_params(resp): - nonlocal node_fixture assert 2 == len(resp.values) assert ParameterType.PARAMETER_STRING_ARRAY == resp.values[0].type assert ParameterType.PARAMETER_STRING_ARRAY == resp.values[1].type assert resp.values[0].string_array_value == ['Four', 'score'] assert resp.values[1].string_array_value == ['and', 'seven'] - with NamedTemporaryFile() as yaml_file: - yaml_file.write(""" -initial_params_node: - ros__parameters: - sa1: ['Four', 'score'] - sa2: ['and', 'seven'] -""") - yaml_file.flush() - yaml_file.close() - - command = (node_fixture['executable'], '__params:=' + yaml_file.name) - actual_test = get_params_test(node_fixture['node'], check_params, ('sa1', 'sa2')) - assert 0 == launch_process_and_coroutine(command, actual_test) - def test_multiple_parameter_files(node_fixture): - def check_params(resp): - nonlocal node_fixture - assert 3 == len(resp.values) - assert ParameterType.PARAMETER_INTEGER == resp.values[0].type - assert ParameterType.PARAMETER_INTEGER == resp.values[1].type - assert ParameterType.PARAMETER_INTEGER == resp.values[2].type - assert 42 == resp.values[0].integer_value - assert 12345 == resp.values[1].integer_value - assert -27 == resp.values[2].integer_value - - with NamedTemporaryFile() as first_yaml_file: - first_yaml_file.write(""" -initial_params_node: + first_yaml_content = """ +multi_params: ros__parameters: i1: 42 i2: -27 -""") - first_yaml_file.flush() - first_yaml_file.close() - with NamedTemporaryFile() as second_yaml_file: - second_yaml_file.write(""" -initial_params_node: +""" + second_yaml_content = """ +multi_params: ros__parameters: i2: 12345 i3: -27 -""") - second_yaml_file.flush() - second_yaml_file.close() +""" + with NamedTemporaryFile(first_yaml_content) as first_yaml_file: + with NamedTemporaryFile(second_yaml_content) as second_yaml_file: command = ( node_fixture['executable'], - '__params:=' + first_yaml_file.name, - '__params:=' + second_yaml_file.name + '__params:=' + first_yaml_file, + '__params:=' + second_yaml_file, + '__node:=multi_params' ) - actual_test = get_params_test(node_fixture['node'], check_params, ('i1', 'i2', 'i3')) - assert 0 == launch_process_and_coroutine(command, actual_test) + with HelperCommand(command): + resp = get_params(node_fixture['node'], 'multi_params', ['i1', 'i2', 'i3']) + + assert 3 == len(resp.values) + assert ParameterType.PARAMETER_INTEGER == resp.values[0].type + assert ParameterType.PARAMETER_INTEGER == resp.values[1].type + assert ParameterType.PARAMETER_INTEGER == resp.values[2].type + assert 42 == resp.values[0].integer_value + assert 12345 == resp.values[1].integer_value + assert -27 == resp.values[2].integer_value diff --git a/test_cli/test/utils.py b/test_cli/test/utils.py index 0533b9dd..f57e3eb3 100644 --- a/test_cli/test/utils.py +++ b/test_cli/test/utils.py @@ -12,14 +12,15 @@ # See the License for the specific language governing permissions and # limitations under the License. +import copy import os import random +import subprocess import sys import tempfile +import threading -from launch.legacy import LaunchDescriptor -from launch.legacy.exit_handler import primary_exit_handler -from launch.legacy.launcher import DefaultLauncher +import rclpy def require_environment_variable(name): @@ -30,49 +31,64 @@ def require_environment_variable(name): return env -def launch_process_and_coroutine(command, coroutine): - """Execute a command and coroutine in parallel.""" - # Execute python files using same python used to start this test - env = dict(os.environ) - if command[0][-3:] == '.py': - command.insert(0, sys.executable) - env['PYTHONUNBUFFERED'] = '1' - - ld = LaunchDescriptor() - ld.add_process( - cmd=command, - name='helper_for_' + coroutine.__name__, - env=env - ) - ld.add_coroutine( - coroutine(), - name=coroutine.__name__, - exit_handler=primary_exit_handler - ) - launcher = DefaultLauncher() - launcher.add_launch_descriptor(ld) - return_code = launcher.launch() - return return_code +class HelperCommand: + """Execute a command in the background.""" + def __init__(self, command): + self._env = dict(os.environ) + self._command = copy.deepcopy(command) -class NamedTemporaryFile: - """ - Create a named temporary file. + # Execute python files using same python used to start this test + if command[0][-3:] == '.py': + self._command.insert(0, sys.executable) + self._env['PYTHONUNBUFFERED'] = '1' + + def __enter__(self): + self._proc = subprocess.Popen(self._command, env=self._env) + return self + + def __exit__(self, t, v, tb): + self._proc.kill() - This allows the file to be closed to allow opening by other processes on windows. - """ - def __init__(self, mode='w'): +class NamedTemporaryFile: + """Create a named temporary file with content.""" + + def __init__(self, content): self._tempdir = tempfile.TemporaryDirectory(prefix='test_cli_') - self._mode = mode + self._content = content def __enter__(self): directory = self._tempdir.__enter__() name = ''.join(random.choice('abcdefghijklmnopqrstuvwxyz') for _ in range(10)) self._filename = os.path.join(directory, name) - self._file = open(self._filename, mode=self._mode) - return self._file + self._file = open(self._filename, mode='w') + self._file.write(self._content) + self._file.flush() + # close so it can be opened again on windows + self._file.close() + return self._file.name def __exit__(self, t, v, tb): - self._file.close() self._tempdir.__exit__(t, v, tb) + + +class BackgroundExecutor: + """Spin an executor in the background.""" + + def __init__(self, node, time_between_spins=0.25): + self._node = node + self._time_between_spins = time_between_spins + + def __enter__(self): + self._stop = threading.Event() + self._thr = threading.Thread(target=self._run, daemon=True) + self._thr.start() + + def _run(self): + while not self._stop.is_set(): + rclpy.spin_once(self._node, timeout_sec=self._time_between_spins) + + def __exit__(self, t, v, tb): + self._stop.set() + self._thr.join() From deb59989c82059923b1fcfa9436476c7e12b9aec Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 7 Jun 2018 15:31:38 -0700 Subject: [PATCH 15/16] NamedTemporaryFile -> TemporaryFileWithContent --- test_cli/test/test_params_yaml.py | 22 +++++++++++----------- test_cli/test/utils.py | 2 +- 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/test_cli/test/test_params_yaml.py b/test_cli/test/test_params_yaml.py index f9cce848..206f0738 100644 --- a/test_cli/test/test_params_yaml.py +++ b/test_cli/test/test_params_yaml.py @@ -19,8 +19,8 @@ from .utils import BackgroundExecutor from .utils import HelperCommand -from .utils import NamedTemporaryFile from .utils import require_environment_variable +from .utils import TemporaryFileWithContent CLIENT_LIBRARY_EXECUTABLES = ( @@ -61,7 +61,7 @@ def test_bool_params(node_fixture): b1: False b2: True """ - with NamedTemporaryFile(param_file_content) as yaml_file: + with TemporaryFileWithContent(param_file_content) as yaml_file: command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=bool_params') with HelperCommand(command): @@ -81,7 +81,7 @@ def test_integer_params(node_fixture): i1: 42 i2: -27 """ - with NamedTemporaryFile(param_file_content) as yaml_file: + with TemporaryFileWithContent(param_file_content) as yaml_file: command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=int_params') with HelperCommand(command): @@ -101,7 +101,7 @@ def test_double_params(node_fixture): d1: 3.14 d2: -2.718 """ - with NamedTemporaryFile(param_file_content) as yaml_file: + with TemporaryFileWithContent(param_file_content) as yaml_file: command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=double_params') with HelperCommand(command): @@ -121,7 +121,7 @@ def test_string_params(node_fixture): s1: hello s2: world """ - with NamedTemporaryFile(param_file_content) as yaml_file: + with TemporaryFileWithContent(param_file_content) as yaml_file: command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=str_params') with HelperCommand(command): @@ -144,7 +144,7 @@ def test_bool_array_params(node_fixture): ba1: [true, false] ba2: [false, true] """ - with NamedTemporaryFile(param_file_content) as yaml_file: + with TemporaryFileWithContent(param_file_content) as yaml_file: command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=ba_params') with HelperCommand(command): @@ -164,7 +164,7 @@ def test_integer_array_params(node_fixture): ia1: [42, -27] ia2: [1234, 5678] """ - with NamedTemporaryFile(param_file_content) as yaml_file: + with TemporaryFileWithContent(param_file_content) as yaml_file: command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=ia_params') with HelperCommand(command): @@ -184,7 +184,7 @@ def test_double_array_params(node_fixture): da1: [3.14, -2.718] da2: [1234.5, -9999.0] """ - with NamedTemporaryFile(param_file_content) as yaml_file: + with TemporaryFileWithContent(param_file_content) as yaml_file: command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=da_params') with HelperCommand(command): @@ -204,7 +204,7 @@ def test_string_array_params(node_fixture): sa1: ['Four', 'score'] sa2: ['and', 'seven'] """ - with NamedTemporaryFile(param_file_content) as yaml_file: + with TemporaryFileWithContent(param_file_content) as yaml_file: command = (node_fixture['executable'], '__params:=' + yaml_file, '__node:=sa_params') with HelperCommand(command): @@ -231,8 +231,8 @@ def test_multiple_parameter_files(node_fixture): i3: -27 """ - with NamedTemporaryFile(first_yaml_content) as first_yaml_file: - with NamedTemporaryFile(second_yaml_content) as second_yaml_file: + with TemporaryFileWithContent(first_yaml_content) as first_yaml_file: + with TemporaryFileWithContent(second_yaml_content) as second_yaml_file: command = ( node_fixture['executable'], '__params:=' + first_yaml_file, diff --git a/test_cli/test/utils.py b/test_cli/test/utils.py index f57e3eb3..55345b02 100644 --- a/test_cli/test/utils.py +++ b/test_cli/test/utils.py @@ -51,7 +51,7 @@ def __exit__(self, t, v, tb): self._proc.kill() -class NamedTemporaryFile: +class TemporaryFileWithContent: """Create a named temporary file with content.""" def __init__(self, content): From 9377eb645f0c811453b704ba3d6740ab2b432fde Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 8 Jun 2018 15:08:55 -0700 Subject: [PATCH 16/16] destroy client after spinning --- test_cli/test/test_params_yaml.py | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/test_cli/test/test_params_yaml.py b/test_cli/test/test_params_yaml.py index 206f0738..3936d99d 100644 --- a/test_cli/test/test_params_yaml.py +++ b/test_cli/test/test_params_yaml.py @@ -44,14 +44,17 @@ def node_fixture(request): def get_params(node, node_name, param_names, wfs_timeout=5.0): + client = node.create_client(GetParameters, '/{name}/get_parameters'.format(name=node_name)) + resp = None with BackgroundExecutor(node): - client = node.create_client(GetParameters, '/{name}/get_parameters'.format(name=node_name)) assert client.wait_for_service(timeout_sec=wfs_timeout) request = GetParameters.Request() request.names = param_names resp = client.call(request) - node.destroy_client(client) - return resp + + # Don't destroy client while spinning ros2/rmw_fastrtps#205 + node.destroy_client(client) + return resp def test_bool_params(node_fixture):