Skip to content

Commit b9f066f

Browse files
Add Service report similar to topic report (#1059)
* init Signed-off-by: Michael Carlstrom <[email protected]> * remove commited build Signed-off-by: Michael Carlstrom <[email protected]> * fix function name Signed-off-by: Michael Carlstrom <[email protected]> * Get unit test working Signed-off-by: Michael Carlstrom <[email protected]> * Update ros2doctor/ros2doctor/api/service.py Co-authored-by: Tomoya Fujita <[email protected]> Signed-off-by: Michael Carlstrom <[email protected]> * requested changes Signed-off-by: Michael Carlstrom <[email protected]> * Update test name Signed-off-by: Michael Carlstrom <[email protected]> * skip test_report for rmw_zenoh_cpp. Signed-off-by: Tomoya Fujita <[email protected]> * Remove zip strict Signed-off-by: Michael Carlstrom <[email protected]> --------- Signed-off-by: Michael Carlstrom <[email protected]> Signed-off-by: Tomoya Fujita <[email protected]> Co-authored-by: Tomoya Fujita <[email protected]>
1 parent 5a3be80 commit b9f066f

File tree

9 files changed

+329
-17
lines changed

9 files changed

+329
-17
lines changed

ros2cli/ros2cli/node/direct.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
# limitations under the License.
1414

1515
import os
16+
from typing import Optional
1617

1718
import rclpy
1819
import rclpy.action
@@ -24,7 +25,7 @@
2425

2526
class DirectNode:
2627

27-
def __init__(self, args, *, node_name=None):
28+
def __init__(self, args, *, node_name: Optional[str] = None):
2829
timeout_reached = False
2930

3031
def timer_callback():

ros2doctor/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636
<test_depend>python3-pytest</test_depend>
3737
<test_depend>python3-pytest-timeout</test_depend>
3838
<test_depend>std_msgs</test_depend>
39+
<test_depend>std_srvs</test_depend>
3940

4041
<export>
4142
<build_type>ament_python</build_type>

ros2doctor/ros2doctor/api/__init__.py

Lines changed: 24 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
from typing import List
1616
from typing import Set
1717
from typing import Tuple
18+
from typing import Union
1819

1920
try:
2021
import importlib.metadata as importlib_metadata
@@ -57,12 +58,20 @@ class Report:
5758
def __init__(self, name: str):
5859
"""Initialize with report name."""
5960
self.name = name
60-
self.items = []
61+
self.items: List[Tuple[str, Union[str, int]]] = []
6162

62-
def add_to_report(self, item_name: str, item_info: str) -> None:
63+
def add_to_report(self, item_name: str, item_info: Union[int, str]) -> None:
6364
"""Add report content to items list (list of string tuples)."""
6465
self.items.append((item_name, item_info))
6566

67+
def __eq__(self, other: object) -> bool:
68+
if not isinstance(other, Report):
69+
return False
70+
return self.name == other.name and self.items == other.items
71+
72+
def __str__(self) -> str:
73+
return f'{self.name} Report, Items: {self.items}'
74+
6675

6776
class Result:
6877
"""Stores check result."""
@@ -163,12 +172,23 @@ def generate_reports(*, categories=None, exclude_packages=False) -> List[Report]
163172
return reports
164173

165174

166-
def get_topic_names(skip_topics: List = ()) -> List:
175+
def get_topic_names(skip_topics: List[str] = []) -> List[str]:
167176
"""Get all topic names using rclpy API."""
168-
topics = []
177+
topics: List[str] = []
169178
with NodeStrategy(None) as node:
170179
topic_names_types = node.get_topic_names_and_types()
171180
for t_name, _ in topic_names_types:
172181
if t_name not in skip_topics:
173182
topics.append(t_name)
174183
return topics
184+
185+
186+
def get_service_names(skip_services: List[str] = []) -> List[str]:
187+
"""Get all service names using rclpy API."""
188+
services: List[str] = []
189+
with NodeStrategy(None) as node:
190+
service_names_types = node.get_service_names_and_types()
191+
for t_name, _ in service_names_types:
192+
if t_name not in skip_services:
193+
services.append(t_name)
194+
return services
Lines changed: 41 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,41 @@
1+
# Copyright 2025 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 typing import Literal
16+
17+
from ros2cli.node.direct import DirectNode
18+
from ros2doctor.api import DoctorReport
19+
from ros2doctor.api import get_service_names
20+
from ros2doctor.api import Report
21+
22+
23+
class ServiceReport(DoctorReport):
24+
"""Report service related information."""
25+
26+
def category(self) -> Literal['topic']:
27+
return 'topic'
28+
29+
def report(self) -> Report:
30+
report = Report('SERVICE LIST')
31+
to_be_reported = get_service_names()
32+
if not to_be_reported:
33+
report.add_to_report('service', 'none')
34+
report.add_to_report('service count', 0)
35+
report.add_to_report('client count', 0)
36+
with DirectNode(None) as node:
37+
for service_name in to_be_reported:
38+
report.add_to_report('service', service_name)
39+
report.add_to_report('service count', node.node.count_services(service_name))
40+
report.add_to_report('client count', node.node.count_clients(service_name))
41+
return report

ros2doctor/setup.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,7 @@
5151
'NetworkReport = ros2doctor.api.network:NetworkReport',
5252
'RMWReport = ros2doctor.api.rmw:RMWReport',
5353
'TopicReport = ros2doctor.api.topic:TopicReport',
54+
'ServiceReport = ros2doctor.api.service:ServiceReport',
5455
'QoSCompatibilityReport = ros2doctor.api.qos_compatibility:QoSCompatibilityReport',
5556
'PackageReport = ros2doctor.api.package:PackageReport',
5657
],

