diff --git a/ros2component/package.xml b/ros2component/package.xml
index f740557c3..9821e719d 100644
--- a/ros2component/package.xml
+++ b/ros2component/package.xml
@@ -24,6 +24,8 @@
ament_pep257
ament_xmllint
python3-pytest
+ ros2component_test_fixtures
+ ros_testing
ament_python
diff --git a/ros2component/test/test_cli_list.py b/ros2component/test/test_cli_list.py
new file mode 100644
index 000000000..0fc6d218a
--- /dev/null
+++ b/ros2component/test/test_cli_list.py
@@ -0,0 +1,147 @@
+# Copyright 2019 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 contextlib
+import unittest
+
+from launch import LaunchDescription
+from launch.actions import ExecuteProcess
+from launch.actions import OpaqueFunction
+from launch.actions import TimerAction
+
+from launch_ros.actions import Node
+
+import launch_testing
+import launch_testing.asserts
+import launch_testing.markers
+import launch_testing.tools
+import launch_testing_ros.tools
+
+import pytest
+
+from rmw_implementation import get_available_rmw_implementations
+
+
+@pytest.mark.rostest
+@launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations())
+def generate_test_description(rmw_implementation, ready_fn):
+ additional_env = {'RMW_IMPLEMENTATION': rmw_implementation}
+ container_node_action = Node(
+ package='rclcpp_components', node_executable='component_container', output='screen',
+ additional_env=additional_env)
+
+ talker_two_command_action = ExecuteProcess(
+ cmd=['ros2', 'component', 'load', '/ComponentManager',
+ 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'],
+ additional_env={
+ 'RMW_IMPLEMENTATION': rmw_implementation,
+ 'PYTHONUNBUFFERED': '1'
+ },
+ name='ros2component-cli',
+ output='screen'
+ )
+
+ talker_one_command_action = ExecuteProcess(
+ cmd=['ros2', 'component', 'load', '/ComponentManager',
+ 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'],
+ additional_env={
+ 'RMW_IMPLEMENTATION': rmw_implementation,
+ 'PYTHONUNBUFFERED': '1'
+ },
+ name='ros2component-cli',
+ output='screen',
+ on_exit=[talker_two_command_action]
+ )
+
+ listener_command_action = ExecuteProcess(
+ cmd=['ros2', 'component', 'load', '/ComponentManager',
+ 'ros2component_test_fixtures', 'ros2component_test_fixtures::Listener'],
+ additional_env={
+ 'RMW_IMPLEMENTATION': rmw_implementation,
+ 'PYTHONUNBUFFERED': '1'
+ },
+ name='ros2component-cli',
+ output='screen',
+ on_exit=[talker_one_command_action]
+ )
+
+ return LaunchDescription([
+ # Always restart daemon to isolate tests.
+ ExecuteProcess(
+ cmd=['ros2', 'daemon', 'stop'],
+ name='daemon-stop',
+ on_exit=[
+ ExecuteProcess(
+ cmd=['ros2', 'daemon', 'start'],
+ name='daemon-start',
+ on_exit=[
+ container_node_action,
+ TimerAction(period=3.0, actions=[listener_command_action]),
+ OpaqueFunction(function=lambda context: ready_fn())
+ ],
+ additional_env=additional_env
+ )
+ ]
+ ),
+ ]), locals()
+
+
+class TestROS2ComponentListCLI(unittest.TestCase):
+
+ @classmethod
+ def setUpClass(
+ cls,
+ launch_service,
+ proc_info,
+ proc_output,
+ rmw_implementation
+ ):
+ @contextlib.contextmanager
+ def launch_component_command(self, arguments):
+ component_command_action = ExecuteProcess(
+ cmd=['ros2', 'component', *arguments],
+ additional_env={
+ 'RMW_IMPLEMENTATION': rmw_implementation,
+ 'PYTHONUNBUFFERED': '1'
+ },
+ name='ros2component-cli',
+ output='screen'
+ )
+ with launch_testing.tools.launch_process(
+ launch_service, component_command_action, proc_info, proc_output,
+ output_filter=launch_testing_ros.tools.basic_output_filter(
+ # ignore ros2cli daemon nodes
+ filtered_patterns=['.*ros2cli.*'],
+ filtered_rmw_implementation=rmw_implementation
+ )
+ ) as component_command:
+ yield component_command
+ cls.launch_component_command = launch_component_command
+
+ @launch_testing.markers.retry_on_failure(times=10)
+ def test_list_verb(self):
+ with self.launch_component_command(
+ arguments=['list']) as list_command:
+ assert list_command.wait_for_shutdown(timeout=10)
+ assert list_command.exit_code == launch_testing.asserts.EXIT_OK
+ assert launch_testing.tools.expect_output(
+ expected_lines=[
+ '/ComponentManager',
+ ' 1 /listener',
+ ' 2 /talker',
+ ' 3 /talker'
+ ],
+ text=list_command.output,
+ strict=False
+ )
diff --git a/ros2component/test/test_cli_load.py b/ros2component/test/test_cli_load.py
new file mode 100644
index 000000000..26e395456
--- /dev/null
+++ b/ros2component/test/test_cli_load.py
@@ -0,0 +1,217 @@
+# Copyright 2019 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 contextlib
+import functools
+import unittest
+
+from launch import LaunchDescription
+from launch.actions import ExecuteProcess
+from launch.actions import OpaqueFunction
+
+from launch_ros.actions import Node
+
+import launch_testing
+import launch_testing.asserts
+import launch_testing.markers
+import launch_testing.tools
+import launch_testing_ros.tools
+
+import pytest
+
+from rmw_implementation import get_available_rmw_implementations
+
+
+@pytest.mark.rostest
+@launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations())
+def generate_test_description(rmw_implementation, ready_fn):
+ additional_env = {'RMW_IMPLEMENTATION': rmw_implementation}
+ container_node_action = Node(
+ package='rclcpp_components', node_executable='component_container', output='own_log',
+ output_format='{line}', additional_env=additional_env,
+ name='container_' + rmw_implementation)
+ return LaunchDescription([
+ # Always restart daemon to isolate tests.
+ ExecuteProcess(
+ cmd=['ros2', 'daemon', 'stop'],
+ name='daemon-stop',
+ on_exit=[
+ ExecuteProcess(
+ cmd=['ros2', 'daemon', 'start'],
+ name='daemon-start',
+ on_exit=[
+ container_node_action,
+ OpaqueFunction(function=lambda context: ready_fn())
+ ],
+ additional_env=additional_env
+ )
+ ]
+ ),
+ ]), locals()
+
+
+class TestROS2ComponentLoadCLI(unittest.TestCase):
+
+ @classmethod
+ def setUpClass(
+ cls,
+ launch_service,
+ proc_info,
+ proc_output,
+ rmw_implementation,
+ container_node_action
+ ):
+ @contextlib.contextmanager
+ def launch_component_command(self, arguments):
+ component_command_action = ExecuteProcess(
+ cmd=['ros2', 'component', *arguments],
+ additional_env={
+ 'RMW_IMPLEMENTATION': rmw_implementation,
+ 'PYTHONUNBUFFERED': '1'
+ },
+ name='ros2component-cli',
+ output='screen'
+ )
+ with launch_testing.tools.launch_process(
+ launch_service, component_command_action, proc_info, proc_output,
+ output_filter=launch_testing_ros.tools.basic_output_filter(
+ # ignore ros2cli daemon nodes
+ filtered_patterns=['.*ros2cli.*'],
+ filtered_rmw_implementation=rmw_implementation
+ )
+ ) as component_command:
+ yield component_command
+ cls.launch_component_command = launch_component_command
+ cls.container_node_action = launch_testing.tools.ProcessProxy(
+ container_node_action, proc_info, proc_output,
+ output_filter=launch_testing_ros.tools.basic_output_filter(
+ # ignore ros2cli daemon nodes
+ filtered_patterns=['.*ros2cli.*'],
+ filtered_rmw_implementation=rmw_implementation
+ )
+ )
+
+ @launch_testing.markers.retry_on_failure(times=2)
+ def test_load_verb(self):
+ with self.launch_component_command(
+ arguments=[
+ 'load', '/ComponentManager',
+ 'ros2component_test_fixtures',
+ 'ros2component_test_fixtures::Talker']) as load_command:
+ assert load_command.wait_for_shutdown(timeout=20)
+ assert load_command.exit_code == launch_testing.asserts.EXIT_OK
+ assert launch_testing.tools.expect_output(
+ expected_lines=[
+ "Loaded component 1 into '/ComponentManager' "
+ "container node as '/talker'"],
+ text=load_command.output,
+ strict=False
+ )
+ assert self.container_node_action.wait_for_output(functools.partial(
+ launch_testing.tools.expect_output, expected_lines=[
+ "[INFO] [talker]: Publishing: 'Hello World'"
+ ], strict=False
+ ), timeout=10)
+ with self.launch_component_command(
+ arguments=[
+ 'load', '/ComponentManager',
+ 'ros2component_test_fixtures',
+ 'ros2component_test_fixtures::Listener']) as load_command:
+ assert load_command.wait_for_shutdown(timeout=20)
+ assert load_command.exit_code == launch_testing.asserts.EXIT_OK
+ assert launch_testing.tools.expect_output(
+ expected_lines=[
+ "Loaded component 2 into '/ComponentManager' "
+ "container node as '/listener'"],
+ text=load_command.output,
+ strict=False
+ )
+ with self.launch_component_command(
+ arguments=[
+ 'unload', '/ComponentManager', '1']) as unload_command:
+ assert unload_command.wait_for_shutdown(timeout=20)
+ assert unload_command.exit_code == launch_testing.asserts.EXIT_OK
+ assert launch_testing.tools.expect_output(
+ expected_lines=["Unloaded component 1 from '/ComponentManager' container"],
+ text=unload_command.output,
+ strict=False
+ )
+ # Test the unique id for loaded nodes.
+ with self.launch_component_command(
+ arguments=[
+ 'load', '/ComponentManager',
+ 'ros2component_test_fixtures',
+ 'ros2component_test_fixtures::Talker']) as load_command:
+ assert load_command.wait_for_shutdown(timeout=20)
+ assert load_command.exit_code == launch_testing.asserts.EXIT_OK
+ assert launch_testing.tools.expect_output(
+ expected_lines=[
+ "Loaded component 3 into '/ComponentManager' "
+ "container node as '/talker'"],
+ text=load_command.output,
+ strict=False
+ )
+ # Test we can load the same node more than once.
+ with self.launch_component_command(
+ arguments=[
+ 'load', '/ComponentManager',
+ 'ros2component_test_fixtures',
+ 'ros2component_test_fixtures::Talker']) as load_command:
+ assert load_command.wait_for_shutdown(timeout=20)
+ assert self.container_node_action.wait_for_output(functools.partial(
+ launch_testing.tools.expect_output, expected_lines=[
+ "[INFO] [talker]: Publishing: 'Hello World'"
+ ] * 3, strict=False
+ ), timeout=10)
+ assert load_command.exit_code == launch_testing.asserts.EXIT_OK
+ assert launch_testing.tools.expect_output(
+ expected_lines=[
+ "Loaded component 4 into '/ComponentManager' "
+ "container node as '/talker'"],
+ text=load_command.output,
+ strict=False
+ )
+
+ @launch_testing.markers.retry_on_failure(times=2)
+ def test_load_nonexistent_component(self):
+ with self.launch_component_command(
+ arguments=[
+ 'load', '/ComponentManager',
+ 'ros2component_test_fixtures',
+ 'ros2component_test_fixtures::NonExistentComponent']) as load_command:
+ assert load_command.wait_for_shutdown(timeout=20)
+ assert load_command.exit_code == 1
+ assert launch_testing.tools.expect_output(
+ expected_lines=[
+ 'Failed to load component: '
+ 'Failed to find class with the requested plugin name.'],
+ text=load_command.output,
+ strict=False
+ )
+
+ @launch_testing.markers.retry_on_failure(times=2)
+ def test_load_nonexistent_plugin(self):
+ with self.launch_component_command(
+ arguments=[
+ 'load', '/ComponentManager',
+ 'non_existent_plugin', 'non_existent_plugin::Test']) as load_command:
+ assert load_command.wait_for_shutdown(timeout=20)
+ assert load_command.exit_code == 1
+ assert launch_testing.tools.expect_output(
+ expected_lines=[
+ 'Failed to load component: '
+ 'Could not find requested resource in ament index'],
+ text=load_command.output,
+ strict=False
+ )
diff --git a/ros2component/test/test_cli_types.py b/ros2component/test/test_cli_types.py
new file mode 100644
index 000000000..e96b8c40c
--- /dev/null
+++ b/ros2component/test/test_cli_types.py
@@ -0,0 +1,97 @@
+# Copyright 2019 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 contextlib
+import unittest
+
+from launch import LaunchDescription
+from launch.actions import ExecuteProcess
+from launch.actions import OpaqueFunction
+
+import launch_testing
+import launch_testing.asserts
+import launch_testing.markers
+import launch_testing.tools
+
+import pytest
+
+from rmw_implementation import get_available_rmw_implementations
+
+
+@pytest.mark.rostest
+@launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations())
+@launch_testing.markers.keep_alive
+def generate_test_description(rmw_implementation, ready_fn):
+ return LaunchDescription([
+ # Always restart daemon to isolate tests.
+ ExecuteProcess(
+ cmd=['ros2', 'daemon', 'stop'],
+ name='daemon-stop',
+ on_exit=[
+ ExecuteProcess(
+ cmd=['ros2', 'daemon', 'start'],
+ name='daemon-start',
+ on_exit=[
+ OpaqueFunction(function=lambda context: ready_fn())
+ ],
+ additional_env={'RMW_IMPLEMENTATION': rmw_implementation}
+ )
+ ]
+ )
+ ])
+
+
+class TestROS2ComponentTypesCLI(unittest.TestCase):
+
+ @classmethod
+ def setUpClass(
+ cls,
+ launch_service,
+ proc_info,
+ proc_output,
+ rmw_implementation
+ ):
+ @contextlib.contextmanager
+ def launch_component_command(self, arguments):
+ component_command_action = ExecuteProcess(
+ cmd=['ros2', 'component', *arguments],
+ additional_env={
+ 'RMW_IMPLEMENTATION': rmw_implementation,
+ 'PYTHONUNBUFFERED': '1'
+ },
+ name='ros2component-cli',
+ output='screen'
+ )
+ with launch_testing.tools.launch_process(
+ launch_service, component_command_action, proc_info, proc_output
+ ) as component_command:
+ yield component_command
+ cls.launch_component_command = launch_component_command
+
+ # Set verb tests
+ @launch_testing.markers.retry_on_failure(times=3)
+ def test_types_verb(self):
+ with self.launch_component_command(
+ arguments=['types']) as component_command:
+ assert component_command.wait_for_shutdown(timeout=20)
+ assert component_command.exit_code == launch_testing.asserts.EXIT_OK
+ assert launch_testing.tools.expect_output(
+ expected_lines=[
+ 'ros2component_test_fixtures',
+ ' ros2component_test_fixtures::Talker',
+ ' ros2component_test_fixtures::Listener'
+ ],
+ text=component_command.output,
+ strict=True
+ )
diff --git a/ros2component/test/test_cli_unload.py b/ros2component/test/test_cli_unload.py
new file mode 100644
index 000000000..284671dc2
--- /dev/null
+++ b/ros2component/test/test_cli_unload.py
@@ -0,0 +1,174 @@
+# Copyright 2019 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 contextlib
+import unittest
+
+from launch import LaunchDescription
+from launch.actions import ExecuteProcess
+from launch.actions import OpaqueFunction
+from launch.actions import TimerAction
+
+from launch_ros.actions import Node
+
+import launch_testing
+import launch_testing.asserts
+import launch_testing.markers
+import launch_testing.tools
+import launch_testing_ros.tools
+
+import pytest
+
+from rmw_implementation import get_available_rmw_implementations
+
+NON_EXISTENT_ID = [
+ "Failed to unload component 5 from '/ComponentManager' container node",
+ ' No node found with unique_id: 5'
+]
+
+
+@pytest.mark.rostest
+@launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations())
+def generate_test_description(rmw_implementation, ready_fn):
+ additional_env = {'RMW_IMPLEMENTATION': rmw_implementation}
+ container_node_action = Node(
+ package='rclcpp_components', node_executable='component_container', output='screen',
+ additional_env=additional_env)
+
+ talker_two_command_action = ExecuteProcess(
+ cmd=['ros2', 'component', 'load', '/ComponentManager',
+ 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'],
+ additional_env={
+ 'RMW_IMPLEMENTATION': rmw_implementation,
+ 'PYTHONUNBUFFERED': '1'
+ },
+ name='ros2component-cli',
+ output='screen'
+ )
+
+ talker_one_command_action = ExecuteProcess(
+ cmd=['ros2', 'component', 'load', '/ComponentManager',
+ 'ros2component_test_fixtures', 'ros2component_test_fixtures::Talker'],
+ additional_env={
+ 'RMW_IMPLEMENTATION': rmw_implementation,
+ 'PYTHONUNBUFFERED': '1'
+ },
+ name='ros2component-cli',
+ output='screen',
+ on_exit=[talker_two_command_action]
+ )
+
+ listener_command_action = ExecuteProcess(
+ cmd=['ros2', 'component', 'load', '/ComponentManager',
+ 'ros2component_test_fixtures', 'ros2component_test_fixtures::Listener'],
+ additional_env={
+ 'RMW_IMPLEMENTATION': rmw_implementation,
+ 'PYTHONUNBUFFERED': '1'
+ },
+ name='ros2component-cli',
+ output='screen',
+ on_exit=[talker_one_command_action]
+ )
+
+ return LaunchDescription([
+ # Always restart daemon to isolate tests.
+ ExecuteProcess(
+ cmd=['ros2', 'daemon', 'stop'],
+ name='daemon-stop',
+ on_exit=[
+ ExecuteProcess(
+ cmd=['ros2', 'daemon', 'start'],
+ name='daemon-start',
+ on_exit=[
+ container_node_action,
+ TimerAction(period=3.0, actions=[listener_command_action]),
+ OpaqueFunction(function=lambda context: ready_fn())
+ ],
+ additional_env=additional_env
+ )
+ ]
+ ),
+ ]), locals()
+
+
+class TestROS2ComponentUnloadCLI(unittest.TestCase):
+
+ @classmethod
+ def setUpClass(
+ cls,
+ launch_service,
+ proc_info,
+ proc_output,
+ rmw_implementation
+ ):
+ @contextlib.contextmanager
+ def launch_component_command(self, arguments):
+ component_command_action = ExecuteProcess(
+ cmd=['ros2', 'component', *arguments],
+ additional_env={
+ 'RMW_IMPLEMENTATION': rmw_implementation,
+ 'PYTHONUNBUFFERED': '1'
+ },
+ name='ros2component-cli',
+ output='screen'
+ )
+ with launch_testing.tools.launch_process(
+ launch_service, component_command_action, proc_info, proc_output,
+ output_filter=launch_testing_ros.tools.basic_output_filter(
+ # ignore ros2cli daemon nodes
+ filtered_patterns=['.*ros2cli.*'],
+ filtered_rmw_implementation=rmw_implementation
+ )
+ ) as component_command:
+ yield component_command
+ cls.launch_component_command = launch_component_command
+
+ @launch_testing.markers.retry_on_failure(times=10)
+ def test_unload_verb(self):
+ with self.launch_component_command(
+ arguments=[
+ 'unload', '/ComponentManager', '1']) as unload_command:
+ assert unload_command.wait_for_shutdown(timeout=10)
+ assert unload_command.exit_code == launch_testing.asserts.EXIT_OK
+ assert launch_testing.tools.expect_output(
+ expected_lines=["Unloaded component 1 from '/ComponentManager' container"],
+ text=unload_command.output,
+ strict=False
+ )
+
+ @launch_testing.markers.retry_on_failure(times=4)
+ def test_unload_verb_nonexistent_id(self):
+ with self.launch_component_command(
+ arguments=[
+ 'unload', '/ComponentManager', '5']) as unload_command:
+ assert unload_command.wait_for_shutdown(timeout=20)
+ assert unload_command.exit_code == 1
+ assert launch_testing.tools.expect_output(
+ expected_lines=NON_EXISTENT_ID,
+ text=unload_command.output,
+ strict=False
+ )
+
+ @launch_testing.markers.retry_on_failure(times=4)
+ def test_unload_verb_nonexistent_container(self):
+ with self.launch_component_command(
+ arguments=[
+ 'unload', '/NonExistentContainer', '5']) as unload_command:
+ assert unload_command.wait_for_shutdown(timeout=20)
+ assert unload_command.exit_code == 1
+ assert launch_testing.tools.expect_output(
+ expected_lines=["Unable to find container node '/NonExistentContainer'"],
+ text=unload_command.output,
+ strict=False
+ )
diff --git a/ros2component_test_fixtures/CMakeLists.txt b/ros2component_test_fixtures/CMakeLists.txt
new file mode 100644
index 000000000..8f4d15e64
--- /dev/null
+++ b/ros2component_test_fixtures/CMakeLists.txt
@@ -0,0 +1,55 @@
+cmake_minimum_required(VERSION 3.5)
+
+project(ros2component_test_fixtures)
+
+# Default to C++14
+if(NOT CMAKE_CXX_STANDARD)
+ set(CMAKE_CXX_STANDARD 14)
+endif()
+
+if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
+ add_compile_options(-Wall -Wextra -Wpedantic)
+endif()
+
+find_package(ament_cmake REQUIRED)
+find_package(rclcpp REQUIRED)
+find_package(rclcpp_components REQUIRED)
+find_package(std_msgs REQUIRED)
+
+include_directories(include)
+
+add_library(talker_component SHARED
+ src/talker_component.cpp)
+target_compile_definitions(talker_component
+ PRIVATE "ros2component_test_fixtures_BUILDING_DLL")
+ament_target_dependencies(talker_component
+ "rclcpp"
+ "rclcpp_components"
+ "std_msgs")
+rclcpp_components_register_nodes(talker_component "ros2component_test_fixtures::Talker")
+
+add_library(listener_component SHARED
+ src/listener_component.cpp)
+target_compile_definitions(listener_component
+ PRIVATE "ros2component_test_fixtures_BUILDING_DLL")
+ament_target_dependencies(listener_component
+ "rclcpp"
+ "rclcpp_components"
+ "std_msgs")
+rclcpp_components_register_nodes(listener_component "ros2component_test_fixtures::Listener")
+
+# since the package installs libraries without exporting them
+# it needs to make sure that the library path is being exported
+if(NOT WIN32)
+ ament_environment_hooks(
+ "${ament_cmake_package_templates_ENVIRONMENT_HOOK_LIBRARY_PATH}")
+endif()
+
+install(TARGETS
+ talker_component
+ listener_component
+ ARCHIVE DESTINATION lib
+ LIBRARY DESTINATION lib
+ RUNTIME DESTINATION bin)
+
+ament_package()
diff --git a/ros2component_test_fixtures/include/ros2component_test_fixtures/listener_component.hpp b/ros2component_test_fixtures/include/ros2component_test_fixtures/listener_component.hpp
new file mode 100644
index 000000000..72dc01fd7
--- /dev/null
+++ b/ros2component_test_fixtures/include/ros2component_test_fixtures/listener_component.hpp
@@ -0,0 +1,37 @@
+// Copyright 2019 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.
+
+#ifndef ROS2COMPONENT_TEST_FIXTURES__LISTENER_COMPONENT_HPP_
+#define ROS2COMPONENT_TEST_FIXTURES__LISTENER_COMPONENT_HPP_
+
+#include "ros2component_test_fixtures/visibility_control.h"
+#include "rclcpp/rclcpp.hpp"
+#include "std_msgs/msg/string.hpp"
+
+namespace ros2component_test_fixtures
+{
+
+class Listener : public rclcpp::Node
+{
+public:
+ ROS2COMPONENT_TEST_FIXTURES_PUBLIC
+ explicit Listener(const rclcpp::NodeOptions & options);
+
+private:
+ rclcpp::Subscription::SharedPtr sub_;
+};
+
+} // namespace ros2component_test_fixtures
+
+#endif // ROS2COMPONENT_TEST_FIXTURES__LISTENER_COMPONENT_HPP_
diff --git a/ros2component_test_fixtures/include/ros2component_test_fixtures/talker_component.hpp b/ros2component_test_fixtures/include/ros2component_test_fixtures/talker_component.hpp
new file mode 100644
index 000000000..8ca6fc880
--- /dev/null
+++ b/ros2component_test_fixtures/include/ros2component_test_fixtures/talker_component.hpp
@@ -0,0 +1,37 @@
+// Copyright 2019 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.
+
+#ifndef ROS2COMPONENT_TEST_FIXTURES__TALKER_COMPONENT_HPP_
+#define ROS2COMPONENT_TEST_FIXTURES__TALKER_COMPONENT_HPP_
+
+#include "ros2component_test_fixtures/visibility_control.h"
+#include "rclcpp/rclcpp.hpp"
+#include "std_msgs/msg/string.hpp"
+
+namespace ros2component_test_fixtures
+{
+
+class Talker : public rclcpp::Node
+{
+public:
+ ROS2COMPONENT_TEST_FIXTURES_PUBLIC
+ explicit Talker(const rclcpp::NodeOptions & options);
+
+private:
+ rclcpp::Publisher::SharedPtr pub_;
+};
+
+} // namespace ros2component_test_fixtures
+
+#endif // ROS2COMPONENT_TEST_FIXTURES__TALKER_COMPONENT_HPP_
diff --git a/ros2component_test_fixtures/include/ros2component_test_fixtures/visibility_control.h b/ros2component_test_fixtures/include/ros2component_test_fixtures/visibility_control.h
new file mode 100644
index 000000000..739f9c929
--- /dev/null
+++ b/ros2component_test_fixtures/include/ros2component_test_fixtures/visibility_control.h
@@ -0,0 +1,58 @@
+// Copyright 2019 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.
+
+#ifndef ROS2COMPONENT_TEST_FIXTURES__VISIBILITY_CONTROL_H_
+#define ROS2COMPONENT_TEST_FIXTURES__VISIBILITY_CONTROL_H_
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+// This logic was borrowed (then namespaced) from the examples on the gcc wiki:
+// https://gcc.gnu.org/wiki/Visibility
+
+#if defined _WIN32 || defined __CYGWIN__
+ #ifdef __GNUC__
+ #define ROS2COMPONENT_TEST_FIXTURES_EXPORT __attribute__ ((dllexport))
+ #define ROS2COMPONENT_TEST_FIXTURES_IMPORT __attribute__ ((dllimport))
+ #else
+ #define ROS2COMPONENT_TEST_FIXTURES_EXPORT __declspec(dllexport)
+ #define ROS2COMPONENT_TEST_FIXTURES_IMPORT __declspec(dllimport)
+ #endif
+ #ifdef ROS2COMPONENT_TEST_FIXTURES_BUILDING_DLL
+ #define ROS2COMPONENT_TEST_FIXTURES_PUBLIC ROS2COMPONENT_TEST_FIXTURES_EXPORT
+ #else
+ #define ROS2COMPONENT_TEST_FIXTURES_PUBLIC ROS2COMPONENT_TEST_FIXTURES_IMPORT
+ #endif
+ #define ROS2COMPONENT_TEST_FIXTURES_PUBLIC_TYPE ROS2COMPONENT_TEST_FIXTURES_PUBLIC
+ #define ROS2COMPONENT_TEST_FIXTURES_LOCAL
+#else
+ #define ROS2COMPONENT_TEST_FIXTURES_EXPORT __attribute__ ((visibility("default")))
+ #define ROS2COMPONENT_TEST_FIXTURES_IMPORT
+ #if __GNUC__ >= 4
+ #define ROS2COMPONENT_TEST_FIXTURES_PUBLIC __attribute__ ((visibility("default")))
+ #define ROS2COMPONENT_TEST_FIXTURES_LOCAL __attribute__ ((visibility("hidden")))
+ #else
+ #define ROS2COMPONENT_TEST_FIXTURES_PUBLIC
+ #define ROS2COMPONENT_TEST_FIXTURES_LOCAL
+ #endif
+ #define ROS2COMPONENT_TEST_FIXTURES_PUBLIC_TYPE
+#endif
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif // ROS2COMPONENT_TEST_FIXTURES__VISIBILITY_CONTROL_H_
diff --git a/ros2component_test_fixtures/package.xml b/ros2component_test_fixtures/package.xml
new file mode 100644
index 000000000..6cacada7f
--- /dev/null
+++ b/ros2component_test_fixtures/package.xml
@@ -0,0 +1,27 @@
+
+
+
+ ros2component_test_fixtures
+ 0.1.0
+ Examples for ros2component cli
+ Dirk Thomas
+ Apache License 2.0
+
+ ament_cmake
+
+ rclcpp
+ rclcpp_components
+ std_msgs
+
+ rclcpp
+ rclcpp_components
+ std_msgs
+
+ ament_cmake_pytest
+ ament_lint_auto
+ ament_lint_common
+
+
+ ament_cmake
+
+
diff --git a/ros2component_test_fixtures/src/listener_component.cpp b/ros2component_test_fixtures/src/listener_component.cpp
new file mode 100644
index 000000000..3f0bf1e80
--- /dev/null
+++ b/ros2component_test_fixtures/src/listener_component.cpp
@@ -0,0 +1,55 @@
+// Copyright 2019 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 "ros2component_test_fixtures/listener_component.hpp"
+
+#include
+#include
+
+#include "rclcpp/rclcpp.hpp"
+#include "std_msgs/msg/string.hpp"
+
+namespace ros2component_test_fixtures
+{
+
+// Create a Listener "component" that subclasses the generic rclcpp::Node base class.
+// Components get built into shared libraries and as such do not write their own main functions.
+// The process using the component's shared library will instantiate the class as a ROS node.
+Listener::Listener(const rclcpp::NodeOptions & options)
+: Node("listener", options)
+{
+ // Create a callback function for when messages are received.
+ // Variations of this function also exist using, for example, UniquePtr for zero-copy transport.
+ auto callback =
+ [this](const typename std_msgs::msg::String::SharedPtr msg) -> void
+ {
+ RCLCPP_INFO(this->get_logger(), "I heard: [%s]", msg->data.c_str());
+ std::flush(std::cout);
+ };
+
+ // Create a subscription to the "chatter" topic which can be matched with one or more
+ // compatible ROS publishers.
+ // Note that not all publishers on the same topic with the same type will be compatible:
+ // they must have compatible Quality of Service policies.
+ sub_ = create_subscription("chatter", 10, callback);
+}
+
+} // namespace ros2component_test_fixtures
+
+#include "rclcpp_components/register_node_macro.hpp"
+
+// Register the component with class_loader.
+// This acts as a sort of entry point, allowing the component to be discoverable when its library
+// is being loaded into a running process.
+RCLCPP_COMPONENTS_REGISTER_NODE(ros2component_test_fixtures::Listener)
diff --git a/ros2component_test_fixtures/src/talker_component.cpp b/ros2component_test_fixtures/src/talker_component.cpp
new file mode 100644
index 000000000..cbac9bd01
--- /dev/null
+++ b/ros2component_test_fixtures/src/talker_component.cpp
@@ -0,0 +1,56 @@
+// Copyright 2019 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 "ros2component_test_fixtures/talker_component.hpp"
+
+#include
+#include
+#include
+#include
+
+#include "rclcpp/rclcpp.hpp"
+#include "std_msgs/msg/string.hpp"
+
+using namespace std::chrono_literals;
+
+namespace ros2component_test_fixtures
+{
+
+// Create a Talker "component" that subclasses the generic rclcpp::Node base class.
+// Components get built into shared libraries and as such do not write their own main functions.
+// The process using the component's shared library will instantiate the class as a ROS node.
+Talker::Talker(const rclcpp::NodeOptions & options)
+: Node("talker", options)
+{
+ // Create a publisher of "std_mgs/String" messages on the "chatter" topic.
+ pub_ = create_publisher("chatter", 10);
+
+ auto msg = std::make_unique();
+ msg->data = "Hello World";
+ RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", msg->data.c_str());
+ std::flush(std::cout);
+
+ // Put the message into a queue to be processed by the middleware.
+ // This call is non-blocking.
+ pub_->publish(std::move(msg));
+}
+
+} // namespace ros2component_test_fixtures
+
+#include "rclcpp_components/register_node_macro.hpp"
+
+// Register the component with class_loader.
+// This acts as a sort of entry point, allowing the component to be discoverable when its library
+// is being loaded into a running process.
+RCLCPP_COMPONENTS_REGISTER_NODE(ros2component_test_fixtures::Talker)