Skip to content

Commit 506887f

Browse files
mergify[bot]mamueluthdestoglchristophfroehlich
authored
Add spawner for hardware (backport #941) (#1216)
--------- Co-authored-by: Manuel Muth <[email protected]> Co-authored-by: Dr. Denis <[email protected]> Co-authored-by: Christoph Froehlich <[email protected]>
1 parent 385293e commit 506887f

File tree

5 files changed

+289
-16
lines changed

5 files changed

+289
-16
lines changed

controller_manager/controller_manager/__init__.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
list_hardware_interfaces,
2121
load_controller,
2222
reload_controller_libraries,
23+
set_hardware_component_state,
2324
switch_controllers,
2425
unload_controller
2526
)
@@ -32,6 +33,7 @@
3233
'list_hardware_interfaces',
3334
'load_controller',
3435
'reload_controller_libraries',
36+
'set_hardware_component_state',
3537
'switch_controllers',
3638
'unload_controller',
3739
]

controller_manager/controller_manager/controller_manager_services.py

Lines changed: 33 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,18 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15-
from controller_manager_msgs.srv import ConfigureController, \
16-
ListControllers, ListControllerTypes, ListHardwareComponents, ListHardwareInterfaces, \
17-
LoadController, ReloadControllerLibraries, SwitchController, UnloadController
15+
from controller_manager_msgs.srv import (
16+
ConfigureController,
17+
ListControllers,
18+
ListControllerTypes,
19+
ListHardwareComponents,
20+
ListHardwareInterfaces,
21+
LoadController,
22+
ReloadControllerLibraries,
23+
SetHardwareComponentState,
24+
SwitchController,
25+
UnloadController,
26+
)
1827

1928
import rclpy
2029

@@ -117,8 +126,27 @@ def reload_controller_libraries(node, controller_manager_name, force_kill, servi
117126
)
118127

119128

