Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions ros2doctor/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@
<exec_depend>rclpy</exec_depend>
<exec_depend>ros2action</exec_depend>
<exec_depend>ros2cli</exec_depend>
<exec_depend>ros2node</exec_depend>
<exec_depend>ros2param</exec_depend>
<exec_depend>ros_environment</exec_depend>
<exec_depend>std_msgs</exec_depend>

Expand Down
69 changes: 69 additions & 0 deletions ros2doctor/ros2doctor/api/node.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
# Copyright 2025 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.


from collections import Counter

from ros2node.api import get_node_names
from ros2cli.node.strategy import NodeStrategy
from ros2doctor.api import DoctorCheck
from ros2doctor.api import DoctorReport
from ros2doctor.api import Report
from ros2doctor.api import Result
from ros2doctor.api.format import doctor_warn


def find_duplicates(values):
"""Return values that appear more than once."""
counts = Counter(values)
return [v for v, c in counts.items() if c > 1]


class NodeCheck(DoctorCheck):
"""Check for duplicate node names."""

def category(self):
return 'node'

def check(self):
result = Result()
with NodeStrategy(None) as node:
node_list = get_node_names(node=node, include_hidden_nodes=True)
node_names = [n.full_name for n in node_list]
duplicates = find_duplicates(node_names)
for duplicate in duplicates:
doctor_warn(f'Duplicate node name: {duplicate}')
result.add_warning()
return result


class NodeReport(DoctorReport):
"""Report node related information."""

def category(self):
return 'node'

def report(self):
report = Report('NODE LIST')
with NodeStrategy(None) as node:
node_list = get_node_names(node=node, include_hidden_nodes=True)
node_names = [n.full_name for n in node_list]
if not node_names:
report.add_to_report('node count', 0)
report.add_to_report('node', 'none')
else:
report.add_to_report('node count', len(node_names))
for node_name in sorted(node_names):
report.add_to_report('node', node_name)
return report
104 changes: 104 additions & 0 deletions ros2doctor/ros2doctor/api/parameter.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,104 @@
# Copyright 2025 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import rclpy
from rclpy.parameter import parameter_value_to_python
from ros2param.api import call_get_parameters
from ros2param.api import call_list_parameters

from ros2cli.node.direct import DirectNode
from ros2cli.node.strategy import NodeStrategy
from ros2doctor.api import DoctorCheck
from ros2doctor.api import DoctorReport
from ros2doctor.api import Report
from ros2doctor.api import Result
from ros2doctor.api.format import doctor_warn


class ParameterReport(DoctorReport):
"""Report parameter related information."""

def category(self):
return 'parameter'

def report(self):
report = Report('PARAMETER LIST')
with NodeStrategy(None) as node:
try:
node_names_and_namespaces = \
node.get_node_names_and_namespaces()
except Exception:
node_names_and_namespaces = []
if not node_names_and_namespaces:
report.add_to_report('total nodes checked', 0)
report.add_to_report('total parameter count', 0)
report.add_to_report('parameter', 'none')
return report

param_count = 0
nodes_checked = 0

with DirectNode(None) as param_node:
for node_name, namespace in sorted(node_names_and_namespaces):
nodes_checked += 1
full_name = f"{namespace.rstrip('/')}/{node_name}"
try:
response = call_list_parameters(
node=param_node.node, node_name=full_name)
if response is None:
continue
elif response.result() is None:
continue

param_names = response.result().result.names
if param_names:
param_count += len(param_names)
report.add_to_report('node', full_name)
try:
param_response = call_get_parameters(
node=param_node.node,
node_name=full_name,
parameter_names=param_names
)
param_values = None
if param_response:
param_values = param_response.values
if param_values and len(param_values) == len(
param_names
):
params_with_values = sorted(
zip(param_names, param_values)
)
for name, value_msg in params_with_values:
value = parameter_value_to_python(
value_msg
)
report.add_to_report(
'parameter', f'{name}: {value}')
else:
for param_name in sorted(param_names):
report.add_to_report(
'parameter', param_name
)
except RuntimeError:
for param_name in sorted(param_names):
report.add_to_report(
'parameter', param_name
)
except RuntimeError:
pass

