Skip to content

Commit e7bab63

Browse files
authored
Closes #796 - Adds list_hardware_components to CLI (#891)
1 parent c1b1865 commit e7bab63

File tree

6 files changed

+139
-1
lines changed

6 files changed

+139
-1
lines changed

controller_manager/controller_manager/__init__.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
configure_controller,
1717
list_controller_types,
1818
list_controllers,
19+
list_hardware_components,
1920
list_hardware_interfaces,
2021
load_controller,
2122
reload_controller_libraries,
@@ -27,6 +28,7 @@
2728
'configure_controller',
2829
'list_controller_types',
2930
'list_controllers',
31+
'list_hardware_components',
3032
'list_hardware_interfaces',
3133
'load_controller',
3234
'reload_controller_libraries',

controller_manager/controller_manager/controller_manager_services.py

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

1515
from controller_manager_msgs.srv import ConfigureController, \
16-
ListControllers, ListControllerTypes, ListHardwareInterfaces, \
16+
ListControllers, ListControllerTypes, ListHardwareComponents, ListHardwareInterfaces, \
1717
LoadController, ReloadControllerLibraries, SwitchController, UnloadController
1818

1919
import rclpy
@@ -57,6 +57,12 @@ def list_controller_types(node, controller_manager_name):
5757
ListControllerTypes, request)
5858

5959

60+
def list_hardware_components(node, controller_manager_name):
61+
request = ListHardwareComponents.Request()
62+
return service_caller(node, f'{controller_manager_name}/list_hardware_components',
63+
ListHardwareComponents, request)
64+
65+
6066
def list_hardware_interfaces(node, controller_manager_name):
6167
request = ListHardwareInterfaces.Request()
6268
return service_caller(node, f'{controller_manager_name}/list_hardware_interfaces',

controller_manager/controller_manager/spawner.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -87,6 +87,7 @@ def wait_for_controller_manager(node, controller_manager, timeout_duration):
8787
f'{controller_manager}/configure_controller',
8888
f'{controller_manager}/list_controllers',
8989
f'{controller_manager}/list_controller_types',
90+
f'{controller_manager}/list_hardware_components',
9091
f'{controller_manager}/list_hardware_interfaces',
9192
f'{controller_manager}/load_controller',
9293
f'{controller_manager}/reload_controller_libraries',

ros2controlcli/doc/userdoc.rst

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@ Currently supported commands are
99

1010
- ros2 control list_controllers
1111
- ros2 control list_controller_types
12+
- ros2 control list_hardware_components
1213
- ros2 control list_hardware_interfaces
1314
- ros2 control load_controller
1415
- ros2 control reload_controller_libraries
@@ -74,6 +75,40 @@ Example output:
7475
joint_trajectory_controller/JointTrajectoryController controller_interface::ControllerInterface
7576
7677
78+
list_hardware_components
79+
------------------------
80+
81+
.. code-block:: console
82+
83+
$ ros2 control list_hardware_components -h
84+
usage: ros2 control list_hardware_components [-h] [--spin-time SPIN_TIME] [-s] [-c CONTROLLER_MANAGER] [--include-hidden-nodes]
85+
86+
Output the list of available hardware components
87+
88+
options:
89+
-h, --help show this help message and exit
90+
--spin-time SPIN_TIME
91+
Spin time in seconds to wait for discovery (only applies when not using an already running daemon)
92+
-s, --use-sim-time Enable ROS simulation time
93+
--verbose, -v List hardware components with command and state interfaces
94+
-c CONTROLLER_MANAGER, --controller-manager CONTROLLER_MANAGER
95+
Name of the controller manager ROS node
96+
--include-hidden-nodes
97+
Consider hidden nodes as well
98+
99+
100+
Example output:
101+
102+
.. code-block:: console
103+
104+
$ ros2 control list_hardware_components
105+
Hardware Component 0
106+
name: RRBot
107+
type: system
108+
plugin name: ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware
109+
state: id=3 label=active
110+
111+
77112
list_hardware_interfaces
78113
------------------------
79114

Lines changed: 78 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,78 @@
1+
# Copyright 2023 ROS2-Control Development Team
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 controller_manager import list_hardware_components
16+
from controller_manager.spawner import bcolors
17+
18+
from ros2cli.node.direct import add_arguments
19+
from ros2cli.node.strategy import NodeStrategy
20+
from ros2cli.verb import VerbExtension
21+
from ros2controlcli.api import add_controller_mgr_parsers
22+
23+
24+
class ListHardwareComponentsVerb(VerbExtension):
25+
"""Output the list of available hardware components."""
26+
27+
def add_arguments(self, parser, cli_name):
28+
add_arguments(parser)
29+
parser.add_argument(
30+
'--verbose', '-v',
31+
action='store_true',
32+
help='List hardware components with command and state interfaces',
33+
)
34+
add_controller_mgr_parsers(parser)
35+
36+
def main(self, *, args):
37+
with NodeStrategy(args) as node:
38+
hardware_components = list_hardware_components(node, args.controller_manager)
39+
40+
for idx, component in enumerate(hardware_components.component):
41+
print(f'Hardware Component {idx}\n\tname: {component.name}\n\ttype: {component.type}')
42+
if hasattr(component, 'plugin_name'):
43+
plugin_name = component.plugin_name
44+
else:
45+
plugin_name = f'{bcolors.WARNING}plugin name missing!{bcolors.ENDC}'
46+
47+
print(f'\tplugin name: {plugin_name}\n\tstate: id={component.state.id} label={component.state.label}\n\tcommand interfaces')
48+
for cmd_interface in component.command_interfaces:
49+
50+
if cmd_interface.is_available:
51+
available_str = f'{bcolors.OKBLUE}[available]{bcolors.ENDC}'
52+
else:
53+
available_str = f'{bcolors.WARNING}[unavailable]{bcolors.ENDC}'
54+
55+
if cmd_interface.is_claimed:
56+
claimed_str = f'{bcolors.OKBLUE}[claimed]{bcolors.ENDC}'
57+
else:
58+
claimed_str = '[unclaimed]'
59+
60+
print(f'\t\t{cmd_interface.name} {available_str} {claimed_str}')
61+
62+
if args.verbose:
63+
print('\tstate interfaces')
64+
for state_interface in component.command_interfaces:
65+
66+
if state_interface.is_available:
67+
available_str = f'{bcolors.OKBLUE}[available]{bcolors.ENDC}'
68+
else:
69+
available_str = f'{bcolors.WARNING}[unavailable]{bcolors.ENDC}'
70+
71+
if state_interface.is_claimed:
72+
claimed_str = f'{bcolors.OKBLUE}[claimed]{bcolors.ENDC}'
73+
else:
74+
claimed_str = '[unclaimed]'
75+
76+
print(f'\t\t{state_interface.name} {available_str} {claimed_str}')
77+
78+
return 0

ros2controlcli/setup.py

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,17 @@
1+
# Copyright 2023 ros2_control Development Team
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+
115
from setuptools import find_packages
216
from setuptools import setup
317

@@ -37,6 +51,8 @@
3751
'ros2controlcli.verb': [
3852
'list_controllers = ros2controlcli.verb.list_controllers:ListControllersVerb',
3953
'view_controller_chains = ros2controlcli.verb.view_controller_chains:ViewControllerChainsVerb',
54+
'list_hardware_components = \
55+
ros2controlcli.verb.list_hardware_components:ListHardwareComponentsVerb',
4056
'list_hardware_interfaces = \
4157
ros2controlcli.verb.list_hardware_interfaces:ListHardwareInterfacesVerb',
4258
'list_controller_types = \

0 commit comments

Comments
 (0)