From 05e3624937fc69bf9ca501dad0d03433de8a5f1a Mon Sep 17 00:00:00 2001 From: Brian Ezequiel Marchi Date: Mon, 28 Oct 2019 10:18:40 -0300 Subject: [PATCH 1/7] Add delay after node creation to ensure discovery for other rmw implementations Signed-off-by: Brian Ezequiel Marchi --- .../sros2/commands/security/verbs/test_generate_policy.py | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py index bc8158bd..e713882c 100644 --- a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py +++ b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py @@ -14,6 +14,7 @@ import os import tempfile +import time import pytest @@ -36,7 +37,8 @@ def test_generate_policy_topics(): node.create_publisher(String, 'test_generate_policy_topics_pub', 1) node.create_subscription( String, 'test_generate_policy_topics_sub', lambda msg: None, 1) - + # Give time to some rmw implementations to advertise the nodes + time.sleep(.500) # Generate the policy for the running node assert cli.main( argv=['security', 'generate_policy', os.path.join(tmpdir, 'test-policy.xml')]) == 0 @@ -77,7 +79,8 @@ def test_generate_policy_services(): node.create_client(Trigger, 'test_generate_policy_services_client') node.create_service(Trigger, 'test_generate_policy_services_server', lambda request, response: response) - + # Give time to some rmw implementations to advertise the nodes + time.sleep(.500) # Generate the policy for the running node assert cli.main( argv=['security', 'generate_policy', os.path.join(tmpdir, 'test-policy.xml')]) == 0 From 6aba460fb676ea4e906244ad519486d41ed29d46 Mon Sep 17 00:00:00 2001 From: Brian Ezequiel Marchi Date: Wed, 27 Nov 2019 18:06:13 -0300 Subject: [PATCH 2/7] Make use of launch_testing to test policies Signed-off-by: Brian Ezequiel Marchi --- sros2/package.xml | 1 + .../verbs/fixtures/client_service_node.py | 55 ++++ .../security/verbs/fixtures/pub_sub_node.py | 55 ++++ .../security/verbs/test_generate_policy.py | 274 +++++++++++------- .../verbs/test_generate_policy_no_nodes.py | 26 ++ 5 files changed, 301 insertions(+), 110 deletions(-) create mode 100644 sros2/test/sros2/commands/security/verbs/fixtures/client_service_node.py create mode 100644 sros2/test/sros2/commands/security/verbs/fixtures/pub_sub_node.py create mode 100644 sros2/test/sros2/commands/security/verbs/test_generate_policy_no_nodes.py diff --git a/sros2/package.xml b/sros2/package.xml index 2ef57ea1..8f665a77 100644 --- a/sros2/package.xml +++ b/sros2/package.xml @@ -22,6 +22,7 @@ ament_mypy ament_pep257 python3-pytest + ros_testing std_msgs std_srvs diff --git a/sros2/test/sros2/commands/security/verbs/fixtures/client_service_node.py b/sros2/test/sros2/commands/security/verbs/fixtures/client_service_node.py new file mode 100644 index 00000000..660c974d --- /dev/null +++ b/sros2/test/sros2/commands/security/verbs/fixtures/client_service_node.py @@ -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. + +import sys + +import rclpy +from rclpy.node import Node + +from std_srvs.srv import Trigger + + +class ClientServiceNode(Node): + + def __init__(self): + super().__init__('test_generate_policy_services_node') + self.client = self.create_client(Trigger, 'test_generate_policy_services_client') + self.service = self.create_service( + Trigger, 'test_generate_policy_services_server', lambda request, response: response) + + def destroy_node(self): + self.client.destroy() + self.service.destroy() + super().destroy_node() + + +def main(args=None): + rclpy.init(args=args) + + node = ClientServiceNode() + + try: + rclpy.spin(node) + except KeyboardInterrupt: + print('node stopped cleanly') + except BaseException: + print('exception in node:', file=sys.stderr) + raise + finally: + node.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/sros2/test/sros2/commands/security/verbs/fixtures/pub_sub_node.py b/sros2/test/sros2/commands/security/verbs/fixtures/pub_sub_node.py new file mode 100644 index 00000000..fbea35d1 --- /dev/null +++ b/sros2/test/sros2/commands/security/verbs/fixtures/pub_sub_node.py @@ -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. + +import sys + +import rclpy +from rclpy.node import Node + +from std_msgs.msg import String + + +class PubSubNode(Node): + + def __init__(self): + super().__init__('test_generate_policy_topics_node') + self.publisher = self.create_publisher(String, 'test_generate_policy_topics_pub', 1) + self.subscription = self.create_subscription( + String, 'test_generate_policy_topics_sub', lambda msg: None, 1) + + def destroy_node(self): + self.publisher.destroy() + self.subscription.destroy() + super().destroy_node() + + +def main(args=None): + rclpy.init(args=args) + + node = PubSubNode() + + try: + rclpy.spin(node) + except KeyboardInterrupt: + print('node stopped cleanly') + except BaseException: + print('exception in node:', file=sys.stderr) + raise + finally: + node.destroy_node() + rclpy.shutdown() + + +if __name__ == '__main__': + main() diff --git a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py index e713882c..f9db7295 100644 --- a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py +++ b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py @@ -12,119 +12,173 @@ # See the License for the specific language governing permissions and # limitations under the License. +import contextlib import os +import sys import tempfile -import time +import unittest + +from launch import LaunchDescription +from launch.actions import ExecuteProcess +from launch_ros.actions import Node + +import launch_testing +from launch_testing.actions import ReadyToTest +import launch_testing.asserts +import launch_testing.markers +import launch_testing.tools +import launch_testing_ros.tools import pytest -import rclpy -from ros2cli import cli +from rmw_implementation import get_available_rmw_implementations from sros2.policy import load_policy -from std_msgs.msg import String -from std_srvs.srv import Trigger - - -def test_generate_policy_topics(): - with tempfile.TemporaryDirectory() as tmpdir: - # Create a test-specific context so that generate_policy can still init - context = rclpy.Context() - rclpy.init(context=context) - node = rclpy.create_node('test_generate_policy_topics_node', context=context) - - try: - # Create a publisher and subscription - node.create_publisher(String, 'test_generate_policy_topics_pub', 1) - node.create_subscription( - String, 'test_generate_policy_topics_sub', lambda msg: None, 1) - # Give time to some rmw implementations to advertise the nodes - time.sleep(.500) - # Generate the policy for the running node - assert cli.main( - argv=['security', 'generate_policy', os.path.join(tmpdir, 'test-policy.xml')]) == 0 - finally: - node.destroy_node() - rclpy.shutdown(context=context) - - # Load the policy and pull out the allowed publications and subscriptions - policy = load_policy(os.path.join(tmpdir, 'test-policy.xml')) - profile = policy.find( - path='profiles/profile[@ns="/"][@node="test_generate_policy_topics_node"]') - assert profile is not None - topics_publish_allowed = profile.find(path='topics[@publish="ALLOW"]') - assert topics_publish_allowed is not None - topics_subscribe_allowed = profile.find(path='topics[@subscribe="ALLOW"]') - assert topics_subscribe_allowed is not None - - # Verify that the allowed publications include topic_pub and not topic_sub - topics = topics_publish_allowed.findall('topic') - assert len([t for t in topics if t.text == 'test_generate_policy_topics_pub']) == 1 - assert len([t for t in topics if t.text == 'test_generate_policy_topics_sub']) == 0 - - # Verify that the allowed subscriptions include topic_sub and not topic_pub - topics = topics_subscribe_allowed.findall('topic') - assert len([t for t in topics if t.text == 'test_generate_policy_topics_sub']) == 1 - assert len([t for t in topics if t.text == 'test_generate_policy_topics_pub']) == 0 - - -def test_generate_policy_services(): - with tempfile.TemporaryDirectory() as tmpdir: - # Create a test-specific context so that generate_policy can still init - context = rclpy.Context() - rclpy.init(context=context) - node = rclpy.create_node('test_generate_policy_services_node', context=context) - - try: - # Create a server and client - node.create_client(Trigger, 'test_generate_policy_services_client') - node.create_service(Trigger, 'test_generate_policy_services_server', lambda request, - response: response) - # Give time to some rmw implementations to advertise the nodes - time.sleep(.500) - # Generate the policy for the running node - assert cli.main( - argv=['security', 'generate_policy', os.path.join(tmpdir, 'test-policy.xml')]) == 0 - finally: - node.destroy_node() - rclpy.shutdown(context=context) - - # Load the policy and pull out allowed replies and requests - policy = load_policy(os.path.join(tmpdir, 'test-policy.xml')) - profile = policy.find( - path='profiles/profile[@ns="/"][@node="test_generate_policy_services_node"]') - assert profile is not None - service_reply_allowed = profile.find(path='services[@reply="ALLOW"]') - assert service_reply_allowed is not None - service_request_allowed = profile.find(path='services[@request="ALLOW"]') - assert service_request_allowed is not None - - # Verify that the allowed replies include service_server and not service_client - services = service_reply_allowed.findall('service') - assert len([s for s in services if s.text == 'test_generate_policy_services_server']) == 1 - assert len([s for s in services if s.text == 'test_generate_policy_services_client']) == 0 - - # Verify that the allowed requests include service_client and not service_server - services = service_request_allowed.findall('service') - assert len([s for s in services if s.text == 'test_generate_policy_services_client']) == 1 - assert len([s for s in services if s.text == 'test_generate_policy_services_server']) == 0 - - -# TODO(jacobperron): On Windows, this test is flakey due to nodes left-over from tests in -# other packages. -# See: https://github.com/ros2/sros2/issues/143 -@pytest.mark.skipif( - 'nt' == os.name, reason='flakey due to nodes left-over from tests in other packages') -def test_generate_policy_no_nodes(capsys): - with tempfile.TemporaryDirectory() as tmpdir: - assert cli.main(argv=[ - 'security', 'generate_policy', os.path.join(tmpdir, 'test-policy.xml')]) != 0 - stderr = capsys.readouterr().err.strip() - assert stderr == 'No nodes detected in the ROS graph. No policy file was generated.' - - -def test_generate_policy_no_policy_file(capsys): - with pytest.raises(SystemExit) as e: - cli.main(argv=['security', 'generate_policy']) - assert e.value.code != 0 - stderr = capsys.readouterr().err.strip() - assert 'following arguments are required: POLICY_FILE_PATH' in stderr + + +@pytest.mark.rostest +@launch_testing.parametrize('rmw_implementation', get_available_rmw_implementations()) +def generate_test_description(rmw_implementation): + additional_env = {'RMW_IMPLEMENTATION': rmw_implementation} + path_to_pub_sub_node_script = os.path.join( + os.path.dirname(__file__), 'fixtures', 'pub_sub_node.py' + ) + path_to_client_srv_node_script = os.path.join( + os.path.dirname(__file__), 'fixtures', 'client_service_node.py' + ) + pub_sub_node = Node( + node_executable=sys.executable, + arguments=[path_to_pub_sub_node_script], + node_name='test_generate_policy_topics_node', + additional_env=additional_env + ) + client_srv_node = Node( + node_executable=sys.executable, + arguments=[path_to_client_srv_node_script], + node_name='test_generate_policy_services_node', + additional_env=additional_env + ) + 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=[ + pub_sub_node, client_srv_node, ReadyToTest() + ], + additional_env=additional_env + ) + ] + ), + ]) + + +class TestSROS2GeneratePolicyVerb(unittest.TestCase): + + @classmethod + def setUpClass( + cls, + launch_service, + proc_info, + proc_output, + rmw_implementation + ): + @contextlib.contextmanager + def launch_gen_policy_command(self, arguments): + gen_policy_command_action = ExecuteProcess( + cmd=['ros2', 'security', 'generate_policy', *arguments], + additional_env={ + 'RMW_IMPLEMENTATION': rmw_implementation, + 'PYTHONUNBUFFERED': '1' + }, + name='ros2security-gen-policy-cli', + output='screen' + ) + with launch_testing.tools.launch_process( + launch_service, gen_policy_command_action, proc_info, proc_output, + output_filter=launch_testing_ros.tools.basic_output_filter( + # ignore launch_ros and ros2cli daemon nodes + filtered_patterns=['.*launch_ros*', '.*ros2cli.*'], + filtered_rmw_implementation=rmw_implementation + ) + ) as gen_policy_command: + yield gen_policy_command + cls.launch_gen_policy_command = launch_gen_policy_command + + @launch_testing.markers.retry_on_failure(times=3) + def test_generate_policy_topics(self): + with tempfile.TemporaryDirectory() as tmpdir: + with self.launch_gen_policy_command( + arguments=[os.path.join(tmpdir, 'test-policy.xml')] + ) as gen_command: + assert gen_command.wait_for_shutdown(timeout=10) + assert gen_command.exit_code == launch_testing.asserts.EXIT_OK + + # Load the policy and pull out the allowed publications and subscriptions + policy = load_policy(os.path.join(tmpdir, 'test-policy.xml')) + profile = policy.find( + path='profiles/profile[@ns="/"][@node="test_generate_policy_topics_node"]') + assert profile is not None + topics_publish_allowed = profile.find(path='topics[@publish="ALLOW"]') + assert topics_publish_allowed is not None + topics_subscribe_allowed = profile.find(path='topics[@subscribe="ALLOW"]') + assert topics_subscribe_allowed is not None + + # Verify that the allowed publications include topic_pub and not topic_sub + topics = topics_publish_allowed.findall('topic') + assert len([t for t in topics if t.text == 'test_generate_policy_topics_pub']) == 1 + assert len([t for t in topics if t.text == 'test_generate_policy_topics_sub']) == 0 + + # Verify that the allowed subscriptions include topic_sub and not topic_pub + topics = topics_subscribe_allowed.findall('topic') + assert len([t for t in topics if t.text == 'test_generate_policy_topics_sub']) == 1 + assert len([t for t in topics if t.text == 'test_generate_policy_topics_pub']) == 0 + + @launch_testing.markers.retry_on_failure(times=3) + def test_generate_policy_services(self): + with tempfile.TemporaryDirectory() as tmpdir: + with self.launch_gen_policy_command( + arguments=[os.path.join(tmpdir, 'test-policy.xml')] + ) as gen_command: + assert gen_command.wait_for_shutdown(timeout=10) + assert gen_command.exit_code == launch_testing.asserts.EXIT_OK + + # Load the policy and pull out allowed replies and requests + policy = load_policy(os.path.join(tmpdir, 'test-policy.xml')) + profile = policy.find( + path='profiles/profile[@ns="/"][@node="test_generate_policy_services_node"]') + assert profile is not None + service_reply_allowed = profile.find(path='services[@reply="ALLOW"]') + assert service_reply_allowed is not None + service_request_allowed = profile.find(path='services[@request="ALLOW"]') + assert service_request_allowed is not None + + # Verify that the allowed replies include service_server and not service_client + services = service_reply_allowed.findall('service') + assert len( + [s for s in services if s.text == 'test_generate_policy_services_server']) == 1 + assert len( + [s for s in services if s.text == 'test_generate_policy_services_client']) == 0 + + # Verify that the allowed requests include service_client and not service_server + services = service_request_allowed.findall('service') + assert len( + [s for s in services if s.text == 'test_generate_policy_services_client']) == 1 + assert len( + [s for s in services if s.text == 'test_generate_policy_services_server']) == 0 + + @launch_testing.markers.retry_on_failure(times=2) + def test_generate_policy_no_policy_file(self): + with self.launch_gen_policy_command(arguments=[]) as gen_command: + assert gen_command.wait_for_shutdown(timeout=10) + assert gen_command.exit_code != 0 + assert launch_testing.tools.expect_output( + expected_lines=[ + 'following arguments are required: POLICY_FILE_PATH' + ], + text=gen_command.output, + strict=False + ) diff --git a/sros2/test/sros2/commands/security/verbs/test_generate_policy_no_nodes.py b/sros2/test/sros2/commands/security/verbs/test_generate_policy_no_nodes.py new file mode 100644 index 00000000..3a0a307f --- /dev/null +++ b/sros2/test/sros2/commands/security/verbs/test_generate_policy_no_nodes.py @@ -0,0 +1,26 @@ +# 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 os +import tempfile + +from ros2cli import cli + + +def test_generate_policy_no_nodes(capsys): + with tempfile.TemporaryDirectory() as tmpdir: + assert cli.main(argv=[ + 'security', 'generate_policy', os.path.join(tmpdir, 'test-policy.xml')]) != 0 + stderr = capsys.readouterr().err.strip() + assert stderr == 'No nodes detected in the ROS graph. No policy file was generated.' From 6ef5111a808de602614572a84bfe12e6d10f515e Mon Sep 17 00:00:00 2001 From: Brian Ezequiel Marchi Date: Thu, 28 Nov 2019 09:47:33 -0300 Subject: [PATCH 3/7] Rewrite tests for windows Signed-off-by: Brian Ezequiel Marchi --- .../security/verbs/test_generate_policy.py | 26 ++++++++++++++----- .../verbs/test_generate_policy_no_nodes.py | 7 +++++ 2 files changed, 26 insertions(+), 7 deletions(-) diff --git a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py index f9db7295..017288ff 100644 --- a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py +++ b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py @@ -175,10 +175,22 @@ def test_generate_policy_no_policy_file(self): with self.launch_gen_policy_command(arguments=[]) as gen_command: assert gen_command.wait_for_shutdown(timeout=10) assert gen_command.exit_code != 0 - assert launch_testing.tools.expect_output( - expected_lines=[ - 'following arguments are required: POLICY_FILE_PATH' - ], - text=gen_command.output, - strict=False - ) + if os.name is not 'nt': + assert launch_testing.tools.expect_output( + expected_lines=[ + 'usage: ros2 security generate_policy [-h] POLICY_FILE_PATH', + 'ros2 security generate_policy: error: the following' + ' arguments are required: POLICY_FILE_PATH' + ], + text=gen_command.output, + strict=False + ) + else: + assert launch_testing.tools.expect_output( + expected_lines=[ + 'usage: ros2 security generate_policy [-h] POLICY_FILE_PATH', + 'ros2 security generate_policy: error: too few arguments' + ], + text=gen_command.output, + strict=False + ) diff --git a/sros2/test/sros2/commands/security/verbs/test_generate_policy_no_nodes.py b/sros2/test/sros2/commands/security/verbs/test_generate_policy_no_nodes.py index 3a0a307f..a03c5360 100644 --- a/sros2/test/sros2/commands/security/verbs/test_generate_policy_no_nodes.py +++ b/sros2/test/sros2/commands/security/verbs/test_generate_policy_no_nodes.py @@ -15,9 +15,16 @@ import os import tempfile +import pytest + from ros2cli import cli +# TODO(jacobperron): On Windows, this test is flakey due to nodes left-over from tests in +# other packages. +# See: https://github.com/ros2/sros2/issues/143 +@pytest.mark.skipif( + 'nt' == os.name, reason='flakey due to nodes left-over from tests in other packages') def test_generate_policy_no_nodes(capsys): with tempfile.TemporaryDirectory() as tmpdir: assert cli.main(argv=[ From b5dbbc682e4f19017173d50a6f727ec65841861e Mon Sep 17 00:00:00 2001 From: Brian Ezequiel Marchi Date: Thu, 28 Nov 2019 10:10:24 -0300 Subject: [PATCH 4/7] Fix flake8 error Signed-off-by: Brian Ezequiel Marchi --- .../test/sros2/commands/security/verbs/test_generate_policy.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py index 017288ff..1bda21ab 100644 --- a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py +++ b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py @@ -175,7 +175,7 @@ def test_generate_policy_no_policy_file(self): with self.launch_gen_policy_command(arguments=[]) as gen_command: assert gen_command.wait_for_shutdown(timeout=10) assert gen_command.exit_code != 0 - if os.name is not 'nt': + if os.name != 'nt': assert launch_testing.tools.expect_output( expected_lines=[ 'usage: ros2 security generate_policy [-h] POLICY_FILE_PATH', From 3195215c239037e9db63142abcaad91625f651fe Mon Sep 17 00:00:00 2001 From: Brian Ezequiel Marchi Date: Fri, 29 Nov 2019 12:37:51 -0300 Subject: [PATCH 5/7] Address PR comments Signed-off-by: Brian Ezequiel Marchi --- .../commands/security/verbs/fixtures/client_service_node.py | 5 ----- .../sros2/commands/security/verbs/fixtures/pub_sub_node.py | 5 ----- .../sros2/commands/security/verbs/test_generate_policy.py | 2 +- 3 files changed, 1 insertion(+), 11 deletions(-) diff --git a/sros2/test/sros2/commands/security/verbs/fixtures/client_service_node.py b/sros2/test/sros2/commands/security/verbs/fixtures/client_service_node.py index 660c974d..c57083f2 100644 --- a/sros2/test/sros2/commands/security/verbs/fixtures/client_service_node.py +++ b/sros2/test/sros2/commands/security/verbs/fixtures/client_service_node.py @@ -12,8 +12,6 @@ # See the License for the specific language governing permissions and # limitations under the License. -import sys - import rclpy from rclpy.node import Node @@ -43,9 +41,6 @@ def main(args=None): rclpy.spin(node) except KeyboardInterrupt: print('node stopped cleanly') - except BaseException: - print('exception in node:', file=sys.stderr) - raise finally: node.destroy_node() rclpy.shutdown() diff --git a/sros2/test/sros2/commands/security/verbs/fixtures/pub_sub_node.py b/sros2/test/sros2/commands/security/verbs/fixtures/pub_sub_node.py index fbea35d1..bfad8a82 100644 --- a/sros2/test/sros2/commands/security/verbs/fixtures/pub_sub_node.py +++ b/sros2/test/sros2/commands/security/verbs/fixtures/pub_sub_node.py @@ -12,8 +12,6 @@ # See the License for the specific language governing permissions and # limitations under the License. -import sys - import rclpy from rclpy.node import Node @@ -43,9 +41,6 @@ def main(args=None): rclpy.spin(node) except KeyboardInterrupt: print('node stopped cleanly') - except BaseException: - print('exception in node:', file=sys.stderr) - raise finally: node.destroy_node() rclpy.shutdown() diff --git a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py index 1bda21ab..3b5786a5 100644 --- a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py +++ b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py @@ -174,7 +174,7 @@ def test_generate_policy_services(self): def test_generate_policy_no_policy_file(self): with self.launch_gen_policy_command(arguments=[]) as gen_command: assert gen_command.wait_for_shutdown(timeout=10) - assert gen_command.exit_code != 0 + assert gen_command.exit_code != launch_testing.asserts.EXIT_OK if os.name != 'nt': assert launch_testing.tools.expect_output( expected_lines=[ From bbe5e85e5b4738b7c64e86113b56913937d29ebe Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Thu, 5 Dec 2019 15:14:02 -0300 Subject: [PATCH 6/7] Do not always make a special case for Windows Signed-off-by: Michel Hidalgo --- .../security/verbs/test_generate_policy.py | 28 ++++++------------- 1 file changed, 9 insertions(+), 19 deletions(-) diff --git a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py index 3b5786a5..dd1bf856 100644 --- a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py +++ b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py @@ -175,22 +175,12 @@ def test_generate_policy_no_policy_file(self): with self.launch_gen_policy_command(arguments=[]) as gen_command: assert gen_command.wait_for_shutdown(timeout=10) assert gen_command.exit_code != launch_testing.asserts.EXIT_OK - if os.name != 'nt': - assert launch_testing.tools.expect_output( - expected_lines=[ - 'usage: ros2 security generate_policy [-h] POLICY_FILE_PATH', - 'ros2 security generate_policy: error: the following' - ' arguments are required: POLICY_FILE_PATH' - ], - text=gen_command.output, - strict=False - ) - else: - assert launch_testing.tools.expect_output( - expected_lines=[ - 'usage: ros2 security generate_policy [-h] POLICY_FILE_PATH', - 'ros2 security generate_policy: error: too few arguments' - ], - text=gen_command.output, - strict=False - ) + assert launch_testing.tools.expect_output( + expected_lines=[ + 'usage: ros2 security generate_policy [-h] POLICY_FILE_PATH', + 'ros2 security generate_policy: error: the following' + ' arguments are required: POLICY_FILE_PATH' + ], + text=gen_command.output, + strict=False + ) From 9c745ef31ae1bc775f7df0e656666af2bbb97d7c Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Fri, 6 Dec 2019 11:44:40 -0300 Subject: [PATCH 7/7] Do not check CLI usage message. Signed-off-by: Michel Hidalgo --- sros2/test/sros2/commands/security/verbs/test_generate_policy.py | 1 - 1 file changed, 1 deletion(-) diff --git a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py index dd1bf856..40f2c85e 100644 --- a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py +++ b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py @@ -177,7 +177,6 @@ def test_generate_policy_no_policy_file(self): assert gen_command.exit_code != launch_testing.asserts.EXIT_OK assert launch_testing.tools.expect_output( expected_lines=[ - 'usage: ros2 security generate_policy [-h] POLICY_FILE_PATH', 'ros2 security generate_policy: error: the following' ' arguments are required: POLICY_FILE_PATH' ],