120-
def switch_controllers(node, controller_manager_name, deactivate_controllers,
121-
activate_controllers, strict, activate_asap, timeout):
129+
def set_hardware_component_state(node, controller_manager_name, component_name, lifecyle_state):
130+
request = SetHardwareComponentState.Request()
131+
request.name = component_name
132+
request.target_state = lifecyle_state
133+
return service_caller(
134+
node,
135+
f"{controller_manager_name}/set_hardware_component_state",
136+
SetHardwareComponentState,
137+
request,
138+
)
139+
140+
141+
def switch_controllers(
142+
node,
143+
controller_manager_name,
144+
deactivate_controllers,
145+
activate_controllers,
146+
strict,
147+
activate_asap,
148+
timeout,
149+
):
122150
request = SwitchController.Request()
123151
request.activate_controllers = activate_controllers
124152
request.deactivate_controllers = deactivate_controllers
Lines changed: 227 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,227 @@
1+
#!/usr/bin/env python3
2+
# Copyright 2023 Stogl Robotics Consulting UG (haftungsbeschränkt)
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+
import argparse
17+
import sys
18+
import time
19+
20+
from controller_manager import set_hardware_component_state
21+
22+
from lifecycle_msgs.msg import State
23+
import rclpy
24+
from rclpy.duration import Duration
25+
from rclpy.node import Node
26+
from rclpy.signals import SignalHandlerOptions
27+
28+
29+
# from https://stackoverflow.com/a/287944
30+
class bcolors:
31+
HEADER = "\033[95m"
32+
OKBLUE = "\033[94m"
33+
OKCYAN = "\033[96m"
34+
OKGREEN = "\033[92m"
35+
WARNING = "\033[93m"
36+
FAIL = "\033[91m"
37+
ENDC = "\033[0m"
38+
BOLD = "\033[1m"
39+
UNDERLINE = "\033[4m"
40+
41+
42+
def first_match(iterable, predicate):
43+
return next((n for n in iterable if predicate(n)), None)
44+
45+
46+
def wait_for_value_or(function, node, timeout, default, description):
47+
while node.get_clock().now() < timeout:
48+
if result := function():
49+
return result
50+
node.get_logger().info(
51+
f"Waiting for {description}", throttle_duration_sec=2, skip_first=True
52+
)
53+
time.sleep(0.2)
54+
return default
55+
56+
57+
def combine_name_and_namespace(name_and_namespace):
58+
node_name, namespace = name_and_namespace
59+
return namespace + ("" if namespace.endswith("/") else "/") + node_name
60+
61+
62+
def find_node_and_namespace(node, full_node_name):
63+
node_names_and_namespaces = node.get_node_names_and_namespaces()
64+
return first_match(
65+
node_names_and_namespaces,
66+
lambda n: combine_name_and_namespace(n) == full_node_name,
67+
)
68+
69+
70+
def has_service_names(node, node_name, node_namespace, service_names):
71+
client_names_and_types = node.get_service_names_and_types_by_node(node_name, node_namespace)
72+
if not client_names_and_types:
73+
return False
74+
client_names, _ = zip(*client_names_and_types)
75+
return all(service in client_names for service in service_names)
76+
77+
78+
def wait_for_controller_manager(node, controller_manager, timeout_duration):
79+
# List of service names from controller_manager we wait for
80+
service_names = (
81+
f"{controller_manager}/list_hardware_components",
82+
f"{controller_manager}/set_hardware_component_state",
83+
)
84+
85+
# Wait for controller_manager
86+
timeout = node.get_clock().now() + Duration(seconds=timeout_duration)
87+
node_and_namespace = wait_for_value_or(
88+
lambda: find_node_and_namespace(node, controller_manager),
89+
node,
90+
timeout,
91+
None,
92+
f"'{controller_manager}' node to exist",
93+
)
94+
95+
# Wait for the services if the node was found
96+
if node_and_namespace:
97+
node_name, namespace = node_and_namespace
98+
return wait_for_value_or(
99+
lambda: has_service_names(node, node_name, namespace, service_names),
100+
node,
101+
timeout,
102+
False,
103+
f"'{controller_manager}' services to be available",
104+
)
105+
106+
return False
107+
108+
109+
def handle_set_component_state_service_call(
110+
node, controller_manager_name, component, target_state, action
111+
):
112+
response = set_hardware_component_state(node, controller_manager_name, component, target_state)
113+
if response.ok and response.state == target_state:
114+
node.get_logger().info(
115+
bcolors.OKGREEN
116+
+ f"{action} component '{component}'. Hardware now in state: {response.state}."
117+
)
118+
elif response.ok and not response.state == target_state:
119+
node.get_logger().warn(
120+
bcolors.WARNING
121+
+ f"Could not {action} component '{component}'. Service call returned ok=True, but state: {response.state} is not equal to target state '{target_state}'."
122+
)
123+
else:
124+
node.get_logger().warn(
125+
bcolors.WARNING
126+
+ f"Could not {action} component '{component}'. Service call failed. Wrong component name?"
127+
)
128+
129+
130+
def activate_components(node, controller_manager_name, components_to_activate):
131+
active_state = State()
132+
active_state.id = State.PRIMARY_STATE_ACTIVE
133+
active_state.label = "active"
134+
for component in components_to_activate:
135+
handle_set_component_state_service_call(
136+
node, controller_manager_name, component, active_state, "activated"
137+
)
138+
139+
140+
def configure_components(node, controller_manager_name, components_to_configure):
141+
inactive_state = State()
142+
inactive_state.id = State.PRIMARY_STATE_INACTIVE
143+
inactive_state.label = "inactive"
144+
for component in components_to_configure:
145+
handle_set_component_state_service_call(
146+
node, controller_manager_name, component, inactive_state, "configured"
147+
)
148+
149+
150+
def main(args=None):
151+
rclpy.init(args=args, signal_handler_options=SignalHandlerOptions.NO)
152+
parser = argparse.ArgumentParser()
153+
activate_or_confiigure_grp = parser.add_mutually_exclusive_group(required=True)
154+
155+
parser.add_argument(
156+
"hardware_component_name",
157+
help="The name of the hardware component which should be activated.",
158+
)
159+
parser.add_argument(
160+
"-c",
161+
"--controller-manager",
162+
help="Name of the controller manager ROS node",
163+
default="controller_manager",
164+
required=False,
165+
)
166+
parser.add_argument(
167+
"--controller-manager-timeout",
168+
help="Time to wait for the controller manager",
169+
required=False,
170+
default=10,
171+
type=int,
172+
)
173+
174+
# add arguments which are mutually exclusive
175+
activate_or_confiigure_grp.add_argument(
176+
"--activate",
177+
help="Activates the given components. Note: Components are by default configured before activated. ",
178+
action="store_true",
179+
required=False,
180+
)
181+
activate_or_confiigure_grp.add_argument(
182+
"--configure",
183+
help="Configures the given components.",
184+
action="store_true",
185+
required=False,
186+
)
187+
188+
command_line_args = rclpy.utilities.remove_ros_args(args=sys.argv)[1:]
189+
args = parser.parse_args(command_line_args)
190+
controller_manager_name = args.controller_manager
191+
controller_manager_timeout = args.controller_manager_timeout
192+
hardware_component = [args.hardware_component_name]
193+
activate = args.activate
194+
configure = args.configure
195+
196+
node = Node("hardware_spawner")
197+
if not controller_manager_name.startswith("/"):
198+
spawner_namespace = node.get_namespace()
199+
if spawner_namespace != "/":
200+
controller_manager_name = f"{spawner_namespace}/{controller_manager_name}"
201+
else:
202+
controller_manager_name = f"/{controller_manager_name}"
203+
204+
try:
205+
if not wait_for_controller_manager(
206+
node, controller_manager_name, controller_manager_timeout
207+
):
208+
node.get_logger().error("Controller manager not available")
209+
return 1
210+
211+
if activate:
212+
activate_components(node, controller_manager_name, hardware_component)
213+
elif configure:
214+
configure_components(node, controller_manager_name, hardware_component)
215+
else:
216+
node.get_logger().error(
217+
'You need to either specify if the hardware component should be activated with the "--activate" flag or configured with the "--configure" flag'
218+
)
219+
parser.print_help()
220+
return 0
221+
finally:
222+
rclpy.shutdown()
223+
224+
225+
if __name__ == "__main__":
226+
ret = main()
227+
sys.exit(ret)