ros2doctor/test/common.py

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,35 @@
1+
# Copyright 2025 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 typing import Iterable
16+
17+
from ros2doctor.api import Report
18+
19+
20+
def generate_expected_topic_report(topic: str, pub_count: int, sub_count: int) -> Report:
21+
expected_report = Report('TOPIC LIST')
22+
expected_report.add_to_report('topic', topic)
23+
expected_report.add_to_report('publisher count', pub_count)
24+
expected_report.add_to_report('subscriber count', sub_count)
25+
return expected_report
26+
27+
28+
def generate_expected_service_report(services: Iterable[str], serv_counts: Iterable[int],
29+
cli_counts: Iterable[int]) -> Report:
30+
expected_report = Report('SERVICE LIST')
31+
for service, serv_count, cli_count in zip(services, serv_counts, cli_counts):
32+
expected_report.add_to_report('service', service)
33+
expected_report.add_to_report('service count', serv_count)
34+
expected_report.add_to_report('client count', cli_count)
35+
return expected_report
Lines changed: 44 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
# Copyright 2025 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+
from std_srvs.srv import SetBool
21+
22+
23+
class ReportTestNode(Node):
24+
25+
def __init__(self):
26+
# Disable all extraneous node services to simplify the test
27+
super().__init__('report_node', start_parameter_services=False)
28+
self.create_publisher(String, 'msg', 10)
29+
self.create_subscription(String, 'msg', lambda msg: None, 10)
30+
self.create_client(SetBool, 'baz')
31+
self.create_service(SetBool, 'bar', lambda req, res: res)
32+
33+
34+
def main():
35+
try:
36+
with rclpy.init():
37+
node = ReportTestNode()
38+
rclpy.spin(node)
39+
except (KeyboardInterrupt, ExternalShutdownException):
40+
print('report_test_node stopped cleanly')
41+
42+
43+
if __name__ == '__main__':
44+
main()

ros2doctor/test/test_api.py

Lines changed: 16 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,9 @@
1414

1515
import unittest
1616

17+
from common import generate_expected_service_report
18+
from common import generate_expected_topic_report
19+
1720
from launch import LaunchDescription
1821
from launch.actions import ExecuteProcess
1922

@@ -22,14 +25,14 @@
2225

2326
import pytest
2427

25-
from ros2doctor.api import Report
28+
from ros2doctor.api.service import ServiceReport
2629
from ros2doctor.api.topic import TopicCheck
2730
from ros2doctor.api.topic import TopicReport
2831

2932

3033
@pytest.mark.rostest
3134
@launch_testing.markers.keep_alive
32-
def generate_test_description():
35+
def generate_test_description() -> LaunchDescription:
3336
return LaunchDescription([
3437
ExecuteProcess(
3538
cmd=['ros2', 'daemon', 'stop'],
@@ -47,14 +50,6 @@ def generate_test_description():
4750
])
4851

4952

50-
def _generate_expected_report(topic, pub_count, sub_count):
51-
expected_report = Report('TOPIC LIST')
52-
expected_report.add_to_report('topic', topic)
53-
expected_report.add_to_report('publisher count', pub_count)
54-
expected_report.add_to_report('subscriber count', sub_count)
55-
return expected_report
56-
57-
5853
class TestROS2DoctorAPI(unittest.TestCase):
5954

6055
def test_topic_check(self):
@@ -64,9 +59,18 @@ def test_topic_check(self):
6459
self.assertEqual(check_result.error, 0)
6560
self.assertEqual(check_result.warning, 0)
6661

67-
def test_topic_report(self):
62+
def test_no_topic_report(self):
6863
"""Assume no topics are publishing or subscribing other than whitelisted ones."""
6964
report = TopicReport().report()
70-
expected_report = _generate_expected_report('none', 0, 0)
65+
expected_report = generate_expected_topic_report('none', 0, 0)
66+
self.assertEqual(report.name, expected_report.name)
67+
self.assertEqual(report.items, expected_report.items)
68+
self.assertEqual(report, expected_report)
69+
70+
def test_no_service_report(self):
71+
"""Assume no services are being used other than whitelisted ones."""
72+
report = ServiceReport().report()
73+
expected_report = generate_expected_service_report(['none'], [0], [0])
7174
self.assertEqual(report.name, expected_report.name)
7275
self.assertEqual(report.items, expected_report.items)
76+
self.assertEqual(report, expected_report)

0 commit comments

Comments
 (0)