Skip to content

Commit 94f016b

Browse files
committed
ros2node: Add verb get_type_description
Adds the verb `get_type_description` which calls the given node's ~/get_type_description service and prints out the response. This verb is basically a shorthand for `ros2 service call <node>/get_type_description ...`. Signed-off-by: Hans-Joachim Krauch <[email protected]>
1 parent 62db738 commit 94f016b

File tree

4 files changed

+107
-0
lines changed

4 files changed

+107
-0
lines changed

ros2node/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919

2020
<exec_depend>rclpy</exec_depend>
2121
<exec_depend>ros2cli</exec_depend>
22+
<exec_depend>rosidl_runtime_py</exec_depend>
2223

2324
<test_depend>ament_copyright</test_depend>
2425
<test_depend>ament_flake8</test_depend>
Lines changed: 64 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,64 @@
1+
# Copyright 2023 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 ros2cli.node import NODE_NAME_PREFIX
17+
from ros2node.api import NodeNameCompleter
18+
from ros2node.verb import VerbExtension
19+
from rosidl_runtime_py import message_to_yaml
20+
from type_description_interfaces.srv import GetTypeDescription
21+
22+
23+
class GetTypeDescriptionVerb(VerbExtension):
24+
"""Call a node's ~/get_type_description service and print the response."""
25+
26+
def add_arguments(self, parser, cli_name):
27+
argument = parser.add_argument(
28+
'node_name',
29+
help='Node name to request information')
30+
argument.completer = NodeNameCompleter()
31+
argument = parser.add_argument(
32+
'type_name',
33+
help='ROS interface type name, in PACKAGE/NAMESPACE/TYPENAME format')
34+
argument = parser.add_argument(
35+
'type_hash',
36+
help='REP-2011 RIHS hash string')
37+
argument = parser.add_argument(
38+
'--include_type_sources', default=False, action='store_true',
39+
help='Whether to return the original idl/msg/etc. source file(s) in the response')
40+
41+
def main(self, *, args):
42+
rclpy.init()
43+
node = rclpy.create_node(NODE_NAME_PREFIX + '_requester_%s_%s' %
44+
('type_description_interfaces', 'GetTypeDescription'))
45+
46+
service_name = args.node_name + '/get_type_description'
47+
cli = node.create_client(GetTypeDescription, service_name)
48+
49+
if not cli.service_is_ready():
50+
print(f'waiting for service {service_name} to become available...')
51+
cli.wait_for_service()
52+
53+
request = GetTypeDescription.Request(type_name=args.type_name,
54+
type_hash=args.type_hash,
55+
include_type_sources=args.include_type_sources)
56+
future = cli.call_async(request)
57+
rclpy.spin_until_future_complete(node, future)
58+
if future.result() is not None:
59+
print(message_to_yaml(future.result()))
60+
else:
61+
raise RuntimeError('Exception while calling service: %r' % future.exception())
62+
63+
node.destroy_node()
64+
rclpy.shutdown()

ros2node/setup.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,7 @@
4242
'ros2node.verb': [
4343
'info = ros2node.verb.info:InfoVerb',
4444
'list = ros2node.verb.list:ListVerb',
45+
'get_type_description = ros2node.verb.get_type_description:GetTypeDescriptionVerb',
4546
],
4647
}
4748
)

ros2node/test/test_cli.py

Lines changed: 41 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -229,3 +229,44 @@ def test_info_hidden_node_hidden_flag(self):
229229
]),
230230
text=node_command.output, strict=False
231231
), 'Output does not match:\n' + node_command.output
232+
233+
@launch_testing.markers.retry_on_failure(times=5, delay=1)
234+
def test_get_type_description_invalid_hash(self):
235+
arguments = ['get_type_description', '/complex_node', 'some_type', 'some_hash']
236+
with self.launch_node_command(arguments=arguments) as node_command:
237+
assert node_command.wait_for_shutdown(timeout=10)
238+
assert node_command.exit_code == launch_testing.asserts.EXIT_OK
239+
assert launch_testing.tools.expect_output(
240+
expected_lines=itertools.chain([
241+
'successful: false',
242+
re.compile(r'failure_reason: .*'),
243+
'type_description:',
244+
' type_description:',
245+
' type_name: ''',
246+
' fields: []',
247+
' referenced_type_descriptions: []',
248+
'type_sources: []',
249+
'extra_information: []',
250+
]),
251+
text=node_command.output, strict=False
252+
), 'Output does not match:\n' + node_command.output
253+
254+
@launch_testing.markers.retry_on_failure(times=5, delay=1)
255+
def test_get_type_description_valid_hash(self):
256+
arguments = [
257+
'get_type_description',
258+
'/complex_node',
259+
'test_msgs.msg.Arrays',
260+
# Type hash below is from test_msgs/share/test_msgs/msg/Arrays.json
261+
'RIHS01_8a321b80dae8c44dfd1ce558eaf1b1cd5ebbe5950863ed675836535511a7f91a'
262+
]
263+
with self.launch_node_command(arguments=arguments) as node_command:
264+
assert node_command.wait_for_shutdown(timeout=10)
265+
assert node_command.exit_code == launch_testing.asserts.EXIT_OK
266+
assert launch_testing.tools.expect_output(
267+
expected_lines=itertools.chain([
268+
'successful: true',
269+
"failure_reason: ''",
270+
]),
271+
text=node_command.output, strict=False
272+
), 'Output does not match:\n' + node_command.output

0 commit comments

Comments
 (0)