diff --git a/test_cli/CMakeLists.txt b/test_cli/CMakeLists.txt new file mode 100644 index 00000000..e37acb97 --- /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=$ + ) + 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..a1901a62 --- /dev/null +++ b/test_cli/package.xml @@ -0,0 +1,27 @@ + + + + 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 + rcl_interfaces + rclcpp + 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..7a2c5694 --- /dev/null +++ b/test_cli/test/initial_params.cpp @@ -0,0 +1,31 @@ +// 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 "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..3936d99d --- /dev/null +++ b/test_cli/test/test_params_yaml.py @@ -0,0 +1,254 @@ +# 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 pytest +from rcl_interfaces.msg import ParameterType +from rcl_interfaces.srv import GetParameters +import rclpy + +from .utils import BackgroundExecutor +from .utils import HelperCommand +from .utils import require_environment_variable +from .utils import TemporaryFileWithContent + + +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, 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): + assert client.wait_for_service(timeout_sec=wfs_timeout) + request = GetParameters.Request() + request.names = param_names + resp = client.call(request) + + # Don't destroy client while spinning ros2/rmw_fastrtps#205 + node.destroy_client(client) + return resp + + +def test_bool_params(node_fixture): + param_file_content = """ +bool_params: + ros__parameters: + b1: False + b2: True +""" + with TemporaryFileWithContent(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']) + + 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 + + +def test_integer_params(node_fixture): + param_file_content = """ +int_params: + ros__parameters: + i1: 42 + i2: -27 +""" + with TemporaryFileWithContent(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']) + + 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 + + +def test_double_params(node_fixture): + param_file_content = """ +double_params: + ros__parameters: + d1: 3.14 + d2: -2.718 +""" + with TemporaryFileWithContent(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']) + + 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 + + +def test_string_params(node_fixture): + param_file_content = """ +str_params: + ros__parameters: + s1: hello + s2: world +""" + with TemporaryFileWithContent(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']) + + 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' + + +# TODO(sloretz) PARAMETER_BYTE_ARRAY when rcl_yaml_param_parser supports it + + +def test_bool_array_params(node_fixture): + param_file_content = """ +ba_params: + ros__parameters: + ba1: [true, false] + ba2: [false, true] +""" + with TemporaryFileWithContent(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] + + +def test_integer_array_params(node_fixture): + param_file_content = """ +ia_params: + ros__parameters: + ia1: [42, -27] + ia2: [1234, 5678] +""" + with TemporaryFileWithContent(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']) + + 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] + + +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 TemporaryFileWithContent(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']) + + 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]) + + +def test_string_array_params(node_fixture): + param_file_content = """ +sa_params: + ros__parameters: + sa1: ['Four', 'score'] + sa2: ['and', 'seven'] +""" + with TemporaryFileWithContent(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']) + + 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'] + + +def test_multiple_parameter_files(node_fixture): + first_yaml_content = """ +multi_params: + ros__parameters: + i1: 42 + i2: -27 +""" + second_yaml_content = """ +multi_params: + ros__parameters: + i2: 12345 + i3: -27 +""" + + 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, + '__params:=' + second_yaml_file, + '__node:=multi_params' + ) + 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 new file mode 100644 index 00000000..55345b02 --- /dev/null +++ b/test_cli/test/utils.py @@ -0,0 +1,94 @@ +# 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 copy +import os +import random +import subprocess +import sys +import tempfile +import threading + +import rclpy + + +def require_environment_variable(name): + """Get environment variable or raise if it does not exist.""" + env = os.getenv(name) + if env is None: + raise EnvironmentError('Missing environment variable "%s"' % name) + return env + + +class HelperCommand: + """Execute a command in the background.""" + + def __init__(self, command): + self._env = dict(os.environ) + self._command = copy.deepcopy(command) + + # 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() + + +class TemporaryFileWithContent: + """Create a named temporary file with content.""" + + def __init__(self, content): + self._tempdir = tempfile.TemporaryDirectory(prefix='test_cli_') + 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='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._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()