Skip to content

Commit bfa9281

Browse files
authored
Merge branch 'master' into feat/interface/remapping
2 parents f0f539b + 40ea191 commit bfa9281

35 files changed

+817
-414
lines changed

codecov.yml

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -14,8 +14,6 @@ fixes:
1414
comment:
1515
layout: "diff, flags, files"
1616
behavior: default
17-
ignore:
18-
- "**/test"
1917
flags:
2018
unittests:
2119
paths:

controller_interface/test/test_controller_interface.cpp

Lines changed: 9 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,8 @@
1616

1717
#include <gmock/gmock.h>
1818
#include <memory>
19+
#include <string>
20+
#include <vector>
1921

2022
#include "rclcpp/executor_options.hpp"
2123
#include "rclcpp/executors/multi_threaded_executor.hpp"
@@ -57,13 +59,16 @@ TEST(TestableControllerInterface, init)
5759
TEST(TestableControllerInterface, setting_update_rate_in_configure)
5860
{
5961
// mocks the declaration of overrides parameters in a yaml file
60-
char const * const argv[] = {"", "--ros-args", "-p", "update_rate:=2812"};
61-
int argc = arrlen(argv);
62-
rclcpp::init(argc, argv);
62+
rclcpp::init(0, nullptr);
6363

6464
TestableControllerInterface controller;
6565
// initialize, create node
66-
const auto node_options = controller.define_custom_node_options();
66+
auto node_options = controller.define_custom_node_options();
67+
std::vector<std::string> node_options_arguments = node_options.arguments();
68+
node_options_arguments.push_back("--ros-args");
69+
node_options_arguments.push_back("-p");
70+
node_options_arguments.push_back("update_rate:=2812");
71+
node_options = node_options.arguments(node_options_arguments);
6772
ASSERT_EQ(
6873
controller.init(TEST_CONTROLLER_NAME, "", 1.0, "", node_options),
6974
controller_interface::return_type::OK);

controller_manager/controller_manager/__init__.py

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,10 @@
2323
set_hardware_component_state,
2424
switch_controllers,
2525
unload_controller,
26+
get_parameter_from_param_file,
27+
set_controller_parameters,
28+
set_controller_parameters_from_param_file,
29+
bcolors,
2630
)
2731

2832
__all__ = [
@@ -36,4 +40,8 @@
3640
"set_hardware_component_state",
3741
"switch_controllers",
3842
"unload_controller",
43+
"get_parameter_from_param_file",
44+
"set_controller_parameters",
45+
"set_controller_parameters_from_param_file",
46+
"bcolors",
3947
]

controller_manager/controller_manager/controller_manager_services.py

Lines changed: 184 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -26,28 +26,96 @@
2626
)
2727

2828
import rclpy
29+
import yaml
30+
from rcl_interfaces.msg import Parameter
2931

32+
# @note: The versions conditioning is added here to support the source-compatibility with Humble
33+
# The `get_parameter_value` function is moved to `rclpy.parameter` module from `ros2param.api` module from version 3.6.0
34+
try:
35+
from rclpy.parameter import get_parameter_value
36+
except ImportError:
37+
from ros2param.api import get_parameter_value
38+
from ros2param.api import call_set_parameters
3039

31-
def service_caller(node, service_name, service_type, request, service_timeout=10.0):
40+
41+
# from https://stackoverflow.com/a/287944
42+
class bcolors:
43+
MAGENTA = "\033[95m"
44+
OKBLUE = "\033[94m"
45+
OKCYAN = "\033[96m"
46+
OKGREEN = "\033[92m"
47+
WARNING = "\033[93m"
48+
FAIL = "\033[91m"
49+
ENDC = "\033[0m"
50+
BOLD = "\033[1m"
51+
UNDERLINE = "\033[4m"
52+
53+
54+
class ServiceNotFoundError(Exception):
55+
pass
56+
57+
58+
def service_caller(
59+
node,
60+
service_name,
61+
service_type,
62+
request,
63+
service_timeout=0.0,
64+
call_timeout=10.0,
65+
max_attempts=3,
66+
):
67+
"""
68+
Abstraction of a service call.
69+
70+
Has an optional timeout to find the service, receive the answer to a call
71+
and a mechanism to retry a call of no response is received.
72+
73+
@param node Node object to be associated with
74+
@type rclpy.node.Node
75+
@param service_name Service URL
76+
@type str
77+
@param request The request to be sent
78+
@type service request type
79+
@param service_timeout Timeout (in seconds) to wait until the service is available. 0 means
80+
waiting forever, retrying every 10 seconds.
81+
@type float
82+
@param call_timeout Timeout (in seconds) for getting a response
83+
@type float
84+
@param max_attempts Number of attempts until a valid response is received. With some
85+
middlewares it can happen, that the service response doesn't reach the client leaving it in
86+
a waiting state forever.
87+
@type int
88+
@return The service response
89+
90+
"""
3291
cli = node.create_client(service_type, service_name)
3392