controller_manager/setup.cfg

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,3 +2,4 @@
22
console_scripts =
33
spawner = controller_manager.spawner:main
44
unspawner = controller_manager.unspawner:main
5+
hardware_spawner = controller_manager.hardware_spawner:main

controller_manager/src/controller_manager.cpp

Lines changed: 26 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -365,27 +365,42 @@ void ControllerManager::init_resource_manager(const std::string & robot_descript
365365
using lifecycle_msgs::msg::State;
366366

367367
std::vector<std::string> configure_components_on_start = std::vector<std::string>({});
368-
get_parameter("configure_components_on_start", configure_components_on_start);
369-
rclcpp_lifecycle::State inactive_state(
370-
State::PRIMARY_STATE_INACTIVE, hardware_interface::lifecycle_state_names::INACTIVE);
371-
for (const auto & component : configure_components_on_start)
368+
if (get_parameter("configure_components_on_start", configure_components_on_start))
372369
{
373-
resource_manager_->set_component_state(component, inactive_state);
370+
RCLCPP_WARN_STREAM(
371+
get_logger(),
372+
"[Deprecated]: Usage of parameter \"activate_components_on_start\" is deprecated. Use "
373+
"hardware_spawner instead.");
374+
rclcpp_lifecycle::State inactive_state(
375+
State::PRIMARY_STATE_INACTIVE, hardware_interface::lifecycle_state_names::INACTIVE);
376+
for (const auto & component : configure_components_on_start)
377+
{
378+
resource_manager_->set_component_state(component, inactive_state);
379+
}
374380
}
375381

376382
std::vector<std::string> activate_components_on_start = std::vector<std::string>({});
377-
get_parameter("activate_components_on_start", activate_components_on_start);
378-
rclcpp_lifecycle::State active_state(
379-
State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE);
380-
for (const auto & component : activate_components_on_start)
383+
if (get_parameter("activate_components_on_start", activate_components_on_start))
381384
{
382-
resource_manager_->set_component_state(component, active_state);
385+
RCLCPP_WARN_STREAM(
386+
get_logger(),
387+
"[Deprecated]: Usage of parameter \"activate_components_on_start\" is deprecated. Use "
388+
"hardware_spawner instead.");
389+
rclcpp_lifecycle::State active_state(
390+
State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE);
391+
for (const auto & component : activate_components_on_start)
392+
{
393+
resource_manager_->set_component_state(component, active_state);
394+
}
383395
}
384-
385396
// if both parameter are empty or non-existing preserve behavior where all components are
386397
// activated per default
387398
if (configure_components_on_start.empty() && activate_components_on_start.empty())
388399
{
400+
RCLCPP_WARN_STREAM(
401+
get_logger(),
402+
"[Deprecated]: Automatic activation of all hardware components will not be supported in the "
403+
"future anymore. Use hardware_spawner instead.");
389404
resource_manager_->activate_all_components();
390405
}
391406
}

0 commit comments

Comments
 (0)