├── .gitignore ├── CONTRIBUTING.md ├── LICENSE ├── README.md ├── pytest.ini ├── ros2action ├── CHANGELOG.rst ├── package.xml ├── resource │ └── ros2action ├── ros2action │ ├── __init__.py │ ├── api │ │ └── __init__.py │ ├── command │ │ ├── __init__.py │ │ └── action.py │ └── verb │ │ ├── __init__.py │ │ ├── echo.py │ │ ├── find.py │ │ ├── info.py │ │ ├── list.py │ │ ├── send_goal.py │ │ └── type.py ├── setup.py └── test │ ├── fixtures │ ├── fibonacci_action_introspection.py │ └── fibonacci_action_server.py │ ├── test_api.py │ ├── test_cli.py │ ├── test_copyright.py │ ├── test_echo.py │ ├── test_flake8.py │ ├── test_pep257.py │ └── test_xmllint.py ├── ros2cli ├── CHANGELOG.rst ├── colcon.pkg ├── completion │ ├── ros2-argcomplete.bash │ └── ros2-argcomplete.zsh ├── package.xml ├── resource │ ├── package.dsv │ └── ros2cli ├── ros2cli │ ├── __init__.py │ ├── cli.py │ ├── command │ │ ├── __init__.py │ │ ├── daemon.py │ │ ├── extension_points.py │ │ └── extensions.py │ ├── daemon │ │ ├── __init__.py │ │ └── daemonize.py │ ├── entry_points.py │ ├── helpers.py │ ├── node │ │ ├── __init__.py │ │ ├── daemon.py │ │ ├── direct.py │ │ ├── network_aware.py │ │ └── strategy.py │ ├── plugin_system.py │ ├── verb │ │ ├── __init__.py │ │ └── daemon │ │ │ ├── __init__.py │ │ │ ├── start.py │ │ │ ├── status.py │ │ │ └── stop.py │ └── xmlrpc │ │ ├── __init__.py │ │ ├── client.py │ │ ├── local_server.py │ │ └── marshal │ │ ├── __init__.py │ │ ├── generic.py │ │ └── rclpy.py ├── setup.py └── test │ ├── test_copyright.py │ ├── test_flake8.py │ ├── test_pep257.py │ ├── test_ros2cli_daemon.py │ ├── test_ros2cli_direct.py │ ├── test_strategy.py │ └── test_xmllint.py ├── ros2cli_test_interfaces ├── CHANGELOG.rst ├── CMakeLists.txt ├── action │ └── ShortVariedMultiNested.action ├── msg │ ├── ShortVaried.msg │ ├── ShortVariedMultiNested.msg │ └── ShortVariedNested.msg ├── package.xml └── srv │ └── ShortVariedMultiNested.srv ├── ros2component ├── CHANGELOG.rst ├── package.xml ├── resource │ └── ros2component ├── ros2component │ ├── __init__.py │ ├── api │ │ └── __init__.py │ ├── command │ │ ├── __init__.py │ │ └── component.py │ └── verb │ │ ├── __init__.py │ │ ├── list.py │ │ ├── load.py │ │ ├── standalone.py │ │ ├── types.py │ │ └── unload.py ├── setup.py └── test │ ├── test_api.py │ ├── test_copyright.py │ ├── test_flake8.py │ ├── test_pep257.py │ └── test_xmllint.py ├── ros2doctor ├── CHANGELOG.rst ├── README.md ├── package.xml ├── resource │ └── ros2doctor ├── ros2doctor │ ├── __init__.py │ ├── api │ │ ├── __init__.py │ │ ├── format.py │ │ ├── network.py │ │ ├── package.py │ │ ├── platform.py │ │ ├── qos_compatibility.py │ │ ├── rmw.py │ │ └── topic.py │ ├── command │ │ ├── __init__.py │ │ └── doctor.py │ └── verb │ │ ├── __init__.py │ │ └── hello.py ├── setup.py └── test │ ├── fixtures │ ├── listener_node_with_reliable_qos.py │ ├── talker_node_with_best_effort_qos.py │ └── talker_node_with_reliable_qos.py │ ├── test_api.py │ ├── test_cli.py │ ├── test_copyright.py │ ├── test_flake8.py │ ├── test_pep257.py │ ├── test_qos_compatibility.py │ └── test_xmllint.py ├── ros2interface ├── CHANGELOG.rst ├── package.xml ├── resource │ └── ros2interface ├── ros2interface │ ├── __init__.py │ ├── api │ │ └── __init__.py │ ├── command │ │ ├── __init__.py │ │ └── interface.py │ └── verb │ │ ├── __init__.py │ │ ├── list.py │ │ ├── package.py │ │ ├── packages.py │ │ ├── proto.py │ │ └── show.py ├── setup.py └── test │ ├── test_cli.py │ ├── test_copyright.py │ ├── test_flake8.py │ ├── test_pep257.py │ └── test_xmllint.py ├── ros2lifecycle ├── CHANGELOG.rst ├── package.xml ├── resource │ └── ros2lifecycle ├── ros2lifecycle │ ├── __init__.py │ ├── api │ │ └── __init__.py │ ├── command │ │ ├── __init__.py │ │ └── lifecycle.py │ └── verb │ │ ├── __init__.py │ │ ├── get.py │ │ ├── list.py │ │ ├── nodes.py │ │ └── set.py ├── setup.py └── test │ ├── test_cli.py │ ├── test_copyright.py │ ├── test_flake8.py │ ├── test_pep257.py │ └── test_xmllint.py ├── ros2lifecycle_test_fixtures ├── CHANGELOG.rst ├── CMakeLists.txt ├── package.xml └── src │ └── simple_lifecycle_node.cpp ├── ros2multicast ├── CHANGELOG.rst ├── README.rst ├── package.xml ├── resource │ └── ros2multicast ├── ros2multicast │ ├── __init__.py │ ├── api │ │ └── __init__.py │ ├── command │ │ ├── __init__.py │ │ └── multicast.py │ └── verb │ │ ├── __init__.py │ │ ├── receive.py │ │ └── send.py ├── setup.py └── test │ ├── test_api.py │ ├── test_copyright.py │ ├── test_flake8.py │ ├── test_pep257.py │ └── test_xmllint.py ├── ros2node ├── CHANGELOG.rst ├── package.xml ├── resource │ └── ros2node ├── ros2node │ ├── __init__.py │ ├── api │ │ └── __init__.py │ ├── command │ │ ├── __init__.py │ │ └── node.py │ └── verb │ │ ├── __init__.py │ │ ├── info.py │ │ └── list.py ├── setup.py └── test │ ├── fixtures │ └── complex_node.py │ ├── test_cli.py │ ├── test_cli_duplicate_node_names.py │ ├── test_copyright.py │ ├── test_flake8.py │ ├── test_node.py │ ├── test_pep257.py │ └── test_xmllint.py ├── ros2param ├── CHANGELOG.rst ├── package.xml ├── resource │ └── ros2param ├── ros2param │ ├── __init__.py │ ├── api │ │ └── __init__.py │ ├── command │ │ ├── __init__.py │ │ └── param.py │ └── verb │ │ ├── __init__.py │ │ ├── delete.py │ │ ├── describe.py │ │ ├── dump.py │ │ ├── get.py │ │ ├── list.py │ │ ├── load.py │ │ └── set.py ├── setup.py └── test │ ├── fixtures │ └── parameter_node.py │ ├── test_api.py │ ├── test_copyright.py │ ├── test_flake8.py │ ├── test_pep257.py │ ├── test_verb_dump.py │ ├── test_verb_list.py │ ├── test_verb_load.py │ └── test_xmllint.py ├── ros2pkg ├── CHANGELOG.rst ├── package.xml ├── resource │ └── ros2pkg ├── ros2pkg │ ├── __init__.py │ ├── api │ │ ├── __init__.py │ │ └── create.py │ ├── command │ │ ├── __init__.py │ │ └── pkg.py │ ├── resource │ │ ├── __init__.py │ │ ├── ament_cmake │ │ │ ├── CMakeLists.txt.em │ │ │ └── __init__.py │ │ ├── ament_python │ │ │ ├── __init__.py │ │ │ ├── init.py.em │ │ │ ├── main.py.em │ │ │ ├── resource_file.em │ │ │ ├── setup.cfg.em │ │ │ ├── setup.py.em │ │ │ ├── test_copyright.py.em │ │ │ ├── test_flake8.py.em │ │ │ ├── test_pep257.py.em │ │ │ └── test_xmllint.py.em │ │ ├── cmake │ │ │ ├── CMakeLists.txt.em │ │ │ ├── Config.cmake.in.em │ │ │ ├── ConfigVersion.cmake.in.em │ │ │ └── __init__.py │ │ ├── cpp │ │ │ ├── __init__.py │ │ │ ├── header.hpp.em │ │ │ ├── library.cpp.em │ │ │ ├── main.cpp.em │ │ │ └── visibility_control.h.em │ │ └── package_environment │ │ │ ├── __init__.py │ │ │ └── package.xml.em │ └── verb │ │ ├── __init__.py │ │ ├── create.py │ │ ├── executables.py │ │ ├── list.py │ │ ├── prefix.py │ │ └── xml.py ├── setup.py └── test │ ├── test_api.py │ ├── test_cli.py │ ├── test_copyright.py │ ├── test_flake8.py │ ├── test_pep257.py │ └── test_xmllint.py ├── ros2run ├── CHANGELOG.rst ├── package.xml ├── resource │ └── ros2run ├── ros2run │ ├── __init__.py │ ├── api │ │ └── __init__.py │ └── command │ │ ├── __init__.py │ │ └── run.py ├── setup.py └── test │ ├── test_copyright.py │ ├── test_flake8.py │ ├── test_pep257.py │ └── test_xmllint.py ├── ros2service ├── CHANGELOG.rst ├── package.xml ├── resource │ └── ros2service ├── ros2service │ ├── __init__.py │ ├── api │ │ └── __init__.py │ ├── command │ │ ├── __init__.py │ │ └── service.py │ └── verb │ │ ├── __init__.py │ │ ├── call.py │ │ ├── echo.py │ │ ├── find.py │ │ ├── info.py │ │ ├── list.py │ │ └── type.py ├── setup.py └── test │ ├── fixtures │ ├── echo_server.py │ └── introspectable.py │ ├── test_cli.py │ ├── test_copyright.py │ ├── test_echo.py │ ├── test_flake8.py │ ├── test_pep257.py │ └── test_xmllint.py └── ros2topic ├── CHANGELOG.rst ├── package.xml ├── resource └── ros2topic ├── ros2topic ├── __init__.py ├── api │ └── __init__.py ├── command │ ├── __init__.py │ └── topic.py └── verb │ ├── __init__.py │ ├── bw.py │ ├── delay.py │ ├── echo.py │ ├── find.py │ ├── hz.py │ ├── info.py │ ├── list.py │ ├── pub.py │ └── type.py ├── setup.py └── test ├── fixtures ├── controller_node.py ├── listener_node.py ├── repeater_node.py └── talker_node.py ├── qos_subscription.py ├── resources └── chatter.yaml ├── test_bw_delay_hz.py ├── test_cli.py ├── test_copyright.py ├── test_echo_pub.py ├── test_flake8.py ├── test_info.py ├── test_pep257.py ├── test_qos_conversions.py ├── test_use_sim_time.py └── test_xmllint.py /.gitignore: -------------------------------------------------------------------------------- 1 | __pycache__ 2 | -------------------------------------------------------------------------------- /CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | Any contribution that you make to this repository will 2 | be under the Apache 2 License, as dictated by that 3 | [license](http://www.apache.org/licenses/LICENSE-2.0.html): 4 | 5 | ~~~ 6 | 5. Submission of Contributions. Unless You explicitly state otherwise, 7 | any Contribution intentionally submitted for inclusion in the Work 8 | by You to the Licensor shall be under the terms and conditions of 9 | this License, without any additional terms or conditions. 10 | Notwithstanding the above, nothing herein shall supersede or modify 11 | the terms of any separate license agreement you may have executed 12 | with Licensor regarding such Contributions. 13 | ~~~ 14 | 15 | Contributors must sign-off each commit by adding a `Signed-off-by: ...` 16 | line to commit messages to certify that they have the right to submit 17 | the code they are contributing to the project according to the 18 | [Developer Certificate of Origin (DCO)](https://developercertificate.org/). 19 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # ros2cli 2 | 3 | This repository contains the source code for ROS 2 command line interface tools included with a standard install of any ROS 2 distro. 4 | 5 | ## Usage 6 | 7 | Run `ros2 --help` to see all available commands. 8 | 9 | Run `ros2 --help` for more information on individual command usage. 10 | 11 | Run `ros2 --help` for even more usage information on a specific command's verbs. 12 | 13 | Read [Introspection with command line tools](https://docs.ros.org/en/rolling/Concepts/Basic/About-Command-Line-Tools.html) for more information and an example. 14 | 15 | ### Cheat Sheet 16 | 17 | This [cheat sheet](https://github.com/artivis/ros2_cheats_sheet/blob/master/cli/cli_cheats_sheet.pdf) provides examples for commands and their verbs (some of which rely on the [ROS 2 demos package](https://github.com/ros2/demos)). 18 | 19 | ## Add New Verbs 20 | 21 | You can use [Python entry points](https://setuptools.readthedocs.io/en/latest/pkg_resources.html#entry-points) to create new commands and verbs for the CLI. 22 | 23 | [Here's an example](https://github.com/ros2/ros2cli/pull/273/files). 24 | 25 | And [here's an example](https://github.com/artivis/ros2hellocli) for how to add a command. 26 | 27 | ## Background 28 | 29 | You can find a [historical discussion](https://discourse.ros.org/t/ros-graph-information-tools-implementation-discussion/674/34) on this subject on Discourse. 30 | -------------------------------------------------------------------------------- /pytest.ini: -------------------------------------------------------------------------------- 1 | [pytest] 2 | junit_family=xunit2 3 | timeout=900 4 | timeout_method=thread 5 | filterwarnings= 6 | # flake8 in Ubuntu 22.04 prints this warning; we ignore it for now 7 | ignore:SelectableGroups:DeprecationWarning 8 | ignore:.*use of fork\(\) may lead to deadlocks in the child.* 9 | -------------------------------------------------------------------------------- /ros2action/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros2action 5 | 0.39.0 6 | 7 | The action command for ROS 2 command line tools. 8 | 9 | 10 | Audrow Nash 11 | Geoffrey Biggs 12 | 13 | Apache License 2.0 14 | 15 | Aditya Pande 16 | Jacob Perron 17 | Mabel Zhang 18 | Michael Jeronimo 19 | 20 | action_msgs 21 | ament_index_python 22 | rclpy 23 | ros2cli 24 | ros2topic 25 | rosidl_runtime_py 26 | 27 | ament_copyright 28 | ament_flake8 29 | ament_pep257 30 | ament_xmllint 31 | launch 32 | launch_testing 33 | launch_testing_ros 34 | python3-pytest 35 | python3-pytest-timeout 36 | test_msgs 37 | 38 | 39 | ament_python 40 | 41 | 42 | -------------------------------------------------------------------------------- /ros2action/resource/ros2action: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2action/resource/ros2action -------------------------------------------------------------------------------- /ros2action/ros2action/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2action/ros2action/__init__.py -------------------------------------------------------------------------------- /ros2action/ros2action/command/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2action/ros2action/command/__init__.py -------------------------------------------------------------------------------- /ros2action/ros2action/command/action.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.command import add_subparsers_on_demand 16 | from ros2cli.command import CommandExtension 17 | 18 | 19 | class ActionCommand(CommandExtension): 20 | """Various action related sub-commands.""" 21 | 22 | def add_arguments(self, parser, cli_name): 23 | self._subparser = parser 24 | # add arguments and sub-commands of verbs 25 | add_subparsers_on_demand( 26 | parser, cli_name, '_verb', 'ros2action.verb', required=False) 27 | 28 | def main(self, *, parser, args): 29 | if not hasattr(args, '_verb'): 30 | # In case no verb was passed 31 | self._subparser.print_help() 32 | return 0 33 | 34 | extension = getattr(args, '_verb') 35 | 36 | # Call the verb's main method 37 | return extension.main(args=args) 38 | -------------------------------------------------------------------------------- /ros2action/ros2action/verb/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.plugin_system import PLUGIN_SYSTEM_VERSION 16 | from ros2cli.plugin_system import satisfies_version 17 | 18 | 19 | class VerbExtension: 20 | """ 21 | The extension point for 'action' verb extensions. 22 | 23 | The following properties must be defined: 24 | * `NAME` (will be set to the entry point name) 25 | 26 | The following methods must be defined: 27 | * `main` 28 | 29 | The following methods can be defined: 30 | * `add_arguments` 31 | """ 32 | 33 | NAME = None 34 | EXTENSION_POINT_VERSION = '0.1' 35 | 36 | def __init__(self): 37 | super(VerbExtension, self).__init__() 38 | satisfies_version(PLUGIN_SYSTEM_VERSION, '^0.1') 39 | 40 | def add_arguments(self, parser, cli_name): 41 | pass 42 | 43 | def main(self, *, args): 44 | raise NotImplementedError() 45 | -------------------------------------------------------------------------------- /ros2action/ros2action/verb/find.py: -------------------------------------------------------------------------------- 1 | # Copyright 2024 Sony Group Corporation. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2action.api import action_type_completer 16 | from ros2action.api import get_action_names_and_types 17 | from ros2action.verb import VerbExtension 18 | from ros2cli.node.strategy import NodeStrategy 19 | 20 | 21 | class FindVerb(VerbExtension): 22 | """Find actions from type.""" 23 | 24 | def add_arguments(self, parser, cli_name): 25 | arg = parser.add_argument( 26 | 'action_type', 27 | help="Name of the ROS action type to find (e.g. 'test_msgs/action/Fibonacci')") 28 | arg.completer = action_type_completer 29 | parser.add_argument( 30 | '-c', '--count-actions', action='store_true', 31 | help='Only display the number of actions discovered') 32 | 33 | def main(self, *, args): 34 | with NodeStrategy(args) as node: 35 | action_names_and_types = get_action_names_and_types(node=node) 36 | 37 | filtered_actions = [] 38 | for (action_name, action_types) in action_names_and_types: 39 | if args.action_type in action_types: 40 | filtered_actions.append(action_name) 41 | 42 | if args.count_actions: 43 | print(len(filtered_actions)) 44 | else: 45 | for filtered_action in filtered_actions: 46 | print(filtered_action) 47 | -------------------------------------------------------------------------------- /ros2action/ros2action/verb/list.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2action.api import get_action_names_and_types 16 | from ros2action.verb import VerbExtension 17 | from ros2cli.node.strategy import NodeStrategy 18 | 19 | 20 | class ListVerb(VerbExtension): 21 | """Output a list of action names.""" 22 | 23 | def add_arguments(self, parser, cli_name): 24 | parser.add_argument( 25 | '-t', '--show-types', action='store_true', 26 | help='Additionally show the action type') 27 | parser.add_argument( 28 | '-c', '--count-actions', action='store_true', 29 | help='Only display the number of actions discovered') 30 | 31 | def main(self, *, args): 32 | with NodeStrategy(args) as node: 33 | action_names_and_types = get_action_names_and_types(node=node) 34 | 35 | if args.count_actions: 36 | print(len(action_names_and_types)) 37 | return 38 | 39 | for name, types in action_names_and_types: 40 | if args.show_types: 41 | types_formatted = ', '.join(types) 42 | print(f'{name} [{types_formatted}]') 43 | else: 44 | print(f'{name}') 45 | -------------------------------------------------------------------------------- /ros2action/ros2action/verb/type.py: -------------------------------------------------------------------------------- 1 | # Copyright 2024 Sony Group Corporation. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2action.api import action_name_completer 16 | from ros2action.api import get_action_names_and_types 17 | from ros2action.verb import VerbExtension 18 | from ros2cli.node.strategy import NodeStrategy 19 | 20 | 21 | class TypeVerb(VerbExtension): 22 | """Print a action's type.""" 23 | 24 | def add_arguments(self, parser, cli_name): 25 | arg = parser.add_argument( 26 | 'action_name', 27 | help="Name of the ROS action to get info (e.g. '/fibonacci')") 28 | arg.completer = action_name_completer 29 | 30 | def main(self, *, args): 31 | with NodeStrategy(args) as node: 32 | action_names_and_types = get_action_names_and_types(node=node) 33 | 34 | for (action_name, action_types) in action_names_and_types: 35 | if args.action_name == action_name: 36 | for action_type in action_types: 37 | print(action_type) 38 | return 0 39 | 40 | return 1 41 | -------------------------------------------------------------------------------- /ros2action/setup.py: -------------------------------------------------------------------------------- 1 | from setuptools import find_packages 2 | from setuptools import setup 3 | 4 | package_name = 'ros2action' 5 | 6 | setup( 7 | name=package_name, 8 | version='0.39.0', 9 | packages=find_packages(exclude=['test']), 10 | data_files=[ 11 | ('share/' + package_name, ['package.xml']), 12 | ('share/ament_index/resource_index/packages', 13 | ['resource/' + package_name]), 14 | ], 15 | install_requires=['ros2cli'], 16 | zip_safe=True, 17 | author='Jacob Perron', 18 | author_email='jacob@openrobotics.org', 19 | maintainer='Audrow Nash, Geoffrey Biggs', 20 | maintainer_email='audrow@openrobotics.org, geoff@openrobotics.org', 21 | url='https://github.com/ros2/ros2cli/tree/master/ros2action', 22 | download_url='https://github.com/ros2/ros2cli/releases', 23 | keywords=[], 24 | classifiers=[ 25 | 'Environment :: Console', 26 | 'Intended Audience :: Developers', 27 | 'License :: OSI Approved :: Apache Software License', 28 | 'Programming Language :: Python', 29 | ], 30 | description='The action command for ROS 2 command line tools.', 31 | long_description="""\ 32 | The package provides the action command for the ROS 2 command line tools.""", 33 | license='Apache License, Version 2.0', 34 | tests_require=['pytest'], 35 | entry_points={ 36 | 'ros2cli.command': [ 37 | 'action = ros2action.command.action:ActionCommand', 38 | ], 39 | 'ros2cli.extension_point': [ 40 | 'ros2action.verb = ros2action.verb:VerbExtension', 41 | ], 42 | 'ros2action.verb': [ 43 | 'info = ros2action.verb.info:InfoVerb', 44 | 'list = ros2action.verb.list:ListVerb', 45 | 'send_goal = ros2action.verb.send_goal:SendGoalVerb', 46 | 'type = ros2action.verb.type:TypeVerb', 47 | 'find = ros2action.verb.find:FindVerb', 48 | 'echo = ros2action.verb.echo:EchoVerb', 49 | ], 50 | } 51 | ) 52 | -------------------------------------------------------------------------------- /ros2action/test/test_api.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2action.api import get_action_clients_and_servers 16 | from ros2action.api import get_action_names 17 | from ros2cli.node.strategy import DirectNode 18 | 19 | 20 | def test_get_action_clients_and_servers(): 21 | with DirectNode(None) as node: 22 | clients, servers = get_action_clients_and_servers( 23 | node=node, 24 | action_name='/test_action_name', 25 | ) 26 | assert len(clients) == 0 27 | assert len(servers) == 0 28 | 29 | 30 | def test_get_action_names(): 31 | with DirectNode(None) as node: 32 | get_action_names(node=node) 33 | -------------------------------------------------------------------------------- /ros2action/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.copyright 20 | @pytest.mark.linter 21 | def test_copyright(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2action/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @pytest.mark.flake8 20 | @pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /ros2action/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /ros2action/test/test_xmllint.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_xmllint.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.xmllint 21 | def test_xmllint(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2cli/colcon.pkg: -------------------------------------------------------------------------------- 1 | { 2 | "hooks": [ 3 | "share/ros2cli/environment/ros2-argcomplete.bash", 4 | "share/ros2cli/environment/ros2-argcomplete.zsh" 5 | ] 6 | } 7 | -------------------------------------------------------------------------------- /ros2cli/completion/ros2-argcomplete.bash: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | if type register-python-argcomplete3 > /dev/null 2>&1; then 16 | eval "$(register-python-argcomplete3 ros2)" 17 | elif type register-python-argcomplete > /dev/null 2>&1; then 18 | eval "$(register-python-argcomplete ros2)" 19 | fi 20 | -------------------------------------------------------------------------------- /ros2cli/completion/ros2-argcomplete.zsh: -------------------------------------------------------------------------------- 1 | # Copyright 2017-2018 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | if (( ! ${+_comps} )); then 16 | autoload -U +X compinit && compinit 17 | fi 18 | autoload -U +X bashcompinit && bashcompinit 19 | 20 | # Get this scripts directory 21 | __ros2cli_completion_dir=${0:a:h} 22 | # Just source the bash version, it works in zsh too 23 | source "$__ros2cli_completion_dir/ros2-argcomplete.bash" 24 | # Cleanup 25 | unset __ros2cli_completion_dir 26 | -------------------------------------------------------------------------------- /ros2cli/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros2cli 5 | 0.39.0 6 | 7 | Framework for ROS 2 command line tools. 8 | 9 | 10 | Audrow Nash 11 | Geoffrey Biggs 12 | 13 | Apache License 2.0 14 | 15 | Aditya Pande 16 | Dirk Thomas 17 | Mabel Zhang 18 | Michael Jeronimo 19 | 20 | python3-argcomplete 21 | python3-importlib-metadata 22 | python3-packaging 23 | python3-psutil 24 | rclpy 25 | 26 | ament_copyright 27 | ament_flake8 28 | ament_pep257 29 | ament_xmllint 30 | python3-pytest 31 | python3-pytest-timeout 32 | test_msgs 33 | 34 | 35 | ament_python 36 | 37 | 38 | -------------------------------------------------------------------------------- /ros2cli/resource/package.dsv: -------------------------------------------------------------------------------- 1 | source;share/ros2cli/environment/ros2-argcomplete.bash 2 | source;share/ros2cli/environment/ros2-argcomplete.zsh 3 | -------------------------------------------------------------------------------- /ros2cli/resource/ros2cli: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2cli/resource/ros2cli -------------------------------------------------------------------------------- /ros2cli/ros2cli/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2cli/ros2cli/__init__.py -------------------------------------------------------------------------------- /ros2cli/ros2cli/command/daemon.py: -------------------------------------------------------------------------------- 1 | # Copyright 2016-2017 Dirk Thomas 2 | # Copyright 2017 Open Source Robotics Foundation, Inc. 3 | # 4 | # Licensed under the Apache License, Version 2.0 (the "License"); 5 | # you may not use this file except in compliance with the License. 6 | # You may obtain a copy of the License at 7 | # 8 | # http://www.apache.org/licenses/LICENSE-2.0 9 | # 10 | # Unless required by applicable law or agreed to in writing, software 11 | # distributed under the License is distributed on an "AS IS" BASIS, 12 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | # See the License for the specific language governing permissions and 14 | # limitations under the License. 15 | 16 | from ros2cli.command import add_subparsers_on_demand 17 | from ros2cli.command import CommandExtension 18 | 19 | 20 | class DaemonCommand(CommandExtension): 21 | """Various daemon related sub-commands.""" 22 | 23 | def add_arguments(self, parser, cli_name): 24 | self._subparser = parser 25 | # add arguments and sub-commands of verbs 26 | add_subparsers_on_demand( 27 | parser, cli_name, '_verb', 'ros2cli.daemon.verb', required=False) 28 | 29 | def main(self, *, parser, args): 30 | if not hasattr(args, '_verb'): 31 | # in case no verb was passed 32 | self._subparser.print_help() 33 | return 0 34 | 35 | extension = getattr(args, '_verb') 36 | 37 | # call the verb's main method 38 | return extension.main(args=args) 39 | -------------------------------------------------------------------------------- /ros2cli/ros2cli/node/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright 2018 Amazon.com, Inc. or its affiliates. All Rights Reserved. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | from rclpy.node import HIDDEN_NODE_PREFIX 15 | NODE_NAME_PREFIX = str(HIDDEN_NODE_PREFIX) + 'ros2cli' 16 | -------------------------------------------------------------------------------- /ros2cli/ros2cli/verb/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright 2016-2017 Dirk Thomas 2 | # Copyright 2017 Open Source Robotics Foundation, Inc. 3 | # 4 | # Licensed under the Apache License, Version 2.0 (the "License"); 5 | # you may not use this file except in compliance with the License. 6 | # You may obtain a copy of the License at 7 | # 8 | # http://www.apache.org/licenses/LICENSE-2.0 9 | # 10 | # Unless required by applicable law or agreed to in writing, software 11 | # distributed under the License is distributed on an "AS IS" BASIS, 12 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 13 | # See the License for the specific language governing permissions and 14 | # limitations under the License. 15 | 16 | from ros2cli.plugin_system import instantiate_extensions 17 | from ros2cli.plugin_system import PLUGIN_SYSTEM_VERSION 18 | from ros2cli.plugin_system import satisfies_version 19 | 20 | 21 | class VerbExtension: 22 | """ 23 | The interface for verb extensions. 24 | 25 | The following properties must be defined: 26 | * `NAME` (will be set to the entry point name) 27 | 28 | The following methods must be defined: 29 | * `main` 30 | """ 31 | 32 | NAME = None 33 | EXTENSION_POINT_VERSION = '0.1' 34 | 35 | def __init__(self): 36 | super(VerbExtension, self).__init__() 37 | satisfies_version(PLUGIN_SYSTEM_VERSION, '^0.1') 38 | 39 | 40 | def get_verb_extensions(name): 41 | extensions = instantiate_extensions(name) 42 | for name, extension in extensions.items(): 43 | extension.NAME = name 44 | return extensions 45 | 46 | 47 | def add_task_arguments(parser, task_name): 48 | plugins = get_verb_extensions(task_name) 49 | for plugin_name, plugin in plugins.items(): 50 | group = parser.add_argument_group( 51 | title=f"Arguments for '{plugin_name}' packages") 52 | func = getattr(plugin, 'add_%s_arguments' % task_name, None) 53 | if func: 54 | func(group) 55 | -------------------------------------------------------------------------------- /ros2cli/ros2cli/verb/daemon/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.plugin_system import PLUGIN_SYSTEM_VERSION 16 | from ros2cli.plugin_system import satisfies_version 17 | 18 | 19 | class VerbExtension: 20 | """ 21 | The extension point for 'daemon' verb extensions. 22 | 23 | The following properties must be defined: 24 | * `NAME` (will be set to the entry point name) 25 | 26 | The following methods must be defined: 27 | * `main` 28 | 29 | The following methods can be defined: 30 | * `add_arguments` 31 | """ 32 | 33 | NAME = None 34 | EXTENSION_POINT_VERSION = '0.1' 35 | 36 | def __init__(self): 37 | super(VerbExtension, self).__init__() 38 | satisfies_version(PLUGIN_SYSTEM_VERSION, '^0.1') 39 | 40 | def add_arguments(self, parser, cli_name): 41 | pass 42 | 43 | def main(self, *, args): 44 | raise NotImplementedError() 45 | -------------------------------------------------------------------------------- /ros2cli/ros2cli/verb/daemon/start.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.node.daemon import spawn_daemon 16 | from ros2cli.verb.daemon import VerbExtension 17 | 18 | 19 | class StartVerb(VerbExtension): 20 | """Start the daemon if it isn't running.""" 21 | 22 | def add_arguments(self, parser, cli_name): 23 | parser.add_argument( 24 | '--debug', '-d', action='store_true', 25 | help='Print debug messages') 26 | 27 | def main(self, *, args): 28 | if spawn_daemon(args, timeout=10.0, debug=args.debug): 29 | print('The daemon has been started') 30 | else: 31 | print('The daemon is already running') 32 | -------------------------------------------------------------------------------- /ros2cli/ros2cli/verb/daemon/status.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.node.daemon import is_daemon_running 16 | from ros2cli.verb.daemon import VerbExtension 17 | 18 | 19 | class StatusVerb(VerbExtension): 20 | """Output the status of the daemon.""" 21 | 22 | def main(self, *, args): 23 | if is_daemon_running(args): 24 | print('The daemon is running') 25 | else: 26 | print('The daemon is not running') 27 | -------------------------------------------------------------------------------- /ros2cli/ros2cli/verb/daemon/stop.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.node.daemon import shutdown_daemon 16 | from ros2cli.verb.daemon import VerbExtension 17 | 18 | 19 | class StopVerb(VerbExtension): 20 | """Stop the daemon if it is running.""" 21 | 22 | def main(self, *, args): 23 | if shutdown_daemon(args, timeout=10.0): 24 | print('The daemon has been stopped') 25 | else: 26 | print('The daemon is not running') 27 | -------------------------------------------------------------------------------- /ros2cli/ros2cli/xmlrpc/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright 2020 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | # Force custom xmlrpc (un)marshalling logic importation. 16 | from . import marshal # noqa: F401 17 | -------------------------------------------------------------------------------- /ros2cli/ros2cli/xmlrpc/client.py: -------------------------------------------------------------------------------- 1 | # Copyright 2020 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | # Alias xmlrpc.client module objects to ensure client code uses ros2cli.xmlrpc 16 | from xmlrpc.client import ProtocolError 17 | from xmlrpc.client import ServerProxy 18 | 19 | 20 | __all__ = [ 21 | 'ProtocolError', 22 | 'ServerProxy' 23 | ] 24 | -------------------------------------------------------------------------------- /ros2cli/ros2cli/xmlrpc/local_server.py: -------------------------------------------------------------------------------- 1 | # Copyright 2020 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | import os 16 | import socket 17 | # Import SimpleXMLRPCRequestHandler to re-export it. 18 | from xmlrpc.server import SimpleXMLRPCRequestHandler # noqa 19 | from xmlrpc.server import SimpleXMLRPCServer 20 | 21 | import psutil 22 | 23 | 24 | def get_local_ipaddrs(): 25 | return [ 26 | addr.address 27 | for _, addrs in psutil.net_if_addrs().items() 28 | for addr in addrs 29 | if addr.family == socket.AF_INET 30 | ] 31 | 32 | 33 | class LocalXMLRPCServer(SimpleXMLRPCServer): 34 | 35 | # Allow re-binding even if another server instance was recently bound (i.e. we are still in 36 | # TCP TIME_WAIT). This is already the default behavior on Windows, and further SO_REUSEADDR can 37 | # lead to undefined behavior on Windows; see 38 | # https://learn.microsoft.com/en-us/windows/win32/winsock/using-so-reuseaddr-and-so-exclusiveaddruse. # noqa 39 | # So we don't set the option for Windows. 40 | allow_reuse_address = False if os.name == 'nt' else True 41 | 42 | def verify_request(self, request, client_address): 43 | if client_address[0] not in get_local_ipaddrs(): 44 | return False 45 | return super(LocalXMLRPCServer, self).verify_request(request, client_address) 46 | -------------------------------------------------------------------------------- /ros2cli/ros2cli/xmlrpc/marshal/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright 2020 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | # Force rclpy specific xmlrpc (un)marshalling logic importation. 16 | from . import rclpy # noqa: F401 17 | -------------------------------------------------------------------------------- /ros2cli/ros2cli/xmlrpc/marshal/generic.py: -------------------------------------------------------------------------------- 1 | # Copyright 2020 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | 16 | def fullname(klass): 17 | return f'{klass.__module__}.{klass.__name__}' 18 | 19 | 20 | def end_any_with_slots(unmarshaller, data, type_): 21 | unmarshaller._stack[-1] = type_(**unmarshaller._stack[-1]) 22 | unmarshaller._value = 0 23 | 24 | 25 | def dump_any_with_slots(marshaller, value, write, transform=None): 26 | write(f'<{fullname(type(value))}>') 27 | slots = value.__slots__ 28 | if transform is not None: 29 | slots = map(transform, slots) 30 | marshaller.dump_struct({name: getattr(value, name) for name in slots}, write) 31 | write(f'') 32 | 33 | 34 | def end_any_enum(unmarshaller, data, enum_): 35 | unmarshaller.append(enum_(int(data))) 36 | unmarshaller._value = 0 37 | 38 | 39 | def dump_any_enum(marshaller, value, write): 40 | write(f'<{fullname(type(value))}>') 41 | write(str(value.value)) 42 | write(f'') 43 | -------------------------------------------------------------------------------- /ros2cli/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.copyright 20 | @pytest.mark.linter 21 | def test_copyright(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2cli/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @pytest.mark.flake8 20 | @pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /ros2cli/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /ros2cli/test/test_xmllint.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_xmllint.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.xmllint 21 | def test_xmllint(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2cli_test_interfaces/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | project(ros2cli_test_interfaces) 3 | 4 | # Default to C++17 5 | if(NOT CMAKE_CXX_STANDARD) 6 | set(CMAKE_CXX_STANDARD 17) 7 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 8 | endif() 9 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 10 | add_compile_options(-Wall -Wextra -Wpedantic) 11 | endif() 12 | 13 | find_package(ament_cmake REQUIRED) 14 | find_package(rosidl_default_generators REQUIRED) 15 | 16 | rosidl_generate_interfaces(${PROJECT_NAME} 17 | "action/ShortVariedMultiNested.action" 18 | "msg/ShortVaried.msg" 19 | "msg/ShortVariedMultiNested.msg" 20 | "msg/ShortVariedNested.msg" 21 | "srv/ShortVariedMultiNested.srv" 22 | ADD_LINTER_TESTS 23 | ) 24 | 25 | ament_export_dependencies(rosidl_default_runtime) 26 | 27 | ament_package() 28 | -------------------------------------------------------------------------------- /ros2cli_test_interfaces/action/ShortVariedMultiNested.action: -------------------------------------------------------------------------------- 1 | # Goal definition 2 | ShortVariedNested short_varied_nested # Comment - Nesting Level 3: 1 of 2 3 | --- 4 | # Result definition 5 | bool bool_value # Comment - Nesting Level 3: 2 of 2 6 | --- 7 | # Feedback definition 8 | bool[3] bool_values 9 | -------------------------------------------------------------------------------- /ros2cli_test_interfaces/msg/ShortVaried.msg: -------------------------------------------------------------------------------- 1 | # A constant 2 | bool BOOL_CONST=true # Comment - Nesting Level 1: 1 of 2 3 | 4 | # Bool and array of bools 5 | bool bool_value 6 | bool[<=3] bool_values # Comment - Nesting Level 1: 2 of 2 7 | 8 | # Trailing comment 9 | -------------------------------------------------------------------------------- /ros2cli_test_interfaces/msg/ShortVariedMultiNested.msg: -------------------------------------------------------------------------------- 1 | # A short, varied, and nested type 2 | ShortVariedNested short_varied_nested # Comment - Nesting Level 3: 1 of 1 3 | # Trailing comment 4 | -------------------------------------------------------------------------------- /ros2cli_test_interfaces/msg/ShortVariedNested.msg: -------------------------------------------------------------------------------- 1 | # A short, varied type 2 | ShortVaried short_varied # Comment - Nesting Level 2: 1 of 1 3 | # Trailing comment 4 | -------------------------------------------------------------------------------- /ros2cli_test_interfaces/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros2cli_test_interfaces 5 | 0.39.0 6 | A package containing interface definitions for testing ros2cli. 7 | 8 | Audrow Nash 9 | Geoffrey Biggs 10 | 11 | Apache License 2.0 12 | 13 | Aditya Pande 14 | Audrow Nash 15 | Mabel Zhang 16 | Michael Jeronimo 17 | 18 | ament_cmake 19 | 20 | rosidl_default_generators 21 | 22 | rosidl_default_runtime 23 | 24 | ament_lint_common 25 | 26 | rosidl_interface_packages 27 | 28 | 29 | ament_cmake 30 | 31 | 32 | -------------------------------------------------------------------------------- /ros2cli_test_interfaces/srv/ShortVariedMultiNested.srv: -------------------------------------------------------------------------------- 1 | # Request 2 | ShortVariedNested short_varied_nested # Comment - Nesting Level 3: 1 of 2 3 | --- 4 | # Response 5 | bool bool_value # Comment - Nesting Level 3: 2 of 2 6 | -------------------------------------------------------------------------------- /ros2component/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros2component 5 | 0.39.0 6 | 7 | The component command for ROS 2 command line tools. 8 | 9 | 10 | Audrow Nash 11 | Geoffrey Biggs 12 | 13 | Apache License 2.0 14 | 15 | Aditya Pande 16 | Mabel Zhang 17 | Michael Jeronimo 18 | Michel Hidalgo 19 | 20 | ament_index_python 21 | composition_interfaces 22 | rcl_interfaces 23 | rclcpp_components 24 | rclpy 25 | ros2cli 26 | ros2node 27 | ros2param 28 | ros2pkg 29 | 30 | ament_copyright 31 | ament_flake8 32 | ament_pep257 33 | ament_xmllint 34 | python3-pytest 35 | python3-pytest-timeout 36 | 37 | 38 | ament_python 39 | 40 | 41 | -------------------------------------------------------------------------------- /ros2component/resource/ros2component: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2component/resource/ros2component -------------------------------------------------------------------------------- /ros2component/ros2component/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2component/ros2component/__init__.py -------------------------------------------------------------------------------- /ros2component/ros2component/command/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2component/ros2component/command/__init__.py -------------------------------------------------------------------------------- /ros2component/ros2component/command/component.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.command import add_subparsers_on_demand 16 | from ros2cli.command import CommandExtension 17 | 18 | 19 | class ComponentCommand(CommandExtension): 20 | """Various component related sub-commands.""" 21 | 22 | def add_arguments(self, parser, cli_name): 23 | self._subparser = parser 24 | # add arguments and sub-commands of verbs 25 | add_subparsers_on_demand( 26 | parser, cli_name, '_verb', 'ros2component.verb', required=False) 27 | 28 | def main(self, *, parser, args): 29 | if not hasattr(args, '_verb'): 30 | # in case no verb was passed 31 | self._subparser.print_help() 32 | return 0 33 | 34 | extension = getattr(args, '_verb') 35 | 36 | # call the verb's main method 37 | return extension.main(args=args) 38 | -------------------------------------------------------------------------------- /ros2component/ros2component/verb/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.plugin_system import PLUGIN_SYSTEM_VERSION 16 | from ros2cli.plugin_system import satisfies_version 17 | 18 | 19 | class VerbExtension: 20 | """ 21 | The extension point for 'node' verb extensions. 22 | 23 | The following properties must be defined: 24 | * `NAME` (will be set to the entry point name) 25 | 26 | The following methods must be defined: 27 | * `main` 28 | 29 | The following methods can be defined: 30 | * `add_arguments` 31 | """ 32 | 33 | NAME = None 34 | EXTENSION_POINT_VERSION = '0.1' 35 | 36 | def __init__(self): 37 | super(VerbExtension, self).__init__() 38 | satisfies_version(PLUGIN_SYSTEM_VERSION, '^0.1') 39 | 40 | def add_arguments(self, parser, cli_name): 41 | pass 42 | 43 | def main(self, *, args): 44 | raise NotImplementedError() 45 | -------------------------------------------------------------------------------- /ros2component/ros2component/verb/types.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2component.api import get_package_component_types 16 | from ros2component.api import get_registered_component_types 17 | from ros2component.verb import VerbExtension 18 | 19 | from ros2pkg.api import get_package_names 20 | from ros2pkg.api import package_name_completer 21 | 22 | 23 | class TypesVerb(VerbExtension): 24 | """Output a list of components registered in the ament index.""" 25 | 26 | def add_arguments(self, parser, cli_name): 27 | argument = parser.add_argument( 28 | 'package_name', nargs='?', default=None, 29 | help='Package name to look for registered components in' 30 | ) 31 | argument.completer = package_name_completer 32 | 33 | def main(self, *, args): 34 | if args.package_name is not None: 35 | if args.package_name not in get_package_names(): 36 | return "Unable to find package '" + args.package_name + "'" 37 | print(*get_package_component_types(package_name=args.package_name), sep='\n') 38 | else: 39 | for package_name, component_types in get_registered_component_types(): 40 | print(package_name) 41 | print(*[' ' + type_name for type_name in component_types], sep='\n') 42 | -------------------------------------------------------------------------------- /ros2component/setup.py: -------------------------------------------------------------------------------- 1 | from setuptools import find_packages 2 | from setuptools import setup 3 | 4 | package_name = 'ros2component' 5 | 6 | setup( 7 | name=package_name, 8 | version='0.39.0', 9 | packages=find_packages(exclude=['test']), 10 | data_files=[ 11 | ('share/' + package_name, ['package.xml']), 12 | ('share/ament_index/resource_index/packages', 13 | ['resource/' + package_name]), 14 | ], 15 | install_requires=['ros2cli'], 16 | zip_safe=True, 17 | author='Michel Hidalgo', 18 | author_email='michel@ekumenlabs.com', 19 | maintainer='Audrow Nash, Geoffrey Biggs', 20 | maintainer_email='audrow@openrobotics.org, geoff@openrobotics.org', 21 | url='https://github.com/ros2/ros2cli/tree/master/ros2component', 22 | download_url='https://github.com/ros2/ros2cli/releases', 23 | keywords=[], 24 | classifiers=[ 25 | 'Environment :: Console', 26 | 'Intended Audience :: Developers', 27 | 'License :: OSI Approved :: Apache Software License', 28 | 'Programming Language :: Python', 29 | ], 30 | description='The component command for ROS 2 command line tools.', 31 | long_description="""\ 32 | The package provides the component command for the ROS 2 command line tools.""", 33 | license='Apache License, Version 2.0', 34 | tests_require=['pytest'], 35 | entry_points={ 36 | 'ros2cli.command': [ 37 | 'component = ros2component.command.component:ComponentCommand', 38 | ], 39 | 'ros2cli.extension_point': [ 40 | 'ros2component.verb = ros2component.verb:VerbExtension', 41 | ], 42 | 'ros2component.verb': [ 43 | 'list = ros2component.verb.list:ListVerb', 44 | 'load = ros2component.verb.load:LoadVerb', 45 | 'standalone = ros2component.verb.standalone:StandaloneVerb', 46 | 'types = ros2component.verb.types:TypesVerb', 47 | 'unload = ros2component.verb.unload:UnloadVerb', 48 | ], 49 | } 50 | ) 51 | -------------------------------------------------------------------------------- /ros2component/test/test_api.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.node.direct import DirectNode 16 | from ros2cli.node.strategy import NodeStrategy 17 | 18 | from ros2component.api import find_container_node_names 19 | from ros2component.api import get_package_component_types 20 | 21 | from ros2node.api import get_node_names 22 | 23 | 24 | def test_find_container_node_names(): 25 | """Test find_container_node_names() API function.""" 26 | with NodeStrategy([]) as node: 27 | node_names = get_node_names(node=node) 28 | 29 | with DirectNode([]) as node: 30 | assert len(find_container_node_names( 31 | node=node, node_names=node_names 32 | )) == 0 33 | 34 | assert len(find_container_node_names( 35 | node=node, node_names=[] 36 | )) == 0 37 | 38 | 39 | def test_get_package_component_types(): 40 | """Test get_package_component_types() API function.""" 41 | assert len(get_package_component_types(package_name='ros2component')) == 0 42 | -------------------------------------------------------------------------------- /ros2component/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.copyright 20 | @pytest.mark.linter 21 | def test_copyright(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2component/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @pytest.mark.flake8 20 | @pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /ros2component/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /ros2component/test/test_xmllint.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_xmllint.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.xmllint 21 | def test_xmllint(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2doctor/README.md: -------------------------------------------------------------------------------- 1 | # ros2doctor 2 | 3 | This folder contains the source code for ros2doctor. 4 | It is one of the ROS 2 command line interface tools included with a standard install of any ROS 2 distro. 5 | `ros2doctor` is similar to `roswtf` from ROS 1. 6 | It will examine your ROS 2 setup, such as distribution, platform, network interface, etc., and look for potential issues in a running ROS 2 system. 7 | 8 | ## Usage 9 | 10 | Run `ros2 doctor` or `ros2 wtf`(alias) to conduct checks. 11 | 12 | Run `ros2 doctor -h/--help` to print all available command arguments. 13 | 14 | Run `ros2 doctor -r/--report` to see report of all checked items. 15 | 16 | Run `ros2 doctor -rf/--report-fail` to see report of failed checks only. 17 | 18 | Run `ros2 doctor -iw/--include-warnings` to include warnings as failed checks. 19 | `-iw` and `-rf` can be used in combination. 20 | 21 | Run `ros2 doctor -ep/--exclude-packages` to exclude package checks or report. 22 | 23 | 24 | ## Add New Checks 25 | 26 | To add your own checks or information to report, use [Python entry points](https://setuptools.readthedocs.io/en/latest/pkg_resources.html#entry-points) to add modules to `setup.py`. 27 | See example below: 28 | 29 | ```python 30 | entry_points={ 31 | 'ros2doctor.checks': [ 32 | 'PlatformCheck = ros2doctor.api.platform:PlatformCheck', 33 | 'NetworkCheck = ros2doctor.api.network:NetworkCheck', 34 | ], 35 | 'ros2doctor.report': [ 36 | 'PlatformReport = ros2doctor.api.platform:PlatformReport', 37 | 'NetworkReport = ros2doctor.api.network:NetworkReport', 38 | ], 39 | } 40 | ``` 41 | -------------------------------------------------------------------------------- /ros2doctor/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros2doctor 5 | 0.39.0 6 | A command line tool to check potential issues in a ROS 2 system 7 | 8 | Audrow Nash 9 | Geoffrey Biggs 10 | 11 | Apache License 2.0 12 | 13 | Aditya Pande 14 | Claire Wang 15 | Mabel Zhang 16 | Michael Jeronimo 17 | 18 | ament_index_python 19 | python3-catkin-pkg-modules 20 | python3-psutil 21 | python3-importlib-metadata 22 | python3-rosdistro-modules 23 | rclpy 24 | ros2cli 25 | ros_environment 26 | std_msgs 27 | 28 | ament_copyright 29 | ament_flake8 30 | ament_pep257 31 | ament_xmllint 32 | launch 33 | launch_ros 34 | launch_testing 35 | launch_testing_ros 36 | python3-pytest 37 | python3-pytest-timeout 38 | std_msgs 39 | 40 | 41 | ament_python 42 | 43 | 44 | -------------------------------------------------------------------------------- /ros2doctor/resource/ros2doctor: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2doctor/resource/ros2doctor -------------------------------------------------------------------------------- /ros2doctor/ros2doctor/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2doctor/ros2doctor/__init__.py -------------------------------------------------------------------------------- /ros2doctor/ros2doctor/api/rmw.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from rclpy.utilities import get_rmw_implementation_identifier 16 | from ros2doctor.api import DoctorReport 17 | from ros2doctor.api import Report 18 | 19 | 20 | class RMWReport(DoctorReport): 21 | """Report current RMW information.""" 22 | 23 | def category(self): 24 | return 'middleware' 25 | 26 | def report(self): 27 | rmw_report = Report('RMW MIDDLEWARE') 28 | rmw_report.add_to_report('middleware name', get_rmw_implementation_identifier()) 29 | return rmw_report 30 | -------------------------------------------------------------------------------- /ros2doctor/ros2doctor/command/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2doctor/ros2doctor/command/__init__.py -------------------------------------------------------------------------------- /ros2doctor/ros2doctor/verb/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright 2020 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.plugin_system import PLUGIN_SYSTEM_VERSION 16 | from ros2cli.plugin_system import satisfies_version 17 | 18 | 19 | class VerbExtension: 20 | """ 21 | The extension point for 'doctor' verb extensions. 22 | 23 | The following properties must be defined: 24 | * `NAME` (will be set to the entry point name) 25 | 26 | The following methods must be defined: 27 | * `main` 28 | 29 | The following methods can be defined: 30 | * `add_arguments` 31 | """ 32 | 33 | NAME = None 34 | EXTENSION_POINT_VERSION = '0.1' 35 | 36 | def __init__(self): 37 | super(VerbExtension, self).__init__() 38 | satisfies_version(PLUGIN_SYSTEM_VERSION, '^0.1') 39 | 40 | def add_arguments(self, parser, cli_name): 41 | pass 42 | 43 | def main(self, *, args): 44 | raise NotImplementedError() 45 | -------------------------------------------------------------------------------- /ros2doctor/test/fixtures/listener_node_with_reliable_qos.py: -------------------------------------------------------------------------------- 1 | # Copyright 2021 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | import rclpy 16 | from rclpy.executors import ExternalShutdownException 17 | from rclpy.node import Node 18 | from rclpy.qos import QoSProfile 19 | from rclpy.qos import QoSReliabilityPolicy 20 | 21 | from std_msgs.msg import String 22 | 23 | 24 | class ListenerNode(Node): 25 | 26 | def __init__(self): 27 | super().__init__('listener') 28 | qos_profile = QoSProfile( 29 | depth=1, 30 | reliability=QoSReliabilityPolicy.RELIABLE, 31 | ) 32 | self.sub = self.create_subscription( 33 | String, 'chatter', self.callback, qos_profile 34 | ) 35 | 36 | def callback(self, msg): 37 | self.get_logger().info('I heard: [%s]' % msg.data) 38 | 39 | 40 | def main(args=None): 41 | try: 42 | with rclpy.init(args=args): 43 | node = ListenerNode() 44 | rclpy.spin(node) 45 | except (KeyboardInterrupt, ExternalShutdownException): 46 | print('listener stopped cleanly') 47 | 48 | 49 | if __name__ == '__main__': 50 | main() 51 | -------------------------------------------------------------------------------- /ros2doctor/test/fixtures/talker_node_with_best_effort_qos.py: -------------------------------------------------------------------------------- 1 | # Copyright 2021 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | import rclpy 16 | from rclpy.executors import ExternalShutdownException 17 | from rclpy.node import Node 18 | from rclpy.qos import QoSProfile 19 | from rclpy.qos import QoSReliabilityPolicy 20 | 21 | from std_msgs.msg import String 22 | 23 | 24 | class TalkerNode(Node): 25 | 26 | def __init__(self): 27 | super().__init__('talker_node') 28 | qos_profile = QoSProfile( 29 | depth=1, 30 | reliability=QoSReliabilityPolicy.BEST_EFFORT, 31 | ) 32 | self.count = 1 33 | self.pub = self.create_publisher(String, 'chatter', qos_profile=qos_profile) 34 | self.tmr = self.create_timer(1.0, self.callback) 35 | 36 | def callback(self): 37 | self.pub.publish(String(data='Hello World: {0}'.format(self.count))) 38 | self.count += 1 39 | 40 | 41 | def main(args=None): 42 | try: 43 | with rclpy.init(args=args): 44 | node = TalkerNode() 45 | rclpy.spin(node) 46 | except (KeyboardInterrupt, ExternalShutdownException): 47 | print('talker stopped cleanly') 48 | 49 | 50 | if __name__ == '__main__': 51 | main() 52 | -------------------------------------------------------------------------------- /ros2doctor/test/fixtures/talker_node_with_reliable_qos.py: -------------------------------------------------------------------------------- 1 | # Copyright 2021 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | import rclpy 16 | from rclpy.executors import ExternalShutdownException 17 | from rclpy.node import Node 18 | from rclpy.qos import QoSProfile 19 | from rclpy.qos import QoSReliabilityPolicy 20 | 21 | from std_msgs.msg import String 22 | 23 | 24 | class TalkerNode(Node): 25 | 26 | def __init__(self): 27 | super().__init__('talker_node') 28 | qos_profile = QoSProfile( 29 | depth=1, 30 | reliability=QoSReliabilityPolicy.RELIABLE, 31 | ) 32 | self.count = 1 33 | self.pub = self.create_publisher(String, 'chatter', qos_profile=qos_profile) 34 | self.tmr = self.create_timer(1.0, self.callback) 35 | 36 | def callback(self): 37 | self.pub.publish(String(data='Hello World: {0}'.format(self.count))) 38 | self.count += 1 39 | 40 | 41 | def main(args=None): 42 | try: 43 | with rclpy.init(args=args): 44 | node = TalkerNode() 45 | rclpy.spin(node) 46 | except (KeyboardInterrupt, ExternalShutdownException): 47 | print('talker stopped cleanly') 48 | 49 | 50 | if __name__ == '__main__': 51 | main() 52 | -------------------------------------------------------------------------------- /ros2doctor/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.copyright 20 | @pytest.mark.linter 21 | def test_copyright(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2doctor/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @pytest.mark.flake8 20 | @pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /ros2doctor/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /ros2doctor/test/test_xmllint.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_xmllint.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.xmllint 21 | def test_xmllint(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2interface/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros2interface 5 | 0.39.0 6 | 7 | The interface command for ROS 2 command line tools 8 | 9 | 10 | Audrow Nash 11 | Geoffrey Biggs 12 | 13 | Apache License 2.0 14 | 15 | Aditya Pande 16 | Jacob Perron 17 | Mabel Zhang 18 | Michael Jeronimo 19 | Siddharth Kucheria 20 | 21 | ament_index_python 22 | ros2cli 23 | rosidl_adapter 24 | rosidl_runtime_py 25 | 26 | ament_copyright 27 | ament_flake8 28 | ament_pep257 29 | ament_xmllint 30 | launch 31 | launch_testing 32 | launch_testing_ros 33 | python3-pytest 34 | python3-pytest-timeout 35 | ros2cli_test_interfaces 36 | test_msgs 37 | 38 | 39 | ament_python 40 | 41 | 42 | -------------------------------------------------------------------------------- /ros2interface/resource/ros2interface: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2interface/resource/ros2interface -------------------------------------------------------------------------------- /ros2interface/ros2interface/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2interface/ros2interface/__init__.py -------------------------------------------------------------------------------- /ros2interface/ros2interface/command/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2interface/ros2interface/command/__init__.py -------------------------------------------------------------------------------- /ros2interface/ros2interface/command/interface.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.command import add_subparsers_on_demand 16 | from ros2cli.command import CommandExtension 17 | 18 | 19 | class InterfaceCommand(CommandExtension): 20 | """Show information about ROS interfaces.""" 21 | 22 | def add_arguments(self, parser, cli_name): 23 | self._subparser = parser 24 | # add arguments and sub-commands of verbs 25 | add_subparsers_on_demand( 26 | parser, cli_name, '_verb', 'ros2interface.verb', required=False) 27 | 28 | def main(self, *, parser, args): 29 | if not hasattr(args, '_verb'): 30 | # in case no verb was passed 31 | self._subparser.print_help() 32 | return 0 33 | extension = getattr(args, '_verb') 34 | # call verb's main method 35 | return extension.main(args=args) 36 | -------------------------------------------------------------------------------- /ros2interface/ros2interface/verb/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.plugin_system import PLUGIN_SYSTEM_VERSION 16 | from ros2cli.plugin_system import satisfies_version 17 | 18 | 19 | class VerbExtension: 20 | """Extension point for 'interface' verb extensions.""" 21 | 22 | NAME = None 23 | EXTENSION_POINT_VERSION = '0.1' 24 | 25 | def __init__(self): 26 | super(VerbExtension, self).__init__() 27 | satisfies_version(PLUGIN_SYSTEM_VERSION, '^0.1') 28 | 29 | def add_arguments(self, parser, cli_name): 30 | pass 31 | 32 | def main(self, *, args): 33 | raise NotImplementedError() 34 | -------------------------------------------------------------------------------- /ros2interface/ros2interface/verb/proto.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Canonical Ldt. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2interface.api import interface_to_yaml 16 | from ros2interface.api import type_completer 17 | from ros2interface.verb import VerbExtension 18 | 19 | 20 | class ProtoVerb(VerbExtension): 21 | """Output an interface prototype.""" 22 | 23 | def add_arguments(self, parser, cli_name): 24 | arg = parser.add_argument( 25 | 'type', 26 | help="Show an interface definition (e.g. 'example_interfaces/msg/String')") 27 | arg.completer = type_completer 28 | parser.add_argument( 29 | '--no-quotes', action='store_true', 30 | help='if true output has no outer quotes.') 31 | 32 | def main(self, *, args): 33 | yaml = interface_to_yaml(args.type) 34 | 35 | if args.no_quotes is True: 36 | print(yaml) 37 | else: 38 | print('"' + yaml + '"') 39 | -------------------------------------------------------------------------------- /ros2interface/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.copyright 20 | @pytest.mark.linter 21 | def test_copyright(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2interface/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @pytest.mark.flake8 20 | @pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /ros2interface/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /ros2interface/test/test_xmllint.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_xmllint.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.xmllint 21 | def test_xmllint(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2lifecycle/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros2lifecycle 5 | 0.39.0 6 | 7 | The lifecycle command for ROS 2 command line tools. 8 | 9 | 10 | Audrow Nash 11 | Geoffrey Biggs 12 | 13 | Apache License 2.0 14 | 15 | Aditya Pande 16 | Dirk Thomas 17 | Mabel Zhang 18 | Michael Jeronimo 19 | 20 | lifecycle_msgs 21 | rclpy 22 | ros2cli 23 | ros2node 24 | ros2service 25 | 26 | ament_copyright 27 | ament_flake8 28 | ament_pep257 29 | ament_xmllint 30 | launch 31 | launch_ros 32 | launch_testing 33 | launch_testing_ros 34 | python3-pytest 35 | python3-pytest-timeout 36 | ros2lifecycle_test_fixtures 37 | 38 | 39 | ament_python 40 | 41 | 42 | -------------------------------------------------------------------------------- /ros2lifecycle/resource/ros2lifecycle: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2lifecycle/resource/ros2lifecycle -------------------------------------------------------------------------------- /ros2lifecycle/ros2lifecycle/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2lifecycle/ros2lifecycle/__init__.py -------------------------------------------------------------------------------- /ros2lifecycle/ros2lifecycle/command/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2lifecycle/ros2lifecycle/command/__init__.py -------------------------------------------------------------------------------- /ros2lifecycle/ros2lifecycle/command/lifecycle.py: -------------------------------------------------------------------------------- 1 | # Copyright 2018 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.command import add_subparsers_on_demand 16 | from ros2cli.command import CommandExtension 17 | 18 | 19 | class LifecycleCommand(CommandExtension): 20 | """Various lifecycle related sub-commands.""" 21 | 22 | def add_arguments(self, parser, cli_name): 23 | self._subparser = parser 24 | 25 | # add arguments and sub-commands of verbs 26 | add_subparsers_on_demand( 27 | parser, cli_name, '_verb', 'ros2lifecycle.verb', required=False) 28 | 29 | def main(self, *, parser, args): 30 | if not hasattr(args, '_verb'): 31 | # in case no verb was passed 32 | self._subparser.print_help() 33 | return 0 34 | 35 | extension = getattr(args, '_verb') 36 | 37 | # call the verb's main method 38 | return extension.main(args=args) 39 | -------------------------------------------------------------------------------- /ros2lifecycle/ros2lifecycle/verb/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright 2018 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.plugin_system import PLUGIN_SYSTEM_VERSION 16 | from ros2cli.plugin_system import satisfies_version 17 | 18 | 19 | class VerbExtension: 20 | """ 21 | The extension point for 'lifecycle' verb extensions. 22 | 23 | The following properties must be defined: 24 | * `NAME` (will be set to the entry point name) 25 | 26 | The following methods must be defined: 27 | * `main` 28 | 29 | The following methods can be defined: 30 | * `add_arguments` 31 | """ 32 | 33 | NAME = None 34 | EXTENSION_POINT_VERSION = '0.1' 35 | 36 | def __init__(self): 37 | super(VerbExtension, self).__init__() 38 | satisfies_version(PLUGIN_SYSTEM_VERSION, '^0.1') 39 | 40 | def add_arguments(self, parser, cli_name): 41 | pass 42 | 43 | def main(self, *, args): 44 | raise NotImplementedError() 45 | -------------------------------------------------------------------------------- /ros2lifecycle/ros2lifecycle/verb/nodes.py: -------------------------------------------------------------------------------- 1 | # Copyright 2018 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.node.strategy import add_arguments 16 | from ros2cli.node.strategy import NodeStrategy 17 | from ros2lifecycle.api import get_node_names 18 | from ros2lifecycle.verb import VerbExtension 19 | 20 | 21 | class NodesVerb(VerbExtension): 22 | """Output a list of nodes with lifecycle.""" 23 | 24 | def add_arguments(self, parser, cli_name): # noqa: D102 25 | add_arguments(parser) 26 | parser.add_argument( 27 | '-a', '--all', action='store_true', 28 | help='Display all nodes even hidden ones') 29 | parser.add_argument( 30 | '-c', '--count-nodes', action='store_true', 31 | help='Only display the number of nodes discovered') 32 | 33 | def main(self, *, args): # noqa: D102 34 | with NodeStrategy(args) as node: 35 | node_names = get_node_names( 36 | node=node, include_hidden_nodes=args.all) 37 | 38 | if args.count_nodes: 39 | print(len(node_names)) 40 | elif node_names: 41 | # Ensure deterministic node name ordering 42 | print(*sorted({n.full_name for n in node_names}), sep='\n') 43 | -------------------------------------------------------------------------------- /ros2lifecycle/setup.py: -------------------------------------------------------------------------------- 1 | from setuptools import find_packages 2 | from setuptools import setup 3 | 4 | package_name = 'ros2lifecycle' 5 | 6 | setup( 7 | name=package_name, 8 | version='0.39.0', 9 | packages=find_packages(exclude=['test']), 10 | data_files=[ 11 | ('share/' + package_name, ['package.xml']), 12 | ('share/ament_index/resource_index/packages', 13 | ['resource/' + package_name]), 14 | ], 15 | install_requires=['ros2cli'], 16 | zip_safe=True, 17 | author='Dirk Thomas', 18 | author_email='dthomas@osrfoundation.org', 19 | maintainer='Audrow Nash, Geoffrey Biggs', 20 | maintainer_email='audrow@openrobotics.org, geoff@openrobotics.org', 21 | url='https://github.com/ros2/ros2cli/tree/master/ros2lifecycle', 22 | download_url='https://github.com/ros2/ros2cli/releases', 23 | keywords=[], 24 | classifiers=[ 25 | 'Environment :: Console', 26 | 'Intended Audience :: Developers', 27 | 'License :: OSI Approved :: Apache Software License', 28 | 'Programming Language :: Python', 29 | ], 30 | description='The lifecycle command for ROS 2 command line tools.', 31 | long_description="""\ 32 | The package provides the lifecycle command for the ROS 2 command line tools.""", 33 | license='Apache License, Version 2.0', 34 | tests_require=['pytest'], 35 | entry_points={ 36 | 'ros2cli.command': [ 37 | 'lifecycle = ros2lifecycle.command.lifecycle:LifecycleCommand', 38 | ], 39 | 'ros2cli.extension_point': [ 40 | 'ros2lifecycle.verb = ros2lifecycle.verb:VerbExtension', 41 | ], 42 | 'ros2lifecycle.verb': [ 43 | 'get = ros2lifecycle.verb.get:GetVerb', 44 | 'list = ros2lifecycle.verb.list:ListVerb', 45 | 'nodes = ros2lifecycle.verb.nodes:NodesVerb', 46 | 'set = ros2lifecycle.verb.set:SetVerb', 47 | ], 48 | } 49 | ) 50 | -------------------------------------------------------------------------------- /ros2lifecycle/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.copyright 20 | @pytest.mark.linter 21 | def test_copyright(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2lifecycle/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @pytest.mark.flake8 20 | @pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /ros2lifecycle/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /ros2lifecycle/test/test_xmllint.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_xmllint.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.xmllint 21 | def test_xmllint(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2lifecycle_test_fixtures/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | 3 | project(ros2lifecycle_test_fixtures) 4 | 5 | # Default to C++17 6 | if(NOT CMAKE_CXX_STANDARD) 7 | set(CMAKE_CXX_STANDARD 17) 8 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 9 | endif() 10 | 11 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 12 | add_compile_options(-Wall -Wextra -Wpedantic) 13 | endif() 14 | 15 | find_package(ament_cmake REQUIRED) 16 | find_package(rclcpp_lifecycle REQUIRED) 17 | find_package(rclcpp REQUIRED) 18 | 19 | add_executable(simple_lifecycle_node 20 | src/simple_lifecycle_node.cpp) 21 | 22 | target_link_libraries(simple_lifecycle_node PRIVATE 23 | rclcpp_lifecycle::rclcpp_lifecycle) 24 | 25 | install(TARGETS 26 | simple_lifecycle_node 27 | DESTINATION lib/${PROJECT_NAME}) 28 | 29 | if(BUILD_TESTING) 30 | find_package(ament_lint_auto REQUIRED) 31 | ament_lint_auto_find_test_dependencies() 32 | endif() 33 | 34 | ament_package() 35 | -------------------------------------------------------------------------------- /ros2lifecycle_test_fixtures/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros2lifecycle_test_fixtures 5 | 0.39.0 6 | Package containing fixture nodes for ros2lifecycle tests 7 | 8 | Audrow Nash 9 | Geoffrey Biggs 10 | 11 | Apache License 2.0 12 | 13 | Aditya Pande 14 | Mabel Zhang 15 | Michael Jeronimo 16 | Michel Hidalgo 17 | 18 | ament_cmake 19 | 20 | rclcpp 21 | rclcpp_lifecycle 22 | 23 | ament_lint_auto 24 | ament_lint_common 25 | 26 | 27 | ament_cmake 28 | 29 | 30 | -------------------------------------------------------------------------------- /ros2multicast/README.rst: -------------------------------------------------------------------------------- 1 | ros2multicast 2 | ============= 3 | 4 | The package provides the multicast command for the ROS 2 command line tools. 5 | 6 | The tool can be used to check if multicast UDP packets are passed between two endpoints. 7 | 8 | First invoke the following command on one machine: 9 | 10 | .. code-block:: bash 11 | 12 | $ ros2 multicast receive 13 | 14 | While the first machine is waiting for a packet to arrive invoke the following command on another machine: 15 | 16 | .. code-block:: bash 17 | 18 | $ ros2 multicast send 19 | 20 | When successful the first machine will output the received message "Hello World!". 21 | -------------------------------------------------------------------------------- /ros2multicast/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros2multicast 5 | 0.39.0 6 | 7 | The multicast command for ROS 2 command line tools. 8 | 9 | 10 | Audrow Nash 11 | Geoffrey Biggs 12 | 13 | Apache License 2.0 14 | 15 | Aditya Pande 16 | Dirk Thomas 17 | Mabel Zhang 18 | Michael Jeronimo 19 | 20 | ros2cli 21 | 22 | ament_copyright 23 | ament_flake8 24 | ament_pep257 25 | ament_xmllint 26 | python3-pytest 27 | python3-pytest-timeout 28 | 29 | 30 | ament_python 31 | 32 | 33 | -------------------------------------------------------------------------------- /ros2multicast/resource/ros2multicast: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2multicast/resource/ros2multicast -------------------------------------------------------------------------------- /ros2multicast/ros2multicast/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2multicast/ros2multicast/__init__.py -------------------------------------------------------------------------------- /ros2multicast/ros2multicast/command/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2multicast/ros2multicast/command/__init__.py -------------------------------------------------------------------------------- /ros2multicast/ros2multicast/command/multicast.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.command import add_subparsers_on_demand 16 | from ros2cli.command import CommandExtension 17 | 18 | 19 | class MulticastCommand(CommandExtension): 20 | """Various multicast related sub-commands.""" 21 | 22 | def add_arguments(self, parser, cli_name): 23 | self._subparser = parser 24 | # add arguments and sub-commands of verbs 25 | add_subparsers_on_demand( 26 | parser, cli_name, '_verb', 'ros2multicast.verb', required=False) 27 | 28 | def main(self, *, parser, args): 29 | if not hasattr(args, '_verb'): 30 | # in case no verb was passed 31 | self._subparser.print_help() 32 | return 0 33 | 34 | extension = getattr(args, '_verb') 35 | 36 | # call the verb's main method 37 | return extension.main(args=args) 38 | -------------------------------------------------------------------------------- /ros2multicast/ros2multicast/verb/receive.py: -------------------------------------------------------------------------------- 1 | # Copyright 2018 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2multicast.api import receive 16 | from ros2multicast.verb import add_group_argument 17 | from ros2multicast.verb import add_port_argument 18 | from ros2multicast.verb import VerbExtension 19 | 20 | 21 | class ReceiveVerb(VerbExtension): 22 | """Receive a single UDP multicast packet.""" 23 | 24 | def add_arguments(self, parser, cli_name): 25 | add_group_argument(parser) 26 | add_port_argument(parser) 27 | 28 | def main(self, *, args): 29 | print('Waiting for UDP multicast datagram...') 30 | try: 31 | data, (host, port) = receive(group=args.group, port=args.port) 32 | except KeyboardInterrupt: 33 | pass 34 | else: 35 | data = data.decode('utf-8') 36 | print(f"Received from {host}:{port}: '{data}'") 37 | -------------------------------------------------------------------------------- /ros2multicast/ros2multicast/verb/send.py: -------------------------------------------------------------------------------- 1 | # Copyright 2018 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2multicast.api import send 16 | from ros2multicast.verb import add_group_argument 17 | from ros2multicast.verb import add_port_argument 18 | from ros2multicast.verb import positive_int 19 | from ros2multicast.verb import VerbExtension 20 | 21 | 22 | class SendVerb(VerbExtension): 23 | """Send a single UDP multicast packet.""" 24 | 25 | def add_arguments(self, parser, cli_name): 26 | add_group_argument(parser) 27 | add_port_argument(parser) 28 | parser.add_argument( 29 | '--ttl', type=positive_int, 30 | help='The multicast TTL') 31 | 32 | def main(self, *, args): 33 | print('Sending one UDP multicast datagram...') 34 | send(b'Hello World!', group=args.group, port=args.port, ttl=args.ttl) 35 | -------------------------------------------------------------------------------- /ros2multicast/setup.py: -------------------------------------------------------------------------------- 1 | from setuptools import find_packages 2 | from setuptools import setup 3 | 4 | package_name = 'ros2multicast' 5 | 6 | setup( 7 | name=package_name, 8 | version='0.39.0', 9 | packages=find_packages(exclude=['test']), 10 | data_files=[ 11 | ('share/' + package_name, ['package.xml']), 12 | ('share/ament_index/resource_index/packages', 13 | ['resource/' + package_name]), 14 | ], 15 | install_requires=['ros2cli'], 16 | zip_safe=True, 17 | author='Dirk Thomas', 18 | author_email='dthomas@osrfoundation.org', 19 | maintainer='Audrow Nash, Geoffrey Biggs', 20 | maintainer_email='audrow@openrobotics.org, geoff@openrobotics.org', 21 | url='https://github.com/ros2/ros2cli/tree/master/ros2multicast', 22 | download_url='https://github.com/ros2/ros2cli/releases', 23 | keywords=[], 24 | classifiers=[ 25 | 'Environment :: Console', 26 | 'Intended Audience :: Developers', 27 | 'License :: OSI Approved :: Apache Software License', 28 | 'Programming Language :: Python', 29 | ], 30 | description='The multicast command for ROS 2 command line tools.', 31 | long_description="""\ 32 | The package provides the multicast command for the ROS 2 command line tools.""", 33 | license='Apache License, Version 2.0', 34 | tests_require=['pytest'], 35 | entry_points={ 36 | 'ros2cli.command': [ 37 | 'multicast = ros2multicast.command.multicast:MulticastCommand', 38 | ], 39 | 'ros2cli.extension_point': [ 40 | 'ros2multicast.verb = ros2multicast.verb:VerbExtension', 41 | ], 42 | 'ros2multicast.verb': [ 43 | 'receive = ros2multicast.verb.receive:ReceiveVerb', 44 | 'send = ros2multicast.verb.send:SendVerb', 45 | ], 46 | }, 47 | ) 48 | -------------------------------------------------------------------------------- /ros2multicast/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.copyright 20 | @pytest.mark.linter 21 | def test_copyright(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2multicast/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @pytest.mark.flake8 20 | @pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /ros2multicast/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /ros2multicast/test/test_xmllint.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_xmllint.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.xmllint 21 | def test_xmllint(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2node/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros2node 5 | 0.39.0 6 | 7 | The node command for ROS 2 command line tools. 8 | 9 | 10 | Audrow Nash 11 | Geoffrey Biggs 12 | 13 | Apache License 2.0 14 | 15 | Aditya Pande 16 | Dirk Thomas 17 | Mabel Zhang 18 | Michael Jeronimo 19 | 20 | rclpy 21 | ros2cli 22 | 23 | ament_copyright 24 | ament_flake8 25 | ament_pep257 26 | ament_xmllint 27 | launch 28 | launch_ros 29 | launch_testing 30 | launch_testing_ros 31 | python3-pytest 32 | python3-pytest-timeout 33 | rclpy 34 | test_msgs 35 | 36 | 37 | ament_python 38 | 39 | 40 | -------------------------------------------------------------------------------- /ros2node/resource/ros2node: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2node/resource/ros2node -------------------------------------------------------------------------------- /ros2node/ros2node/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2node/ros2node/__init__.py -------------------------------------------------------------------------------- /ros2node/ros2node/command/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2node/ros2node/command/__init__.py -------------------------------------------------------------------------------- /ros2node/ros2node/command/node.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.command import add_subparsers_on_demand 16 | from ros2cli.command import CommandExtension 17 | 18 | 19 | class NodeCommand(CommandExtension): 20 | """Various node related sub-commands.""" 21 | 22 | def add_arguments(self, parser, cli_name): 23 | self._subparser = parser 24 | # add arguments and sub-commands of verbs 25 | add_subparsers_on_demand( 26 | parser, cli_name, '_verb', 'ros2node.verb', required=False) 27 | 28 | def main(self, *, parser, args): 29 | if not hasattr(args, '_verb'): 30 | # in case no verb was passed 31 | self._subparser.print_help() 32 | return 0 33 | 34 | extension = getattr(args, '_verb') 35 | 36 | # call the verb's main method 37 | return extension.main(args=args) 38 | -------------------------------------------------------------------------------- /ros2node/ros2node/verb/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.plugin_system import PLUGIN_SYSTEM_VERSION 16 | from ros2cli.plugin_system import satisfies_version 17 | 18 | 19 | class VerbExtension: 20 | """ 21 | The extension point for 'node' verb extensions. 22 | 23 | The following properties must be defined: 24 | * `NAME` (will be set to the entry point name) 25 | 26 | The following methods must be defined: 27 | * `main` 28 | 29 | The following methods can be defined: 30 | * `add_arguments` 31 | """ 32 | 33 | NAME = None 34 | EXTENSION_POINT_VERSION = '0.1' 35 | 36 | def __init__(self): 37 | super(VerbExtension, self).__init__() 38 | satisfies_version(PLUGIN_SYSTEM_VERSION, '^0.1') 39 | 40 | def add_arguments(self, parser, cli_name): 41 | pass 42 | 43 | def main(self, *, args): 44 | raise NotImplementedError() 45 | -------------------------------------------------------------------------------- /ros2node/setup.py: -------------------------------------------------------------------------------- 1 | from setuptools import find_packages 2 | from setuptools import setup 3 | 4 | package_name = 'ros2node' 5 | 6 | setup( 7 | name=package_name, 8 | version='0.39.0', 9 | packages=find_packages(exclude=['test']), 10 | data_files=[ 11 | ('share/' + package_name, ['package.xml']), 12 | ('share/ament_index/resource_index/packages', 13 | ['resource/' + package_name]), 14 | ], 15 | install_requires=['ros2cli'], 16 | zip_safe=True, 17 | author='Dirk Thomas', 18 | author_email='dthomas@osrfoundation.org', 19 | maintainer='Audrow Nash, Geoffrey Biggs', 20 | maintainer_email='audrow@openrobotics.org, geoff@openrobotics.org', 21 | url='https://github.com/ros2/ros2cli/tree/master/ros2node', 22 | download_url='https://github.com/ros2/ros2cli/releases', 23 | keywords=[], 24 | classifiers=[ 25 | 'Environment :: Console', 26 | 'Intended Audience :: Developers', 27 | 'License :: OSI Approved :: Apache Software License', 28 | 'Programming Language :: Python', 29 | ], 30 | description='The node command for ROS 2 command line tools.', 31 | long_description="""\ 32 | The package provides the node command for the ROS 2 command line tools.""", 33 | license='Apache License, Version 2.0', 34 | tests_require=['pytest'], 35 | entry_points={ 36 | 'ros2cli.command': [ 37 | 'node = ros2node.command.node:NodeCommand', 38 | ], 39 | 'ros2cli.extension_point': [ 40 | 'ros2node.verb = ros2node.verb:VerbExtension', 41 | ], 42 | 'ros2node.verb': [ 43 | 'info = ros2node.verb.info:InfoVerb', 44 | 'list = ros2node.verb.list:ListVerb', 45 | ], 46 | } 47 | ) 48 | -------------------------------------------------------------------------------- /ros2node/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.copyright 20 | @pytest.mark.linter 21 | def test_copyright(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2node/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @pytest.mark.flake8 20 | @pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /ros2node/test/test_node.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2node.api import has_duplicates 16 | from ros2node.api import parse_node_name 17 | 18 | 19 | def test_parse_node_name(): 20 | """Test parse_node_name api function.""" 21 | # The input of parse_node_name is the full_name without the initial '/' 22 | name = parse_node_name('/talker') 23 | assert name.full_name == '/talker' 24 | assert name.namespace == '/' 25 | assert name.name == 'talker' 26 | name = parse_node_name('/ns/talker') 27 | assert name.full_name == '/ns/talker' 28 | assert name.namespace == '/ns' 29 | assert name.name == 'talker' 30 | name = parse_node_name('talker') 31 | assert name.full_name == '/talker' 32 | assert name.namespace == '/' 33 | assert name.name == 'talker' 34 | name = parse_node_name('ns/talker') 35 | assert name.full_name == '/ns/talker' 36 | assert name.namespace == '/ns' 37 | assert name.name == 'talker' 38 | 39 | 40 | def test_has_duplicates(): 41 | assert not has_duplicates([]) 42 | assert not has_duplicates(['ns_foo/foo', 'ns_foo/bar']) 43 | assert has_duplicates(['ns_foo/foo'] * 2) 44 | assert has_duplicates(['ns_foo/foo'] * 3) 45 | assert has_duplicates(['ns_foo/foo', 'ns_foo/foo', 'ns_foo/bar']) 46 | -------------------------------------------------------------------------------- /ros2node/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /ros2node/test/test_xmllint.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_xmllint.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.xmllint 21 | def test_xmllint(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2param/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros2param 5 | 0.39.0 6 | 7 | The param command for ROS 2 command line tools. 8 | 9 | 10 | Audrow Nash 11 | Geoffrey Biggs 12 | 13 | Apache License 2.0 14 | 15 | Aditya Pande 16 | Dirk Thomas 17 | Mabel Zhang 18 | Michael Jeronimo 19 | 20 | rcl_interfaces 21 | rclpy 22 | ros2cli 23 | ros2node 24 | ros2service 25 | 26 | ament_copyright 27 | ament_flake8 28 | ament_pep257 29 | ament_xmllint 30 | launch 31 | launch_ros 32 | launch_testing 33 | launch_testing_ros 34 | python3-pytest 35 | python3-pytest-timeout 36 | 37 | 38 | ament_python 39 | 40 | 41 | -------------------------------------------------------------------------------- /ros2param/resource/ros2param: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2param/resource/ros2param -------------------------------------------------------------------------------- /ros2param/ros2param/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2param/ros2param/__init__.py -------------------------------------------------------------------------------- /ros2param/ros2param/command/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2param/ros2param/command/__init__.py -------------------------------------------------------------------------------- /ros2param/ros2param/command/param.py: -------------------------------------------------------------------------------- 1 | # Copyright 2018 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.command import add_subparsers_on_demand 16 | from ros2cli.command import CommandExtension 17 | 18 | 19 | class ParamCommand(CommandExtension): 20 | """Various param related sub-commands.""" 21 | 22 | def add_arguments(self, parser, cli_name, *, argv=None): 23 | self._subparser = parser 24 | 25 | # add arguments and sub-commands of verbs 26 | add_subparsers_on_demand( 27 | parser, cli_name, '_verb', 'ros2param.verb', required=False, 28 | argv=argv) 29 | 30 | def main(self, *, parser, args): 31 | if not hasattr(args, '_verb'): 32 | # in case no verb was passed 33 | self._subparser.print_help() 34 | return 0 35 | 36 | extension = getattr(args, '_verb') 37 | 38 | # call the verb's main method 39 | return extension.main(args=args) 40 | -------------------------------------------------------------------------------- /ros2param/ros2param/verb/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright 2018 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.plugin_system import PLUGIN_SYSTEM_VERSION 16 | from ros2cli.plugin_system import satisfies_version 17 | 18 | 19 | class VerbExtension: 20 | """ 21 | The extension point for 'param' verb extensions. 22 | 23 | The following properties must be defined: 24 | * `NAME` (will be set to the entry point name) 25 | 26 | The following methods must be defined: 27 | * `main` 28 | 29 | The following methods can be defined: 30 | * `add_arguments` 31 | """ 32 | 33 | NAME = None 34 | EXTENSION_POINT_VERSION = '0.1' 35 | 36 | def __init__(self): 37 | super(VerbExtension, self).__init__() 38 | satisfies_version(PLUGIN_SYSTEM_VERSION, '^0.1') 39 | 40 | def add_arguments(self, parser, cli_name): 41 | pass 42 | 43 | def main(self, *, args): 44 | raise NotImplementedError() 45 | -------------------------------------------------------------------------------- /ros2param/test/fixtures/parameter_node.py: -------------------------------------------------------------------------------- 1 | # Copyright 2020 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | import rclpy 16 | from rclpy.executors import ExternalShutdownException 17 | from rclpy.parameter import PARAMETER_SEPARATOR_STRING 18 | 19 | 20 | def main(args=None): 21 | try: 22 | with rclpy.init(args=args): 23 | node = rclpy.create_node('parameter_node') 24 | node.declare_parameter('bool_param', True) 25 | node.declare_parameter('int_param', 42) 26 | node.declare_parameter('double_param', 1.23) 27 | node.declare_parameter('str_param', 'Hello World') 28 | node.declare_parameter('bool_array_param', [False, False, True]) 29 | node.declare_parameter('int_array_param', [1, 2, 3]) 30 | node.declare_parameter('str_array_param', ['foo', 'bar', 'baz']) 31 | node.declare_parameter('double_array_param', [3.125, 6.25, 12.5]) 32 | node.declare_parameter('foo' + PARAMETER_SEPARATOR_STRING + 'str_param', 'foo') 33 | node.declare_parameter('foo' + PARAMETER_SEPARATOR_STRING + 34 | 'bar' + PARAMETER_SEPARATOR_STRING + 35 | 'str_param', 'foobar') 36 | 37 | rclpy.spin(node) 38 | except (KeyboardInterrupt, ExternalShutdownException): 39 | print('parameter node stopped cleanly') 40 | 41 | 42 | if __name__ == '__main__': 43 | main() 44 | -------------------------------------------------------------------------------- /ros2param/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.copyright 20 | @pytest.mark.linter 21 | def test_copyright(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2param/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @pytest.mark.flake8 20 | @pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /ros2param/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /ros2param/test/test_xmllint.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_xmllint.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.xmllint 21 | def test_xmllint(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2pkg/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros2pkg 5 | 0.39.0 6 | 7 | The pkg command for ROS 2 command line tools. 8 | 9 | 10 | Audrow Nash 11 | Geoffrey Biggs 12 | 13 | Apache License 2.0 14 | 15 | Aditya Pande 16 | Dirk Thomas 17 | Mabel Zhang 18 | Michael Jeronimo 19 | 20 | ament_copyright 21 | ament_index_python 22 | python3-catkin-pkg-modules 23 | python3-empy 24 | python3-importlib-resources 25 | ros2cli 26 | 27 | ament_flake8 28 | ament_pep257 29 | ament_xmllint 30 | launch 31 | launch_testing 32 | launch_testing_ros 33 | python3-pytest 34 | python3-pytest-timeout 35 | 36 | 37 | ament_python 38 | 39 | 40 | -------------------------------------------------------------------------------- /ros2pkg/resource/ros2pkg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2pkg/resource/ros2pkg -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2pkg/ros2pkg/__init__.py -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/command/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2pkg/ros2pkg/command/__init__.py -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/command/pkg.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.command import add_subparsers_on_demand 16 | from ros2cli.command import CommandExtension 17 | 18 | 19 | class PkgCommand(CommandExtension): 20 | """Various package related sub-commands.""" 21 | 22 | def add_arguments(self, parser, cli_name): 23 | self._subparser = parser 24 | # add arguments and sub-commands of verbs 25 | add_subparsers_on_demand( 26 | parser, cli_name, '_verb', 'ros2pkg.verb', required=False) 27 | 28 | def main(self, *, parser, args): 29 | if not hasattr(args, '_verb'): 30 | # in case no verb was passed 31 | self._subparser.print_help() 32 | return 0 33 | 34 | extension = getattr(args, '_verb') 35 | 36 | # call the verb's main method 37 | return extension.main(args=args) 38 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2pkg/ros2pkg/resource/__init__.py -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/ament_cmake/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2pkg/ros2pkg/resource/ament_cmake/__init__.py -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/ament_python/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2pkg/ros2pkg/resource/ament_python/__init__.py -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/ament_python/init.py.em: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2pkg/ros2pkg/resource/ament_python/init.py.em -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/ament_python/main.py.em: -------------------------------------------------------------------------------- 1 | def main(): 2 | print('Hi from @project_name.') 3 | 4 | 5 | if __name__ == '__main__': 6 | main() 7 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/ament_python/resource_file.em: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2pkg/ros2pkg/resource/ament_python/resource_file.em -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/ament_python/setup.cfg.em: -------------------------------------------------------------------------------- 1 | [develop] 2 | script_dir=$base/lib/@(project_name) 3 | [install] 4 | install_scripts=$base/lib/@(project_name) 5 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/ament_python/setup.py.em: -------------------------------------------------------------------------------- 1 | from setuptools import find_packages, setup 2 | 3 | package_name = '@project_name' 4 | 5 | setup( 6 | name=package_name, 7 | version='0.0.0', 8 | packages=find_packages(exclude=['test']), 9 | data_files=[ 10 | ('share/ament_index/resource_index/packages', 11 | ['resource/' + package_name]), 12 | ('share/' + package_name, ['package.xml']), 13 | ], 14 | install_requires=['setuptools'], 15 | zip_safe=True, 16 | maintainer='@maintainer_name', 17 | maintainer_email='@maintainer_email', 18 | description='@package_description', 19 | license='@package_license', 20 | tests_require=['pytest'], 21 | entry_points={ 22 | 'console_scripts': [ 23 | @[if node_name]@ 24 | '@node_name = @project_name.@node_name:main' 25 | @[end if]@ 26 | ], 27 | }, 28 | ) 29 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/ament_python/test_copyright.py.em: -------------------------------------------------------------------------------- 1 | # Copyright 2015 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | # Remove the `skip` decorator once the source file(s) have a copyright header 20 | @@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.') 21 | @@pytest.mark.copyright 22 | @@pytest.mark.linter 23 | def test_copyright(): 24 | rc = main(argv=['.', 'test']) 25 | assert rc == 0, 'Found errors' 26 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/ament_python/test_flake8.py.em: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @@pytest.mark.flake8 20 | @@pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/ament_python/test_pep257.py.em: -------------------------------------------------------------------------------- 1 | # Copyright 2015 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @@pytest.mark.linter 20 | @@pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/ament_python/test_xmllint.py.em: -------------------------------------------------------------------------------- 1 | # Copyright 2015 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_xmllint.main import main 16 | import pytest 17 | 18 | 19 | @@pytest.mark.linter 20 | @@pytest.mark.xmllint 21 | def test_xmllint() -> None: 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/cmake/Config.cmake.in.em: -------------------------------------------------------------------------------- 1 | # - Config file for the @(project_name) package 2 | # It defines the following variables 3 | # @(project_name)_INCLUDE_DIRS - include directories for FooBar 4 | # @(project_name)_LIBRARIES - libraries to link against 5 | # @(project_name)_EXECUTABLE - the bar executable 6 | 7 | set(@(project_name)_INCLUDE_DIRS "@@CONF_INCLUDE_DIRS@@") 8 | 9 | # Our library dependencies (contains definitions for IMPORTED targets) 10 | include("${@(project_name)_DIR}/export_@(project_name).cmake") 11 | 12 | # These are IMPORTED targets created by @(project_name)Targets.cmake 13 | @[if cpp_library_name]@ 14 | set(@(project_name)_LIBRARIES @(cpp_library_name)) 15 | @[end if] 16 | @[if cpp_node_name]@ 17 | set(@(project_name)_EXECUTABLE @(cpp_node_name)) 18 | @[end if] 19 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/cmake/ConfigVersion.cmake.in.em: -------------------------------------------------------------------------------- 1 | set(PACKAGE_VERSION "@@@(project_name)_VERSION@@") 2 | 3 | # Check whether the requested PACKAGE_FIND_VERSION is compatible 4 | if("${PACKAGE_VERSION}" VERSION_LESS "${PACKAGE_FIND_VERSION}") 5 | set(PACKAGE_VERSION_COMPATIBLE FALSE) 6 | else() 7 | set(PACKAGE_VERSION_COMPATIBLE TRUE) 8 | if ("${PACKAGE_VERSION}" VERSION_EQUAL "${PACKAGE_FIND_VERSION}") 9 | set(PACKAGE_VERSION_EXACT TRUE) 10 | endif() 11 | endif() 12 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/cmake/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2pkg/ros2pkg/resource/cmake/__init__.py -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/cpp/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2pkg/ros2pkg/resource/cpp/__init__.py -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/cpp/header.hpp.em: -------------------------------------------------------------------------------- 1 | #ifndef @(package_name.upper())__@(library_name.upper())_HPP_ 2 | #define @(package_name.upper())__@(library_name.upper())_HPP_ 3 | 4 | #include "@(package_name)/visibility_control.h" 5 | 6 | namespace @(package_name) 7 | { 8 | 9 | class @(class_name) 10 | { 11 | public: 12 | @(class_name)(); 13 | 14 | virtual ~@(class_name)(); 15 | }; 16 | 17 | } // namespace @(package_name) 18 | 19 | #endif // @(package_name.upper())__@(library_name.upper())_HPP_ 20 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/cpp/library.cpp.em: -------------------------------------------------------------------------------- 1 | #include "@(package_name)/@(library_name).hpp" 2 | 3 | namespace @(package_name) 4 | { 5 | 6 | @(class_name)::@(class_name)() 7 | { 8 | } 9 | 10 | @(class_name)::~@(class_name)() 11 | { 12 | } 13 | 14 | } // namespace @(package_name) 15 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/cpp/main.cpp.em: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | int main([[maybe_unused]] int argc, [[maybe_unused]] char ** argv) 4 | { 5 | printf("hello world @(package_name) package\n"); 6 | } 7 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/cpp/visibility_control.h.em: -------------------------------------------------------------------------------- 1 | #ifndef @(package_name)__VISIBILITY_CONTROL_H_ 2 | #define @(package_name)__VISIBILITY_CONTROL_H_ 3 | 4 | // This logic was borrowed (then namespaced) from the examples on the gcc wiki: 5 | // https://gcc.gnu.org/wiki/Visibility 6 | 7 | #if defined _WIN32 || defined __CYGWIN__ 8 | #ifdef __GNUC__ 9 | #define @(package_name)_EXPORT __attribute__ ((dllexport)) 10 | #define @(package_name)_IMPORT __attribute__ ((dllimport)) 11 | #else 12 | #define @(package_name)_EXPORT __declspec(dllexport) 13 | #define @(package_name)_IMPORT __declspec(dllimport) 14 | #endif 15 | #ifdef @(package_name)_BUILDING_LIBRARY 16 | #define @(package_name)_PUBLIC @(package_name)_EXPORT 17 | #else 18 | #define @(package_name)_PUBLIC @(package_name)_IMPORT 19 | #endif 20 | #define @(package_name)_PUBLIC_TYPE @(package_name)_PUBLIC 21 | #define @(package_name)_LOCAL 22 | #else 23 | #define @(package_name)_EXPORT __attribute__ ((visibility("default"))) 24 | #define @(package_name)_IMPORT 25 | #if __GNUC__ >= 4 26 | #define @(package_name)_PUBLIC __attribute__ ((visibility("default"))) 27 | #define @(package_name)_LOCAL __attribute__ ((visibility("hidden"))) 28 | #else 29 | #define @(package_name)_PUBLIC 30 | #define @(package_name)_LOCAL 31 | #endif 32 | #define @(package_name)_PUBLIC_TYPE 33 | #endif 34 | 35 | #endif // @(package_name)__VISIBILITY_CONTROL_H_ 36 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/package_environment/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2pkg/ros2pkg/resource/package_environment/__init__.py -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/resource/package_environment/package.xml.em: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | @package_name 5 | 0.0.0 6 | @package_description 7 | @maintainer_name 8 | @package_license 9 | 10 | @[if buildtool_dependencies]@ 11 | @[ for dep in buildtool_dependencies]@ 12 | @dep 13 | @[ end for]@ 14 | 15 | @[end if]@ 16 | @[if dependencies]@ 17 | @[ for dep in dependencies]@ 18 | @dep 19 | @[ end for]@ 20 | 21 | @[end if]@ 22 | @[if test_dependencies]@ 23 | @[ for dep in test_dependencies]@ 24 | @dep 25 | @[ end for]@ 26 | 27 | @[end if]@ 28 | 29 | @[if exports]@ 30 | @[ for export in exports]@ 31 | <@export.tagname>@export.content 32 | @[ end for]@ 33 | @[end if]@ 34 | 35 | 36 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/verb/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.plugin_system import PLUGIN_SYSTEM_VERSION 16 | from ros2cli.plugin_system import satisfies_version 17 | 18 | 19 | class VerbExtension: 20 | """ 21 | The extension point for 'pkg' verb extensions. 22 | 23 | The following properties must be defined: 24 | * `NAME` (will be set to the entry point name) 25 | 26 | The following methods must be defined: 27 | * `main` 28 | 29 | The following methods can be defined: 30 | * `add_arguments` 31 | """ 32 | 33 | NAME = None 34 | EXTENSION_POINT_VERSION = '0.1' 35 | 36 | def __init__(self): 37 | super(VerbExtension, self).__init__() 38 | satisfies_version(PLUGIN_SYSTEM_VERSION, '^0.1') 39 | 40 | def add_arguments(self, parser, cli_name): 41 | pass 42 | 43 | def main(self, *, args): 44 | raise NotImplementedError() 45 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/verb/list.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2pkg.api import get_package_names 16 | from ros2pkg.verb import VerbExtension 17 | 18 | 19 | class ListVerb(VerbExtension): 20 | """Output a list of available packages.""" 21 | 22 | def main(self, *, args): 23 | for pkg_name in sorted(get_package_names()): 24 | print(pkg_name) 25 | -------------------------------------------------------------------------------- /ros2pkg/ros2pkg/verb/prefix.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_index_python import get_package_share_directory 16 | from ament_index_python import PackageNotFoundError 17 | from ros2pkg.api import get_prefix_path 18 | from ros2pkg.api import package_name_completer 19 | from ros2pkg.verb import VerbExtension 20 | 21 | PACKAGE_NOT_FOUND = 'Package not found' 22 | 23 | 24 | class PrefixVerb(VerbExtension): 25 | """Output the prefix path of a package.""" 26 | 27 | def add_arguments(self, parser, cli_name): 28 | arg = parser.add_argument( 29 | 'package_name', 30 | help='The package name') 31 | parser.add_argument( 32 | '--share', 33 | action='store_true', 34 | help='Show share directory for the package') 35 | arg.completer = package_name_completer 36 | 37 | def main(self, *, args): 38 | if not args.share: 39 | prefix_path = get_prefix_path(args.package_name) 40 | if prefix_path is None: 41 | return PACKAGE_NOT_FOUND 42 | print(prefix_path) 43 | else: 44 | try: 45 | print(get_package_share_directory(args.package_name)) 46 | except PackageNotFoundError: 47 | return PACKAGE_NOT_FOUND 48 | -------------------------------------------------------------------------------- /ros2pkg/setup.py: -------------------------------------------------------------------------------- 1 | from setuptools import find_packages 2 | from setuptools import setup 3 | 4 | package_name = 'ros2pkg' 5 | 6 | setup( 7 | name=package_name, 8 | version='0.39.0', 9 | packages=find_packages(exclude=['test']), 10 | data_files=[ 11 | ('share/' + package_name, ['package.xml']), 12 | ('share/ament_index/resource_index/packages', 13 | ['resource/' + package_name]), 14 | ], 15 | install_requires=['ros2cli'], 16 | zip_safe=True, 17 | author='Dirk Thomas', 18 | author_email='dthomas@osrfoundation.org', 19 | maintainer='Audrow Nash, Geoffrey Biggs', 20 | maintainer_email='audrow@openrobotics.org, geoff@openrobotics.org', 21 | url='https://github.com/ros2/ros2cli/tree/master/ros2pkg', 22 | download_url='https://github.com/ros2/ros2cli/releases', 23 | keywords=[], 24 | classifiers=[ 25 | 'Environment :: Console', 26 | 'Intended Audience :: Developers', 27 | 'License :: OSI Approved :: Apache Software License', 28 | 'Programming Language :: Python', 29 | ], 30 | description='The pkg command for ROS 2 command line tools.', 31 | long_description="""\ 32 | The package provides the pkg command for the ROS 2 command line tools.""", 33 | license='Apache License, Version 2.0', 34 | tests_require=['pytest'], 35 | entry_points={ 36 | 'ros2cli.command': [ 37 | 'pkg = ros2pkg.command.pkg:PkgCommand', 38 | ], 39 | 'ros2cli.extension_point': [ 40 | 'ros2pkg.verb = ros2pkg.verb:VerbExtension', 41 | ], 42 | 'ros2pkg.verb': [ 43 | 'create = ros2pkg.verb.create:CreateVerb', 44 | 'executables = ros2pkg.verb.executables:ExecutablesVerb', 45 | 'list = ros2pkg.verb.list:ListVerb', 46 | 'prefix = ros2pkg.verb.prefix:PrefixVerb', 47 | 'xml = ros2pkg.verb.xml:XmlVerb', 48 | ], 49 | }, 50 | package_data={ 51 | 'ros2pkg': [ 52 | 'resource/**/*', 53 | ], 54 | }, 55 | ) 56 | -------------------------------------------------------------------------------- /ros2pkg/test/test_api.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from collections.abc import Iterable 16 | import os 17 | 18 | from ros2pkg.api import get_package_names 19 | from ros2pkg.api import get_prefix_path 20 | 21 | 22 | def test_api(): 23 | package_names = get_package_names() 24 | assert isinstance(package_names, Iterable) 25 | 26 | # explicit dependencies of this package will for sure be available 27 | assert 'ros2cli' in package_names 28 | 29 | prefix_path = get_prefix_path('ros2cli') 30 | assert os.path.isdir(prefix_path) 31 | 32 | prefix_path = get_prefix_path('not_existing_package_name') 33 | assert prefix_path is None 34 | 35 | prefix_path = get_prefix_path('invalid.package.name') 36 | assert prefix_path is None 37 | -------------------------------------------------------------------------------- /ros2pkg/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.copyright 20 | @pytest.mark.linter 21 | def test_copyright(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2pkg/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @pytest.mark.flake8 20 | @pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /ros2pkg/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /ros2pkg/test/test_xmllint.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_xmllint.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.xmllint 21 | def test_xmllint(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2run/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros2run 5 | 0.39.0 6 | 7 | The run command for ROS 2 command line tools. 8 | 9 | 10 | Audrow Nash 11 | Geoffrey Biggs 12 | 13 | Apache License 2.0 14 | 15 | Aditya Pande 16 | Dirk Thomas 17 | Mabel Zhang 18 | Michael Jeronimo 19 | 20 | ros2cli 21 | ros2pkg 22 | 23 | ament_copyright 24 | ament_flake8 25 | ament_pep257 26 | ament_xmllint 27 | python3-pytest 28 | python3-pytest-timeout 29 | 30 | 31 | ament_python 32 | 33 | 34 | -------------------------------------------------------------------------------- /ros2run/resource/ros2run: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2run/resource/ros2run -------------------------------------------------------------------------------- /ros2run/ros2run/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2run/ros2run/__init__.py -------------------------------------------------------------------------------- /ros2run/ros2run/command/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2run/ros2run/command/__init__.py -------------------------------------------------------------------------------- /ros2run/setup.py: -------------------------------------------------------------------------------- 1 | from setuptools import find_packages 2 | from setuptools import setup 3 | 4 | package_name = 'ros2run' 5 | 6 | setup( 7 | name=package_name, 8 | version='0.39.0', 9 | packages=find_packages(exclude=['test']), 10 | data_files=[ 11 | ('share/' + package_name, ['package.xml']), 12 | ('share/ament_index/resource_index/packages', 13 | ['resource/' + package_name]), 14 | ], 15 | install_requires=['ros2cli'], 16 | zip_safe=True, 17 | author='Dirk Thomas', 18 | author_email='dthomas@osrfoundation.org', 19 | maintainer='Audrow Nash, Geoffrey Biggs', 20 | maintainer_email='audrow@openrobotics.org, geoff@openrobotics.org', 21 | url='https://github.com/ros2/ros2cli/tree/master/ros2run', 22 | download_url='https://github.com/ros2/ros2cli/releases', 23 | keywords=[], 24 | classifiers=[ 25 | 'Environment :: Console', 26 | 'Intended Audience :: Developers', 27 | 'License :: OSI Approved :: Apache Software License', 28 | 'Programming Language :: Python', 29 | ], 30 | description='The run command for ROS 2 command line tools.', 31 | long_description="""\ 32 | The package provides the run command for the ROS 2 command line tools.""", 33 | license='Apache License, Version 2.0', 34 | tests_require=['pytest'], 35 | entry_points={ 36 | 'ros2cli.command': [ 37 | 'run = ros2run.command.run:RunCommand', 38 | ], 39 | } 40 | ) 41 | -------------------------------------------------------------------------------- /ros2run/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.copyright 20 | @pytest.mark.linter 21 | def test_copyright(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2run/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @pytest.mark.flake8 20 | @pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /ros2run/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /ros2run/test/test_xmllint.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_xmllint.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.xmllint 21 | def test_xmllint(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2service/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros2service 5 | 0.39.0 6 | 7 | The service command for ROS 2 command line tools. 8 | 9 | 10 | Audrow Nash 11 | Geoffrey Biggs 12 | 13 | Apache License 2.0 14 | 15 | Aditya Pande 16 | Mabel Zhang 17 | Michael Jeronimo 18 | William Woodall 19 | 20 | python3-yaml 21 | rclpy 22 | ros2cli 23 | ros2topic 24 | rosidl_runtime_py 25 | 26 | ament_copyright 27 | ament_flake8 28 | ament_pep257 29 | ament_xmllint 30 | launch 31 | launch_ros 32 | launch_testing 33 | launch_testing_ros 34 | python3-pytest 35 | python3-pytest-timeout 36 | test_msgs 37 | 38 | 39 | ament_python 40 | 41 | 42 | -------------------------------------------------------------------------------- /ros2service/resource/ros2service: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2service/resource/ros2service -------------------------------------------------------------------------------- /ros2service/ros2service/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2service/ros2service/__init__.py -------------------------------------------------------------------------------- /ros2service/ros2service/command/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2service/ros2service/command/__init__.py -------------------------------------------------------------------------------- /ros2service/ros2service/command/service.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.command import add_subparsers_on_demand 16 | from ros2cli.command import CommandExtension 17 | 18 | 19 | class ServiceCommand(CommandExtension): 20 | """Various service related sub-commands.""" 21 | 22 | def add_arguments(self, parser, cli_name): 23 | self._subparser = parser 24 | parser.add_argument( 25 | '--include-hidden-services', action='store_true', 26 | help='Consider hidden services as well') 27 | 28 | # add arguments and sub-commands of verbs 29 | add_subparsers_on_demand( 30 | parser, cli_name, '_verb', 'ros2service.verb', required=False) 31 | 32 | def main(self, *, parser, args): 33 | if not hasattr(args, '_verb'): 34 | # in case no verb was passed 35 | self._subparser.print_help() 36 | return 0 37 | 38 | extension = getattr(args, '_verb') 39 | 40 | # call the verb's main method 41 | return extension.main(args=args) 42 | -------------------------------------------------------------------------------- /ros2service/ros2service/verb/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.plugin_system import PLUGIN_SYSTEM_VERSION 16 | from ros2cli.plugin_system import satisfies_version 17 | 18 | 19 | class VerbExtension: 20 | """ 21 | The extension point for 'service' verb extensions. 22 | 23 | The following properties must be defined: 24 | * `NAME` (will be set to the entry point name) 25 | 26 | The following methods must be defined: 27 | * `main` 28 | 29 | The following methods can be defined: 30 | * `add_arguments` 31 | """ 32 | 33 | NAME = None 34 | EXTENSION_POINT_VERSION = '0.1' 35 | 36 | def __init__(self): 37 | super(VerbExtension, self).__init__() 38 | satisfies_version(PLUGIN_SYSTEM_VERSION, '^0.1') 39 | 40 | def add_arguments(self, parser, cli_name): 41 | pass 42 | 43 | def main(self, *, args): 44 | raise NotImplementedError() 45 | -------------------------------------------------------------------------------- /ros2service/ros2service/verb/type.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Canonical Ltd. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.node.strategy import NodeStrategy 16 | from ros2service.api import get_service_names_and_types 17 | from ros2service.api import ServiceNameCompleter 18 | from ros2service.verb import VerbExtension 19 | 20 | 21 | class TypeVerb(VerbExtension): 22 | """Output a service's type.""" 23 | 24 | def add_arguments(self, parser, cli_name): 25 | arg = parser.add_argument( 26 | 'service_name', 27 | help="Name of the ROS service to get type (e.g. '/talker/list_parameters')") 28 | arg.completer = ServiceNameCompleter( 29 | include_hidden_services_key='include_hidden_services') 30 | 31 | def main(self, *, args): 32 | with NodeStrategy(args) as node: 33 | service_names_and_types = get_service_names_and_types( 34 | node=node, 35 | include_hidden_services=args.include_hidden_services) 36 | 37 | for (service_name, service_types) in service_names_and_types: 38 | if args.service_name == service_name: 39 | for service_type in service_types: 40 | print(service_type) 41 | return 0 42 | 43 | return 1 44 | -------------------------------------------------------------------------------- /ros2service/setup.py: -------------------------------------------------------------------------------- 1 | from setuptools import find_packages 2 | from setuptools import setup 3 | 4 | package_name = 'ros2service' 5 | 6 | setup( 7 | name=package_name, 8 | version='0.39.0', 9 | packages=find_packages(exclude=['test']), 10 | data_files=[ 11 | ('share/' + package_name, ['package.xml']), 12 | ('share/ament_index/resource_index/packages', 13 | ['resource/' + package_name]), 14 | ], 15 | install_requires=['ros2cli'], 16 | zip_safe=True, 17 | author='William Woodall', 18 | author_email='william@osrfoundation.org', 19 | maintainer='Audrow Nash, Geoffrey Biggs', 20 | maintainer_email='audrow@openrobotics.org, geoff@openrobotics.org', 21 | url='https://github.com/ros2/ros2cli/tree/master/ros2service', 22 | download_url='https://github.com/ros2/ros2cli/releases', 23 | keywords=[], 24 | classifiers=[ 25 | 'Environment :: Console', 26 | 'Intended Audience :: Developers', 27 | 'License :: OSI Approved :: Apache Software License', 28 | 'Programming Language :: Python', 29 | ], 30 | description='The service command for ROS 2 command line tools.', 31 | long_description="""\ 32 | The package provides the service command for the ROS 2 command line tools.""", 33 | license='Apache License, Version 2.0', 34 | tests_require=['pytest'], 35 | entry_points={ 36 | 'ros2cli.command': [ 37 | 'service = ros2service.command.service:ServiceCommand', 38 | ], 39 | 'ros2cli.extension_point': [ 40 | 'ros2service.verb = ros2service.verb:VerbExtension', 41 | ], 42 | 'ros2service.verb': [ 43 | 'call = ros2service.verb.call:CallVerb', 44 | 'echo = ros2service.verb.echo:EchoVerb', 45 | 'find = ros2service.verb.find:FindVerb', 46 | 'info = ros2service.verb.info:InfoVerb', 47 | 'list = ros2service.verb.list:ListVerb', 48 | 'type = ros2service.verb.type:TypeVerb', 49 | ], 50 | } 51 | ) 52 | -------------------------------------------------------------------------------- /ros2service/test/fixtures/echo_server.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | import rclpy 16 | from rclpy.executors import ExternalShutdownException 17 | from rclpy.node import Node 18 | 19 | from test_msgs.srv import BasicTypes 20 | 21 | 22 | class EchoServer(Node): 23 | 24 | def __init__(self): 25 | super().__init__('echo_server') 26 | self.server = self.create_service(BasicTypes, 'echo', self.callback) 27 | 28 | def callback(self, request, response): 29 | for field_name in request.get_fields_and_field_types(): 30 | setattr(response, field_name, getattr(request, field_name)) 31 | return response 32 | 33 | 34 | def main(args=None): 35 | try: 36 | with rclpy.init(args=args): 37 | node = EchoServer() 38 | rclpy.spin(node) 39 | except (KeyboardInterrupt, ExternalShutdownException): 40 | print('server stopped cleanly') 41 | 42 | 43 | if __name__ == '__main__': 44 | main() 45 | -------------------------------------------------------------------------------- /ros2service/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.copyright 20 | @pytest.mark.linter 21 | def test_copyright(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2service/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @pytest.mark.flake8 20 | @pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /ros2service/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /ros2service/test/test_xmllint.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_xmllint.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.xmllint 21 | def test_xmllint(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2topic/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | ros2topic 5 | 0.39.0 6 | 7 | The topic command for ROS 2 command line tools. 8 | 9 | 10 | Audrow Nash 11 | Geoffrey Biggs 12 | 13 | Apache License 2.0 14 | BSD-3-Clause 15 | 16 | Aditya Pande 17 | Dirk Thomas 18 | Mabel Zhang 19 | Michael Jeronimo 20 | 21 | python3-numpy 22 | python3-yaml 23 | rclpy 24 | ros2cli 25 | rosidl_runtime_py 26 | 27 | ament_copyright 28 | ament_flake8 29 | ament_pep257 30 | ament_xmllint 31 | geometry_msgs 32 | launch 33 | launch_ros 34 | launch_testing 35 | launch_testing_ros 36 | python3-pytest 37 | python3-pytest-timeout 38 | rosgraph_msgs 39 | std_msgs 40 | test_msgs 41 | 42 | 43 | ament_python 44 | 45 | 46 | -------------------------------------------------------------------------------- /ros2topic/resource/ros2topic: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2topic/resource/ros2topic -------------------------------------------------------------------------------- /ros2topic/ros2topic/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2topic/ros2topic/__init__.py -------------------------------------------------------------------------------- /ros2topic/ros2topic/command/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/ros2cli/c0fabeaa7cdef097a92965104e3d809d9f6926f1/ros2topic/ros2topic/command/__init__.py -------------------------------------------------------------------------------- /ros2topic/ros2topic/command/topic.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.command import add_subparsers_on_demand 16 | from ros2cli.command import CommandExtension 17 | 18 | 19 | class TopicCommand(CommandExtension): 20 | """Various topic related sub-commands.""" 21 | 22 | def add_arguments(self, parser, cli_name): 23 | self._subparser = parser 24 | parser.add_argument( 25 | '--include-hidden-topics', action='store_true', 26 | help='Consider hidden topics as well') 27 | 28 | # add arguments and sub-commands of verbs 29 | add_subparsers_on_demand( 30 | parser, cli_name, '_verb', 'ros2topic.verb', required=False) 31 | 32 | def main(self, *, parser, args): 33 | if not hasattr(args, '_verb'): 34 | # in case no verb was passed 35 | self._subparser.print_help() 36 | return 0 37 | 38 | extension = getattr(args, '_verb') 39 | 40 | # call the verb's main method 41 | return extension.main(args=args) 42 | -------------------------------------------------------------------------------- /ros2topic/ros2topic/verb/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.plugin_system import PLUGIN_SYSTEM_VERSION 16 | from ros2cli.plugin_system import satisfies_version 17 | 18 | 19 | class VerbExtension: 20 | """ 21 | The extension point for 'topic' verb extensions. 22 | 23 | The following properties must be defined: 24 | * `NAME` (will be set to the entry point name) 25 | 26 | The following methods must be defined: 27 | * `main` 28 | 29 | The following methods can be defined: 30 | * `add_arguments` 31 | """ 32 | 33 | NAME = None 34 | EXTENSION_POINT_VERSION = '0.1' 35 | 36 | def __init__(self): 37 | super(VerbExtension, self).__init__() 38 | satisfies_version(PLUGIN_SYSTEM_VERSION, '^0.1') 39 | 40 | def add_arguments(self, parser, cli_name): 41 | pass 42 | 43 | def main(self, *, args): 44 | raise NotImplementedError() 45 | -------------------------------------------------------------------------------- /ros2topic/ros2topic/verb/type.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Canonical Ltd. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ros2cli.node.strategy import add_arguments as add_strategy_node_arguments 16 | from ros2cli.node.strategy import NodeStrategy 17 | 18 | from ros2topic.api import get_topic_names_and_types 19 | from ros2topic.api import TopicNameCompleter 20 | from ros2topic.verb import VerbExtension 21 | 22 | 23 | class TypeVerb(VerbExtension): 24 | """Print a topic's type.""" 25 | 26 | def add_arguments(self, parser, cli_name): 27 | add_strategy_node_arguments(parser) 28 | 29 | arg = parser.add_argument( 30 | 'topic_name', 31 | help="Name of the ROS topic to get type (e.g. '/chatter')") 32 | arg.completer = TopicNameCompleter( 33 | include_hidden_topics_key='include_hidden_topics') 34 | 35 | def main(self, *, args): 36 | with NodeStrategy(args) as node: 37 | topic_names_and_types = get_topic_names_and_types( 38 | node=node, 39 | include_hidden_topics=args.include_hidden_topics) 40 | 41 | for (topic_name, topic_types) in topic_names_and_types: 42 | if args.topic_name == topic_name: 43 | for topic_type in topic_types: 44 | print(topic_type) 45 | return 0 46 | 47 | return 1 48 | -------------------------------------------------------------------------------- /ros2topic/test/fixtures/controller_node.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from geometry_msgs.msg import TwistStamped 16 | 17 | import rclpy 18 | from rclpy.executors import ExternalShutdownException 19 | from rclpy.node import Node 20 | from rclpy.qos import qos_profile_system_default 21 | 22 | 23 | class ControllerNode(Node): 24 | 25 | def __init__(self): 26 | super().__init__('controller') 27 | self.pub = self.create_publisher( 28 | TwistStamped, 'cmd_vel', qos_profile_system_default 29 | ) 30 | self.tmr = self.create_timer(1.0, self.callback) 31 | 32 | def callback(self): 33 | msg = TwistStamped() 34 | msg.header.stamp = self.get_clock().now().to_msg() 35 | msg.twist.linear.x = 1.0 36 | self.pub.publish(msg) 37 | 38 | 39 | def main(args=None): 40 | try: 41 | with rclpy.init(args=args): 42 | node = ControllerNode() 43 | rclpy.spin(node) 44 | except (KeyboardInterrupt, ExternalShutdownException): 45 | print('controller stopped cleanly') 46 | 47 | 48 | if __name__ == '__main__': 49 | main() 50 | -------------------------------------------------------------------------------- /ros2topic/test/fixtures/listener_node.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | import rclpy 16 | from rclpy.executors import ExternalShutdownException 17 | from rclpy.node import Node 18 | from ros2topic.api import qos_profile_from_short_keys 19 | 20 | from std_msgs.msg import String 21 | 22 | 23 | class ListenerNode(Node): 24 | 25 | def __init__(self): 26 | super().__init__('listener') 27 | qos_profile = qos_profile_from_short_keys( 28 | 'system_default', durability='transient_local', 29 | reliability='reliable') 30 | self.sub = self.create_subscription( 31 | String, 'chatter', self.callback, qos_profile 32 | ) 33 | 34 | def callback(self, msg): 35 | self.get_logger().info('I heard: [%s]' % msg.data) 36 | 37 | 38 | def main(args=None): 39 | try: 40 | with rclpy.init(args=args): 41 | node = ListenerNode() 42 | rclpy.spin(node) 43 | except (KeyboardInterrupt, ExternalShutdownException): 44 | print('listener stopped cleanly') 45 | 46 | 47 | if __name__ == '__main__': 48 | main() 49 | -------------------------------------------------------------------------------- /ros2topic/test/fixtures/talker_node.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | import rclpy 16 | from rclpy.executors import ExternalShutdownException 17 | from rclpy.node import Node 18 | 19 | from std_msgs.msg import String 20 | 21 | 22 | class TalkerNode(Node): 23 | 24 | def __init__(self): 25 | super().__init__('talker_node') 26 | self.count = 1 27 | self.pub = self.create_publisher(String, 'chatter', 10) 28 | self.tmr = self.create_timer(1.0, self.callback) 29 | 30 | def callback(self): 31 | self.pub.publish(String(data='Hello World: {0}'.format(self.count))) 32 | self.count += 1 33 | 34 | 35 | def main(args=None): 36 | try: 37 | with rclpy.init(args=args): 38 | node = TalkerNode() 39 | rclpy.spin(node) 40 | except (KeyboardInterrupt, ExternalShutdownException): 41 | print('talker stopped cleanly') 42 | 43 | 44 | if __name__ == '__main__': 45 | main() 46 | -------------------------------------------------------------------------------- /ros2topic/test/resources/chatter.yaml: -------------------------------------------------------------------------------- 1 | --- 2 | data: 'Hello ROS Users' 3 | --- 4 | --- 5 | data: Hello ROS Developers 6 | --- 7 | data: Hello ROS Developers 8 | --- 9 | --- 10 | data: 'Hello ROS Users' 11 | -------------------------------------------------------------------------------- /ros2topic/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.copyright 20 | @pytest.mark.linter 21 | def test_copyright(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /ros2topic/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_flake8.main import main_with_errors 16 | import pytest 17 | 18 | 19 | @pytest.mark.flake8 20 | @pytest.mark.linter 21 | def test_flake8(): 22 | rc, errors = main_with_errors(argv=[]) 23 | assert rc == 0, \ 24 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 25 | '\n'.join(errors) 26 | -------------------------------------------------------------------------------- /ros2topic/test/test_info.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from argparse import Namespace 16 | from contextlib import redirect_stderr 17 | from io import StringIO 18 | 19 | from ros2topic.verb.info import InfoVerb 20 | 21 | 22 | def _generate_expected_error_output(topic_name): 23 | return "Unknown topic '%s'" % topic_name 24 | 25 | 26 | def test_info_zero_publishers_subscribers(): 27 | args = Namespace() 28 | args.topic_name = '/test_ros2_topic_cli' 29 | s = StringIO() 30 | with redirect_stderr(s): 31 | info_verb = InfoVerb() 32 | err_msg = info_verb.main(args=args) 33 | expected_output = _generate_expected_error_output(args.topic_name) 34 | assert expected_output == err_msg 35 | -------------------------------------------------------------------------------- /ros2topic/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2017 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_pep257.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.pep257 21 | def test_pep257(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found code style errors / warnings' 24 | -------------------------------------------------------------------------------- /ros2topic/test/test_qos_conversions.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Amazon.com, Inc. or its affiliates. All rights reserved. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | import rclpy 16 | from rclpy.duration import Duration 17 | 18 | from ros2topic.api import qos_profile_from_short_keys 19 | 20 | 21 | def test_profile_conversion(): 22 | profile = qos_profile_from_short_keys( 23 | 'sensor_data', reliability='reliable', durability='transient_local', 24 | depth=10, history='keep_last', liveliness='manual_by_topic', 25 | liveliness_lease_duration_s=10.3) 26 | assert profile.durability == rclpy.qos.QoSDurabilityPolicy.TRANSIENT_LOCAL 27 | assert profile.reliability == rclpy.qos.QoSReliabilityPolicy.RELIABLE 28 | assert profile.depth == 10 29 | assert profile.history == rclpy.qos.QoSHistoryPolicy.KEEP_LAST 30 | assert profile.liveliness == rclpy.qos.QoSLivelinessPolicy.MANUAL_BY_TOPIC 31 | assert profile.liveliness_lease_duration == Duration(seconds=10.3) 32 | -------------------------------------------------------------------------------- /ros2topic/test/test_xmllint.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_xmllint.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.xmllint 21 | def test_xmllint(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found errors' 24 | --------------------------------------------------------------------------------