34-
if not cli.service_is_ready():
35-
node.get_logger().debug(
36-
f"waiting {service_timeout} seconds for service {service_name} to become available..."
37-
)
38-
if not cli.wait_for_service(service_timeout):
39-
raise RuntimeError(f"Could not contact service {service_name}")
93+
while not cli.service_is_ready():
94+
node.get_logger().info(f"waiting for service {service_name} to become available...")
95+
if service_timeout:
96+
if not cli.wait_for_service(service_timeout):
97+
raise ServiceNotFoundError(f"Could not contact service {service_name}")
98+
elif not cli.wait_for_service(10.0):
99+
node.get_logger().warn(f"Could not contact service {service_name}")
40100

41101
node.get_logger().debug(f"requester: making request: {request}\n")
42-
future = cli.call_async(request)
43-
rclpy.spin_until_future_complete(node, future)
44-
if future.result() is not None:
45-
return future.result()
46-
else:
47-
raise RuntimeError(f"Exception while calling service: {future.exception()}")
102+
future = None
103+
for attempt in range(max_attempts):
104+
future = cli.call_async(request)
105+
rclpy.spin_until_future_complete(node, future, timeout_sec=call_timeout)
106+
if future.result() is None:
107+
node.get_logger().warning(
108+
f"Failed getting a result from calling {service_name} in "
109+
f"{service_timeout}. (Attempt {attempt+1} of {max_attempts}.)"
110+
)
111+
else:
112+
return future.result()
113+
raise RuntimeError(
114+
f"Could not successfully call service {service_name} after {max_attempts} attempts."
115+
)
48116

49117