report.add_to_report('total nodes checked', nodes_checked)
report.add_to_report('total parameter count', param_count)
return report
6 changes: 5 additions & 1 deletion ros2doctor/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,8 @@
'TopicCheck = ros2doctor.api.topic:TopicCheck',
'QoSCompatibilityCheck = ros2doctor.api.qos_compatibility:QoSCompatibilityCheck',
'PackageCheck = ros2doctor.api.package:PackageCheck',
'NodeCheck = ros2doctor.api.node:NodeCheck',
'ParameterCheck = ros2doctor.api.parameter:ParameterCheck',
],
'ros2doctor.report': [
'PlatformReport = ros2doctor.api.platform:PlatformReport',
Expand All @@ -58,7 +60,9 @@
'ActionReport = ros2doctor.api.action:ActionReport',
'QoSCompatibilityReport = ros2doctor.api.qos_compatibility:QoSCompatibilityReport',
'PackageReport = ros2doctor.api.package:PackageReport',
'EnvironmentReport = ros2doctor.api.environment:EnvironmentReport'
'EnvironmentReport = ros2doctor.api.environment:EnvironmentReport',
'NodeReport = ros2doctor.api.node:NodeReport',
'ParameterReport = ros2doctor.api.parameter:ParameterReport'
],
'ros2cli.extension_point': [
'ros2doctor.verb = ros2doctor.verb:VerbExtension',
Expand Down
29 changes: 29 additions & 0 deletions ros2doctor/test/common.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,3 +33,32 @@ def generate_expected_service_report(services: Iterable[str], serv_counts: Itera
expected_report.add_to_report('service count', serv_count)
expected_report.add_to_report('client count', cli_count)
return expected_report


def generate_expected_node_report(node_count: int, nodes: Iterable[str]) -> Report:
expected_report = Report('NODE LIST')
if node_count == 0:
expected_report.add_to_report('node count', 0)
expected_report.add_to_report('node', 'none')
else:
expected_report.add_to_report('node count', node_count)
for node in nodes:
expected_report.add_to_report('node', node)
return expected_report


def generate_expected_parameter_report(nodes_checked: int, param_count: int,
node_params: Iterable[tuple]) -> Report:
expected_report = Report('PARAMETER LIST')
if nodes_checked == 0:
expected_report.add_to_report('total nodes checked', 0)
expected_report.add_to_report('total parameter count', 0)
expected_report.add_to_report('parameter', 'none')
else:
for node_name, params in node_params:
expected_report.add_to_report('node', node_name)
for param in params:
expected_report.add_to_report('parameter', param)
expected_report.add_to_report('total nodes checked', nodes_checked)
expected_report.add_to_report('total parameter count', param_count)
return expected_report
69 changes: 69 additions & 0 deletions ros2doctor/test/fixtures/complex_node.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
# Copyright 2026 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import rclpy
from rclpy.action import ActionServer
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node
from rclpy.qos import qos_profile_system_default

from test_msgs.action import Fibonacci
from test_msgs.msg import Arrays
from test_msgs.msg import Strings
from test_msgs.srv import BasicTypes


class ComplexNode(Node):

def __init__(self):
super().__init__('complex_node')
self.publisher = self.create_publisher(
Arrays, 'arrays', qos_profile_system_default
)
self.subscription = self.create_subscription(
Strings, 'strings', lambda msg: None, qos_profile_system_default
)
self.server = self.create_service(BasicTypes, 'basic', lambda req, res: res)
self.action_server = ActionServer(
self, Fibonacci, 'fibonacci', self.action_callback
)
self.timer = self.create_timer(1.0, self.pub_callback)

def destroy_node(self):
self.timer.destroy()
self.publisher.destroy()
self.subscription.destroy()
self.server.destroy()
self.action_server.destroy()
super().destroy_node()

def pub_callback(self):
self.publisher.publish(Arrays())

def action_callback(self, goal_handle):
goal_handle.succeed()
return Fibonacci.Result()


def main(args=None):
try:
with rclpy.init(args=args):
node = ComplexNode()
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
print('node stopped cleanly')


if __name__ == '__main__':
main()
44 changes: 44 additions & 0 deletions ros2doctor/test/fixtures/parameter_fixtures_node.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
# Copyright 2025 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

"""Test fixture node with parameters for ros2doctor testing."""

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.parameter import PARAMETER_SEPARATOR_STRING


def main():
try:
with rclpy.init():
node = rclpy.create_node('parameter_node')
# Declare various parameter types for testing
node.declare_parameter('bool_param', True)
node.declare_parameter('int_param', 42)
node.declare_parameter('double_param', 3.14)
node.declare_parameter('str_param', 'hello')
node.declare_parameter('bool_array_param', [True, False])
node.declare_parameter('int_array_param', [1, 2, 3])
node.declare_parameter('double_array_param', [1.0, 2.0])
node.declare_parameter('str_array_param', ['foo', 'bar'])
node.declare_parameter(
'nested' + PARAMETER_SEPARATOR_STRING + 'param', 'nested_value'
)
rclpy.spin(node)
except (KeyboardInterrupt, ExternalShutdownException):
print('parameter_node stopped cleanly')


if __name__ == '__main__':
main()
24 changes: 24 additions & 0 deletions ros2doctor/test/test_api.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

import unittest

from common import generate_expected_node_report
from common import generate_expected_service_report
from common import generate_expected_topic_report

Expand All @@ -25,6 +26,9 @@

import pytest

from ros2doctor.api.node import NodeCheck
from ros2doctor.api.node import NodeReport
from ros2doctor.api.parameter import ParameterReport
from ros2doctor.api.service import ServiceReport
from ros2doctor.api.topic import TopicCheck
from ros2doctor.api.topic import TopicReport
Expand Down Expand Up @@ -74,3 +78,23 @@ def test_no_service_report(self):
self.assertEqual(report.name, expected_report.name)
self.assertEqual(report.items, expected_report.items)
self.assertEqual(report, expected_report)

def test_node_check(self):
"""Assume no duplicate nodes exist in a clean environment."""
node_check = NodeCheck()
check_result = node_check.check()
self.assertEqual(check_result.error, 0)
self.assertEqual(check_result.warning, 0)

def test_no_node_report(self):
"""Assume no nodes are running in a clean environment."""
report = NodeReport().report()
expected_report = generate_expected_node_report(0, [])
self.assertEqual(report.name, expected_report.name)
self.assertEqual(report.name, 'NODE LIST')

def test_no_parameter_report(self):
"""Assume no parameters in a clean environment."""
report = ParameterReport().report()
self.assertEqual(report.name, 'PARAMETER LIST')
self.assertIsNotNone(report)
Loading