Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Test initializing parameters from command line #274

Merged
merged 16 commits into from
Jun 9, 2018
Merged
Show file tree
Hide file tree
Changes from 14 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
35 changes: 35 additions & 0 deletions test_cli/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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=$<TARGET_FILE:initial_params_rclcpp>
)
set_tests_properties(test_params_yaml
PROPERTIES DEPENDS
initial_params_rclcpp)
endif()

ament_auto_package()
27 changes: 27 additions & 0 deletions test_cli/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>test_cli</name>
<version>0.4.0</version>
<description>
Test command line arguments passed to ros2 executables.
</description>
<maintainer email="[email protected]">Shane Loretz</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake_auto</buildtool_depend>

<build_depend>ament_cmake</build_depend>

<test_depend>ament_cmake_pytest</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>launch</test_depend>
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Seems like an unused dependency?

<test_depend>rcl_interfaces</test_depend>
<test_depend>rclcpp</test_depend>
<test_depend>rclpy</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
Empty file added test_cli/test/__init__.py
Empty file.
31 changes: 31 additions & 0 deletions test_cli/test/initial_params.cpp
Original file line number Diff line number Diff line change
@@ -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 <string>

#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;
}
251 changes: 251 additions & 0 deletions test_cli/test/test_params_yaml.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,251 @@
# 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 NamedTemporaryFile
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, 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
resp = client.call(request)
node.destroy_client(client)
return resp


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'])

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 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'])

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 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'])

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 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'])

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 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]


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'])

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 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'])

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 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'])

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 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,
'__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
Loading