50-
def configure_controller(node, controller_manager_name, controller_name, service_timeout=10.0):
118+
def configure_controller(node, controller_manager_name, controller_name, service_timeout=0.0):
51119
request = ConfigureController.Request()
52120
request.name = controller_name
53121
return service_caller(
@@ -59,7 +127,7 @@ def configure_controller(node, controller_manager_name, controller_name, service
59127
)
60128

61129

62-
def list_controllers(node, controller_manager_name, service_timeout=10.0):
130+
def list_controllers(node, controller_manager_name, service_timeout=0.0):
63131
request = ListControllers.Request()
64132
return service_caller(
65133
node,
@@ -70,7 +138,7 @@ def list_controllers(node, controller_manager_name, service_timeout=10.0):
70138
)
71139

72140

73-
def list_controller_types(node, controller_manager_name, service_timeout=10.0):
141+
def list_controller_types(node, controller_manager_name, service_timeout=0.0):
74142
request = ListControllerTypes.Request()
75143
return service_caller(
76144
node,
@@ -81,7 +149,7 @@ def list_controller_types(node, controller_manager_name, service_timeout=10.0):
81149
)
82150

83151

84-
def list_hardware_components(node, controller_manager_name, service_timeout=10.0):
152+
def list_hardware_components(node, controller_manager_name, service_timeout=0.0):
85153
request = ListHardwareComponents.Request()
86154
return service_caller(
87155
node,
@@ -92,7 +160,7 @@ def list_hardware_components(node, controller_manager_name, service_timeout=10.0
92160
)
93161

94162

95-
def list_hardware_interfaces(node, controller_manager_name, service_timeout=10.0):
163+
def list_hardware_interfaces(node, controller_manager_name, service_timeout=0.0):
96164
request = ListHardwareInterfaces.Request()
97165
return service_caller(
98166
node,
@@ -103,7 +171,7 @@ def list_hardware_interfaces(node, controller_manager_name, service_timeout=10.0
103171
)
104172

105173

106-
def load_controller(node, controller_manager_name, controller_name, service_timeout=10.0):
174+
def load_controller(node, controller_manager_name, controller_name, service_timeout=0.0):
107175
request = LoadController.Request()
108176
request.name = controller_name
109177
return service_caller(
@@ -115,7 +183,7 @@ def load_controller(node, controller_manager_name, controller_name, service_time
115183
)
116184

117185

118-
def reload_controller_libraries(node, controller_manager_name, force_kill, service_timeout=10.0):
186+
def reload_controller_libraries(node, controller_manager_name, force_kill, service_timeout=0.0):
119187
request = ReloadControllerLibraries.Request()
120188
request.force_kill = force_kill
121189
return service_caller(
@@ -128,7 +196,7 @@ def reload_controller_libraries(node, controller_manager_name, force_kill, servi
128196

129197

130198
def set_hardware_component_state(
131-
node, controller_manager_name, component_name, lifecyle_state, service_timeout=10.0
199+
node, controller_manager_name, component_name, lifecyle_state, service_timeout=0.0
132200
):
133201
request = SetHardwareComponentState.Request()
134202
request.name = component_name
@@ -165,7 +233,7 @@ def switch_controllers(
165233
)
166234

167235

168-
def unload_controller(node, controller_manager_name, controller_name, service_timeout=10.0):
236+
def unload_controller(node, controller_manager_name, controller_name, service_timeout=0.0):
169237
request = UnloadController.Request()
170238
request.name = controller_name
171239
return service_caller(
@@ -175,3 +243,97 @@ def unload_controller(node, controller_manager_name, controller_name, service_ti
175243
request,
176244
service_timeout,
177245
)
246+
247+
248+
def get_parameter_from_param_file(controller_name, namespace, parameter_file, parameter_name):
249+
with open(parameter_file) as f:
250+
namespaced_controller = (
251+
controller_name if namespace == "/" else f"{namespace}/{controller_name}"
252+
)
253+
parameters = yaml.safe_load(f)
254+
if namespaced_controller in parameters:
255+
value = parameters[namespaced_controller]
256+
if not isinstance(value, dict) or "ros__parameters" not in value:
257+
raise RuntimeError(
258+
f"YAML file : {parameter_file} is not a valid ROS parameter file for controller : {namespaced_controller}"
259+
)
260+
if parameter_name in parameters[namespaced_controller]["ros__parameters"]:
261+
return parameters[namespaced_controller]["ros__parameters"][parameter_name]
262+
else:
263+
return None
264+
else:
265+
return None
266+
267+
268+
def set_controller_parameters(
269+
node, controller_manager_name, controller_name, parameter_name, parameter_value
270+
):
271+
parameter = Parameter()
272+
parameter.name = controller_name + "." + parameter_name
273+
parameter_string = str(parameter_value)
274+
parameter.value = get_parameter_value(string_value=parameter_string)
275+
276+
response = call_set_parameters(
277+
node=node, node_name=controller_manager_name, parameters=[parameter]
278+
)
279+
assert len(response.results) == 1
280+
result = response.results[0]
281+
if result.successful:
282+
node.get_logger().info(
283+
bcolors.OKCYAN
284+
+ 'Setting controller param "'
285+
+ parameter_name
286+
+ '" to "'
287+
+ parameter_string
288+
+ '" for '
289+
+ bcolors.BOLD
290+
+ controller_name
291+
+ bcolors.ENDC
292+
)
293+
else:
294+
node.get_logger().fatal(
295+
bcolors.FAIL
296+
+ 'Could not set controller param "'
297+
+ parameter_name
298+
+ '" to "'
299+
+ parameter_string
300+
+ '" for '
301+
+ bcolors.BOLD
302+
+ controller_name
303+
+ bcolors.ENDC
304+
)
305+
return False
306+
return True
307+
308+
309+
def set_controller_parameters_from_param_file(
310+
node, controller_manager_name, controller_name, parameter_file, namespace=None
311+
):
312+
if parameter_file:
313+
spawner_namespace = namespace if namespace else node.get_namespace()
314+
set_controller_parameters(
315+
node, controller_manager_name, controller_name, "params_file", parameter_file
316+
)
317+
318+
controller_type = get_parameter_from_param_file(
319+
controller_name, spawner_namespace, parameter_file, "type"
320+
)
321+
if controller_type:
322+
if not set_controller_parameters(
323+
node, controller_manager_name, controller_name, "type", controller_type
324+
):
325+
return False
326+
327+
fallback_controllers = get_parameter_from_param_file(
328+
controller_name, spawner_namespace, parameter_file, "fallback_controllers"
329+
)
330+
if fallback_controllers:
331+
if not set_controller_parameters(
332+
node,
333+
controller_manager_name,
334+
controller_name,
335+
"fallback_controllers",
336+
fallback_controllers,
337+
):
338+
return False
339+
return True

0 commit comments

Comments
 (0)