diff --git a/ros2action/package.xml b/ros2action/package.xml new file mode 100644 index 000000000..74d0eef21 --- /dev/null +++ b/ros2action/package.xml @@ -0,0 +1,30 @@ + + + + ros2action + 0.6.3 + + The action command for ROS 2 command line tools. + + Jacob Perron + Apache License 2.0 + + Jacob Perron + + rclpy + ros2cli + + action_msgs + ament_index_python + rosidl_runtime_py + + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + test_msgs + + + ament_python + + diff --git a/ros2action/ros2action/__init__.py b/ros2action/ros2action/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/ros2action/ros2action/api/__init__.py b/ros2action/ros2action/api/__init__.py new file mode 100644 index 000000000..de9f0d921 --- /dev/null +++ b/ros2action/ros2action/api/__init__.py @@ -0,0 +1,141 @@ +# 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 + +from ament_index_python import get_resource +from ament_index_python import get_resources +from ament_index_python import has_resource + +import rclpy.action +from rclpy.expand_topic_name import expand_topic_name +from rclpy.validate_full_topic_name import validate_full_topic_name +from ros2cli.node.direct import DirectNode + + +def _is_action_status_topic(topic_name, action_name): + return action_name + '/_action/status' == topic_name + + +def get_action_clients_and_servers(*, node, action_name): + action_clients = [] + action_servers = [] + + expanded_name = expand_topic_name(action_name, node.get_name(), node.get_namespace()) + validate_full_topic_name(expanded_name) + + node_names_and_ns = node.get_node_names_and_namespaces() + for node_name, node_ns in node_names_and_ns: + # Construct fully qualified name + node_fqn = '/'.join(node_ns) + node_name + + # Get any action clients associated with the node + client_names_and_types = rclpy.action.get_action_client_names_and_types_by_node( + node, + node_name, + node_ns, + ) + for client_name, client_types in client_names_and_types: + if client_name == expanded_name: + action_clients.append((node_fqn, client_types)) + + # Get any action servers associated with the node + server_names_and_types = rclpy.action.get_action_server_names_and_types_by_node( + node, + node_name, + node_ns, + ) + for server_name, server_types in server_names_and_types: + if server_name == expanded_name: + action_servers.append((node_fqn, server_types)) + + return (action_clients, action_servers) + + +def get_action_names_and_types(*, node): + return rclpy.action.get_action_names_and_types(node) + + +def get_action_names(*, node): + action_names_and_types = get_action_names_and_types(node=node) + return [n for (n, t) in action_names_and_types] + + +def get_action_types(package_name): + if not has_resource('packages', package_name): + raise LookupError('Unknown package name') + try: + content, _ = get_resource('rosidl_interfaces', package_name) + except LookupError: + return [] + interface_names = content.splitlines() + # TODO(jacobperron) this logic should come from a rosidl related package + # Only return actions in action folder + return list(sorted({ + n[7:-7] + for n in interface_names + if n.startswith('action/') and n[-7:] in ('.idl', '.action')})) + + +def get_all_action_types(): + all_action_types = {} + for package_name in get_resources('rosidl_interfaces'): + action_types = get_action_types(package_name) + if action_types: + all_action_types[package_name] = action_types + return all_action_types + + +def get_action_path(package_name, action_name): + action_types = get_action_types(package_name) + if action_name not in action_types: + raise LookupError('Unknown action type') + prefix_path = has_resource('packages', package_name) + # TODO(jacobperron) this logic should come from a rosidl related package + return os.path.join(prefix_path, 'share', package_name, 'action', action_name + '.action') + + +def action_name_completer(prefix, parsed_args, **kwargs): + """Callable returning a list of action names.""" + with DirectNode(parsed_args) as node: + return get_action_names(node=node) + + +def action_type_completer(**kwargs): + """Callable returning a list of action types.""" + action_types = [] + for package_name, action_names in get_all_action_types().items(): + for action_name in action_names: + action_types.append( + '{package_name}/{action_name}'.format_map(locals())) + return action_types + + +class ActionTypeCompleter: + """Callable returning a list of action types.""" + + def __init__(self, *, action_name_key=None): + self.action_name_key = action_name_key + + def __call__(self, prefix, parsed_args, **kwargs): + if self.action_name_key is None: + return action_type_completer() + + action_name = getattr(parsed_args, self.action_name_key) + with DirectNode(parsed_args) as node: + names_and_types = get_action_names_and_types(node=node) + for n, t in names_and_types: + if n == action_name: + return t + return [] diff --git a/ros2action/ros2action/command/__init__.py b/ros2action/ros2action/command/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/ros2action/ros2action/command/action.py b/ros2action/ros2action/command/action.py new file mode 100644 index 000000000..24bcb21a3 --- /dev/null +++ b/ros2action/ros2action/command/action.py @@ -0,0 +1,38 @@ +# 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. + +from ros2cli.command import add_subparsers +from ros2cli.command import CommandExtension +from ros2cli.verb import get_verb_extensions + + +class ActionCommand(CommandExtension): + """Various action related sub-commands.""" + + def add_arguments(self, parser, cli_name): + self._subparser = parser + # Get verb extensions and let them add their arguments and sub-commands + verb_extensions = get_verb_extensions('ros2action.verb') + add_subparsers(parser, cli_name, '_verb', verb_extensions, required=False) + + def main(self, *, parser, args): + if not hasattr(args, '_verb'): + # In case no verb was passed + self._subparser.print_help() + return 0 + + extension = getattr(args, '_verb') + + # Call the verb's main method + return extension.main(args=args) diff --git a/ros2action/ros2action/verb/__init__.py b/ros2action/ros2action/verb/__init__.py new file mode 100644 index 000000000..919ef8a0e --- /dev/null +++ b/ros2action/ros2action/verb/__init__.py @@ -0,0 +1,44 @@ +# 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. + +from ros2cli.plugin_system import PLUGIN_SYSTEM_VERSION +from ros2cli.plugin_system import satisfies_version + + +class VerbExtension: + """ + The extension point for 'action' verb extensions. + + The following properties must be defined: + * `NAME` (will be set to the entry point name) + + The following methods must be defined: + * `main` + + The following methods can be defined: + * `add_arguments` + """ + + NAME = None + EXTENSION_POINT_VERSION = '0.1' + + def __init__(self): + super(VerbExtension, self).__init__() + satisfies_version(PLUGIN_SYSTEM_VERSION, '^0.1') + + def add_arguments(self, parser, cli_name): + pass + + def main(self, *, args): + raise NotImplementedError() diff --git a/ros2action/ros2action/verb/info.py b/ros2action/ros2action/verb/info.py new file mode 100644 index 000000000..043806fe8 --- /dev/null +++ b/ros2action/ros2action/verb/info.py @@ -0,0 +1,63 @@ +# 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 rclpy +from ros2action.api import action_name_completer +from ros2action.api import get_action_clients_and_servers +from ros2action.verb import VerbExtension +from ros2cli.node.direct import DirectNode + + +class InfoVerb(VerbExtension): + """Print information about an action.""" + + def add_arguments(self, parser, cli_name): + arg = parser.add_argument( + 'action_name', + help="Name of the ROS action to get info (e.g. '/fibonacci')") + arg.completer = action_name_completer + parser.add_argument( + '-t', '--show-types', action='store_true', + help='Additionally show the action type') + parser.add_argument( + '-c', '--count', action='store_true', + help='Only display the number of action clients and action servers') + + def main(self, *, args): + with DirectNode(args) as node: + try: + action_clients, action_servers = get_action_clients_and_servers( + node=node, + action_name=args.action_name, + ) + except (ValueError, rclpy.exceptions.InvalidTopicNameException) as e: + raise RuntimeError(e) + + print('Action: {}'.format(args.action_name)) + print('Action clients: {}'.format(len(action_clients))) + if not args.count: + for client_name, client_types in action_clients: + if args.show_types: + types_formatted = ', '.join(client_types) + print(' {client_name} [{types_formatted}]'.format_map(locals())) + else: + print(' {client_name}'.format_map(locals())) + print('Action servers: {}'.format(len(action_servers))) + if not args.count: + for server_name, server_types in action_servers: + if args.show_types: + types_formatted = ', '.join(server_types) + print(' {server_name} [{types_formatted}]'.format_map(locals())) + else: + print(' {server_name}'.format_map(locals())) diff --git a/ros2action/ros2action/verb/list.py b/ros2action/ros2action/verb/list.py new file mode 100644 index 000000000..893d0d9f3 --- /dev/null +++ b/ros2action/ros2action/verb/list.py @@ -0,0 +1,44 @@ +# 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. + +from ros2action.api import get_action_names_and_types +from ros2action.verb import VerbExtension +from ros2cli.node.strategy import DirectNode + + +class ListVerb(VerbExtension): + """Output a list of action names.""" + + def add_arguments(self, parser, cli_name): + parser.add_argument( + '-t', '--show-types', action='store_true', + help='Additionally show the action type') + parser.add_argument( + '-c', '--count-actions', action='store_true', + help='Only display the number of actions discovered') + + def main(self, *, args): + with DirectNode(args) as node: + action_names_and_types = get_action_names_and_types(node=node) + + if args.count_actions: + print(len(action_names_and_types)) + return + + for name, types in action_names_and_types: + if args.show_types: + types_formatted = ', '.join(types) + print('{name} [{types_formatted}]'.format_map(locals())) + else: + print('{name}'.format_map(locals())) diff --git a/ros2action/ros2action/verb/send_goal.py b/ros2action/ros2action/verb/send_goal.py new file mode 100644 index 000000000..ef7ed9ec6 --- /dev/null +++ b/ros2action/ros2action/verb/send_goal.py @@ -0,0 +1,163 @@ +# 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 importlib + +from action_msgs.msg import GoalStatus +import rclpy +from rclpy.action import ActionClient +from ros2action.api import action_name_completer +from ros2action.api import ActionTypeCompleter +from ros2action.verb import VerbExtension +from ros2cli.node import NODE_NAME_PREFIX +from rosidl_runtime_py import message_to_yaml +from rosidl_runtime_py import set_message_fields + +import yaml + + +class SendGoalVerb(VerbExtension): + """Send an action goal.""" + + def add_arguments(self, parser, cli_name): + arg = parser.add_argument( + 'action_name', + help="Name of the ROS action (e.g. '/fibonacci')") + arg.completer = action_name_completer + arg = parser.add_argument( + 'action_type', + help="Type of the ROS action (e.g. 'example_interfaces/Fibonacci')") + arg.completer = ActionTypeCompleter(action_name_key='action_name') + parser.add_argument( + 'goal', + help="Goal request values in YAML format (e.g. '{order: 10}')") + parser.add_argument( + '-f', '--feedback', action='store_true', + help='Echo feedback messages for the goal') + + def main(self, *, args): + feedback_callback = None + if args.feedback: + feedback_callback = _feedback_callback + return send_goal(args.action_name, args.action_type, args.goal, feedback_callback) + + +def _goal_status_to_string(status): + if GoalStatus.STATUS_ACCEPTED == status: + return 'ACCEPTED' + elif GoalStatus.STATUS_EXECUTING == status: + return 'EXECUTING' + elif GoalStatus.STATUS_CANCELING == status: + return 'CANCELING' + elif GoalStatus.STATUS_SUCCEEDED == status: + return 'SUCCEEDED' + elif GoalStatus.STATUS_CANCELED == status: + return 'CANCELED' + elif GoalStatus.STATUS_ABORTED == status: + return 'ABORTED' + else: + return 'UNKNOWN' + + +def _feedback_callback(feedback): + print('Feedback:\n {}'.format(message_to_yaml(feedback.feedback, None))) + + +def send_goal(action_name, action_type, goal_values, feedback_callback): + goal_handle = None + node = None + action_client = None + try: + # TODO(jacobperron): This logic should come from a rosidl related package + package_name, action_type = action_type.split('/', 2) + if not package_name or not action_type: + raise RuntimeError('The passed action type is invalid') + + module = importlib.import_module(package_name + '.action') + action_module = getattr(module, action_type) + goal_dict = yaml.load(goal_values) + + rclpy.init() + + node_name = NODE_NAME_PREFIX + '_send_goal_{}_{}'.format(package_name, action_type) + node = rclpy.create_node(node_name) + + action_client = ActionClient(node, action_module, action_name) + + goal = action_module.Goal() + + try: + set_message_fields(goal, goal_dict) + except Exception as ex: + return 'Failed to populate message fields: {!r}'.format(ex) + + print('Waiting for an action server to become available...') + action_client.wait_for_server() + + print('Sending goal:\n {}'.format(message_to_yaml(goal, None))) + goal_future = action_client.send_goal_async(goal, feedback_callback) + rclpy.spin_until_future_complete(node, goal_future) + + goal_handle = goal_future.result() + + if goal_handle is None: + raise RuntimeError( + 'Exeception while sending goal: {!r}'.format(goal_future.exception())) + + if not goal_handle.accepted: + print('Goal was rejected.') + return + + print('Goal accepted with ID: {}\n'.format(bytes(goal_handle.goal_id.uuid).hex())) + + result_future = goal_handle.get_result_async() + rclpy.spin_until_future_complete(node, result_future) + + result = result_future.result() + + if result is None: + raise RuntimeError( + 'Exeception while getting result: {!r}'.format(result_future.exception())) + + print('Result:\n {}'.format(message_to_yaml(result.result, None))) + print('Goal finished with status: {}'.format(_goal_status_to_string(result.status))) + finally: + # Cancel the goal if it's still active + if (goal_handle is not None and + (GoalStatus.STATUS_ACCEPTED == goal_handle.status or + GoalStatus.STATUS_EXECUTING == goal_handle.status)): + print('Canceling goal...') + cancel_future = goal_handle.cancel_goal_async() + rclpy.spin_until_future_complete(node, cancel_future) + + cancel_response = cancel_future.result() + + if cancel_response is None: + raise RuntimeError( + 'Exeception while canceling goal: {!r}'.format(cancel_future.exception())) + + if len(cancel_response.goals_canceling) == 0: + raise RuntimeError('Failed to cancel goal') + if len(cancel_response.goals_canceling) > 1: + raise RuntimeError('More than one goal canceled') + if cancel_response.goals_canceling[0].goal_id != goal_handle.goal_id: + raise RuntimeError('Canceled goal with incorrect goal ID') + print('Goal canceled.') + + if action_client is not None: + action_client.destroy() + if node is not None: + node.destroy_node() + if rclpy.ok(): + rclpy.shutdown() diff --git a/ros2action/ros2action/verb/show.py b/ros2action/ros2action/verb/show.py new file mode 100644 index 000000000..b2df89326 --- /dev/null +++ b/ros2action/ros2action/verb/show.py @@ -0,0 +1,38 @@ +# 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. + +from ros2action.api import action_type_completer +from ros2action.api import get_action_path +from ros2action.verb import VerbExtension + + +class ShowVerb(VerbExtension): + """Output the action definition.""" + + def add_arguments(self, parser, cli_name): + arg = parser.add_argument( + 'action_type', + help="Type of the ROS action (e.g. 'example_interfaces/Fibonacci')") + arg.completer = action_type_completer + + def main(self, *, args): + package_name, action_name = args.action_type.split('/', 2) + if not package_name or not action_name: + raise RuntimeError('The passed action type is invalid') + try: + path = get_action_path(package_name, action_name) + except LookupError as e: + return str(e) + with open(path, 'r') as action_file: + print(action_file.read(), end='') diff --git a/ros2action/setup.py b/ros2action/setup.py new file mode 100644 index 000000000..169b53b84 --- /dev/null +++ b/ros2action/setup.py @@ -0,0 +1,43 @@ +from setuptools import find_packages +from setuptools import setup + +setup( + name='ros2action', + version='0.6.3', + packages=find_packages(exclude=['test']), + install_requires=['ros2cli'], + zip_safe=True, + author='Jacob Perron', + author_email='jacob@openrobotics.org', + maintainer='Jacob Perron', + maintainer_email='jacob@openrobotics.org', + url='https://github.com/ros2/ros2cli/tree/master/ros2action', + download_url='https://github.com/ros2/ros2cli/releases', + keywords=[], + classifiers=[ + 'Environment :: Console', + 'Intended Audience :: Developers', + 'License :: OSI Approved :: Apache Software License', + 'Programming Language :: Python', + ], + description='The action command for ROS 2 command line tools.', + long_description="""\ +The package provides the action command for the ROS 2 command line tools.""", + license='Apache License, Version 2.0', + tests_require=['pytest'], + entry_points={ + 'ros2cli.command': [ + 'action = ros2action.command.action:ActionCommand', + ], + 'ros2cli.extension_point': [ + 'ros2action.verb = ros2action.verb:VerbExtension', + ], + 'ros2action.verb': [ + # 'echo = ros2action.verb.echo:EchoVerb', + 'info = ros2action.verb.info:InfoVerb', + 'list = ros2action.verb.list:ListVerb', + 'send_goal = ros2action.verb.send_goal:SendGoalVerb', + 'show = ros2action.verb.show:ShowVerb', + ], + } +) diff --git a/ros2action/test/test_api.py b/ros2action/test/test_api.py new file mode 100644 index 000000000..8b42245af --- /dev/null +++ b/ros2action/test/test_api.py @@ -0,0 +1,60 @@ +# 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 pytest + +from ros2action.api import get_action_clients_and_servers +from ros2action.api import get_action_names +from ros2action.api import get_action_path +from ros2action.api import get_action_types +from ros2cli.node.strategy import DirectNode + + +def test_get_action_clients_and_servers(): + with DirectNode(None) as node: + clients, servers = get_action_clients_and_servers( + node=node, + action_name='/test_action_name', + ) + assert len(clients) == 0 + assert len(servers) == 0 + + +def test_get_action_names(): + with DirectNode(None) as node: + get_action_names(node=node) + + +def test_get_action_path(): + action_path = get_action_path('test_msgs', 'Fibonacci') + assert os.path.isfile(action_path) + + with pytest.raises(LookupError): + get_action_path('_not_a_real_package_name', 'Fibonacci') + + +def test_get_action_types(): + action_types = get_action_types('test_msgs') + # Expect only strings + for t in action_types: + assert isinstance(t, str) + # Explicit dependencies of this package should be available + assert 'Fibonacci' in action_types + assert 'NestedMessage' in action_types + # Some things that should not be in the list + assert '' not in action_types + assert 'test_msgs' not in action_types + assert 'NotAnActionMessage' not in action_types diff --git a/ros2action/test/test_copyright.py b/ros2action/test/test_copyright.py new file mode 100644 index 000000000..ca44b846e --- /dev/null +++ b/ros2action/test/test_copyright.py @@ -0,0 +1,23 @@ +# 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. + +from ament_copyright.main import main +import pytest + + +@pytest.mark.copyright +@pytest.mark.linter +def test_copyright(): + rc = main(argv=['.', 'test']) + assert rc == 0, 'Found errors' diff --git a/ros2action/test/test_flake8.py b/ros2action/test/test_flake8.py new file mode 100644 index 000000000..b90428249 --- /dev/null +++ b/ros2action/test/test_flake8.py @@ -0,0 +1,23 @@ +# 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. + +from ament_flake8.main import main +import pytest + + +@pytest.mark.flake8 +@pytest.mark.linter +def test_flake8(): + rc = main(argv=[]) + assert rc == 0, 'Found errors' diff --git a/ros2action/test/test_pep257.py b/ros2action/test/test_pep257.py new file mode 100644 index 000000000..6b8c791ef --- /dev/null +++ b/ros2action/test/test_pep257.py @@ -0,0 +1,23 @@ +# 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. + +from ament_pep257.main import main +import pytest + + +@pytest.mark.linter +@pytest.mark.pep257 +def test_pep257(): + rc = main(argv=[]) + assert rc == 0, 'Found code style errors / warnings'