Skip to content

Commit 9b964fa

Browse files
authored
Merge branch 'ros2:rolling' into hliberacki/spin_until
2 parents 4cd9754 + 3053a8a commit 9b964fa

File tree

12 files changed

+715
-11
lines changed

12 files changed

+715
-11
lines changed
Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
name: Mirror rolling to master
2+
3+
on:
4+
push:
5+
branches: [ rolling ]
6+
7+
jobs:
8+
mirror-to-master:
9+
runs-on: ubuntu-latest
10+
steps:
11+
- uses: zofrex/mirror-branch@v1
12+
with:
13+
target-branch: master

rclpy/docs/source/api/parameters.rst

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,3 +10,8 @@ Parameter Service
1010
-----------------
1111

1212
.. automodule:: rclpy.parameter_service
13+
14+
Parameter Client
15+
-----------------
16+
17+
.. automodule:: rclpy.parameter_client

rclpy/docs/source/conf.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,7 @@
5858
'sphinx.ext.autosummary',
5959
'sphinx.ext.doctest',
6060
'sphinx.ext.coverage',
61+
'sphinx_rtd_theme',
6162
]
6263

6364
# Add any paths that contain templates here, relative to this directory.
@@ -93,7 +94,7 @@
9394
# The theme to use for HTML and HTML Help pages. See the documentation for
9495
# a list of builtin themes.
9596
#
96-
html_theme = 'alabaster'
97+
html_theme = 'sphinx_rtd_theme'
9798

9899
# Theme options are theme-specific and customize the look and feel of a theme
99100
# further. For a list of options available for each theme, see the

rclpy/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,7 @@
4848
<test_depend>test_msgs</test_depend>
4949

5050
<doc_depend>python3-sphinx</doc_depend>
51+
<doc_depend>python3-sphinx-rtd-theme</doc_depend>
5152

5253
<export>
5354
<build_type>ament_cmake</build_type>

rclpy/rclpy/client.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ def unblock(future):
101101

102102
def call_async(self, request: SrvTypeRequest) -> Future:
103103
"""
104-
Make a service request and asyncronously get the result.
104+
Make a service request and asynchronously get the result.
105105
106106
:param request: The service request.
107107
:return: A future that completes when the request does.
@@ -170,6 +170,7 @@ def wait_for_service(self, timeout_sec: float = None) -> bool:
170170
"""
171171
# TODO(sloretz) Return as soon as the service is available
172172
# This is a temporary implementation. The sleep time is arbitrary.
173+
# https://github.com/ros2/rclpy/issues/58
173174
sleep_time = 0.25
174175
if timeout_sec is None:
175176
timeout_sec = float('inf')

rclpy/rclpy/executors.py

Lines changed: 12 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -79,15 +79,15 @@ def __exit__(self, t, v, tb):
7979
self._num_work_executing -= 1
8080
self._work_condition.notify_all()
8181

82-
def wait(self, timeout_sec=None):
82+
def wait(self, timeout_sec: Optional[float] = None):
8383
"""
8484
Wait until all work completes.
8585
8686
:param timeout_sec: Seconds to wait. Block forever if None or negative. Don't wait if 0
8787
:type timeout_sec: float or None
8888
:rtype: bool True if all work completed
8989
"""
90-
if timeout_sec is not None and timeout_sec < 0:
90+
if timeout_sec is not None and timeout_sec < 0.0:
9191
timeout_sec = None
9292
# Wait for all work to complete
9393
with self._work_condition:
@@ -204,9 +204,9 @@ def shutdown(self, timeout_sec: float = None) -> bool:
204204
self._is_shutdown = True
205205
# Tell executor it's been shut down
206206
self._guard.trigger()
207-
208-
if not self._work_tracker.wait(timeout_sec):
209-
return False
207+
if not self._is_shutdown:
208+
if not self._work_tracker.wait(timeout_sec):
209+
return False
210210

211211
# Clean up stuff that won't be used anymore
212212
with self._nodes_lock:
@@ -464,7 +464,13 @@ async def handler(entity, gc, is_shutdown, work_tracker):
464464
entity.callback_group.ending_execution(entity)
465465
# Signal that work has been done so the next callback in a mutually exclusive
466466
# callback group can get executed
467-
gc.trigger()
467+
468+
# Catch expected error where calling executor.shutdown()
469+
# from callback causes the GuardCondition to be destroyed
470+
try:
471+
gc.trigger()
472+
except InvalidHandle:
473+
pass
468474
task = Task(
469475
handler, (entity, self._guard, self._is_shutdown, self._work_tracker),
470476
executor=self)

rclpy/rclpy/node.py

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -349,6 +349,9 @@ def declare_parameter(
349349
This method, if successful, will result in any callback registered with
350350
:func:`add_on_set_parameters_callback` to be called.
351351
352+
The name and type in the given descriptor is ignored, and should be specified using
353+
the name argument to this function and the default value's type instead.
354+
352355
:param name: Fully-qualified name of the parameter, including its namespace.
353356
:param value: Value of the parameter to declare.
354357
:param descriptor: Descriptor for the parameter to declare.
@@ -381,6 +384,8 @@ def declare_parameters(
381384
382385
The tuples in the given parameter list shall contain the name for each parameter,
383386
optionally providing a value and a descriptor.
387+
The name and type in the given descriptors are ignored, and should be specified using
388+
the name argument to this function and the default value's type instead.
384389
For each entry in the list, a parameter with a name of "namespace.name"
385390
will be declared.
386391
The resulting value for each declared parameter will be returned, considering
@@ -750,7 +755,7 @@ def set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetParam
750755
allowed for the node, this method will raise a ParameterNotDeclaredException exception.
751756
752757
Parameters are set all at once.
753-
If setting a parameter fails due to not being declared, then no parameter will be set set.
758+
If setting a parameter fails due to not being declared, then no parameter will be set.
754759
Either all of the parameters are set or none of them are set.
755760
756761
If undeclared parameters are allowed for the node, then all the parameters will be

rclpy/rclpy/parameter.py

Lines changed: 126 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,9 +14,14 @@
1414

1515
import array
1616
from enum import Enum
17+
from typing import Dict
18+
from typing import List
19+
from typing import Optional
1720

1821
from rcl_interfaces.msg import Parameter as ParameterMsg
19-
from rcl_interfaces.msg import ParameterType, ParameterValue
22+
from rcl_interfaces.msg import ParameterType
23+
from rcl_interfaces.msg import ParameterValue
24+
import yaml
2025

2126
PARAMETER_SEPARATOR_STRING = '.'
2227

@@ -177,6 +182,50 @@ def to_parameter_msg(self):
177182
return ParameterMsg(name=self.name, value=self.get_parameter_value())
178183

179184

185+
def get_parameter_value(string_value: str) -> ParameterValue:
186+
"""
187+
Guess the desired type of the parameter based on the string value.
188+
189+
:param string_value: The string value to be converted to a ParameterValue.
190+
:return: The ParameterValue.
191+
"""
192+
value = ParameterValue()
193+
try:
194+
yaml_value = yaml.safe_load(string_value)
195+
except yaml.parser.ParserError:
196+
yaml_value = string_value
197+
198+
if isinstance(yaml_value, bool):
199+
value.type = ParameterType.PARAMETER_BOOL
200+
value.bool_value = yaml_value
201+
elif isinstance(yaml_value, int):
202+
value.type = ParameterType.PARAMETER_INTEGER
203+
value.integer_value = yaml_value
204+
elif isinstance(yaml_value, float):
205+
value.type = ParameterType.PARAMETER_DOUBLE
206+
value.double_value = yaml_value
207+
elif isinstance(yaml_value, list):
208+
if all((isinstance(v, bool) for v in yaml_value)):
209+
value.type = ParameterType.PARAMETER_BOOL_ARRAY
210+
value.bool_array_value = yaml_value
211+
elif all((isinstance(v, int) for v in yaml_value)):
212+
value.type = ParameterType.PARAMETER_INTEGER_ARRAY
213+
value.integer_array_value = yaml_value
214+
elif all((isinstance(v, float) for v in yaml_value)):
215+
value.type = ParameterType.PARAMETER_DOUBLE_ARRAY
216+
value.double_array_value = yaml_value
217+
elif all((isinstance(v, str) for v in yaml_value)):
218+
value.type = ParameterType.PARAMETER_STRING_ARRAY
219+
value.string_array_value = yaml_value
220+
else:
221+
value.type = ParameterType.PARAMETER_STRING
222+
value.string_value = string_value
223+
else:
224+
value.type = ParameterType.PARAMETER_STRING
225+
value.string_value = yaml_value
226+
return value
227+
228+
180229
def parameter_value_to_python(parameter_value: ParameterValue):
181230
"""
182231
Get the value for the Python builtin type from a rcl_interfaces/msg/ParameterValue object.
@@ -211,3 +260,79 @@ def parameter_value_to_python(parameter_value: ParameterValue):
211260
raise RuntimeError(f'unexpected parameter type {parameter_value.type}')
212261

213262
return value
263+
264+
265+
def parameter_dict_from_yaml_file(
266+
parameter_file: str,
267+
use_wildcard: bool = False,
268+
target_nodes: Optional[List[str]] = None,
269+
namespace: str = ''
270+
) -> Dict[str, ParameterMsg]:
271+
"""
272+
Build a dict of parameters from a YAML file.
273+
274+
Will load all parameters if ``target_nodes`` is None or empty.
275+
276+
:raises RuntimeError: if a target node is not in the file
277+
:raises RuntimeError: if the is not a valid ROS parameter file
278+
279+
:param parameter_file: Path to the YAML file to load parameters from.
280+
:param use_wildcard: Use wildcard matching for the target nodes.
281+
:param target_nodes: List of nodes in the YAML file to load parameters from.
282+
:param namespace: Namespace to prepend to all parameters.
283+
:return: A dict of Parameter messages keyed by the parameter names
284+
"""
285+
with open(parameter_file, 'r') as f:
286+
param_file = yaml.safe_load(f)
287+
param_keys = []
288+
param_dict = {}
289+
290+
if use_wildcard and '/**' in param_file:
291+
param_keys.append('/**')
292+
293+
if target_nodes:
294+
for n in target_nodes:
295+
if n not in param_file.keys():
296+
raise RuntimeError(f'Param file does not contain parameters for {n},'
297+
f'only for nodes: {list(param_file.keys())} ')
298+
param_keys.append(n)
299+
else:
300+
# wildcard key must go to the front of param_keys so that
301+
# node-namespaced parameters will override the wildcard parameters
302+
keys = set(param_file.keys())
303+
keys.discard('/**')
304+
param_keys.extend(keys)
305+
306+
if len(param_keys) == 0:
307+
raise RuntimeError('Param file does not contain selected parameters')
308+
309+
for n in param_keys:
310+
value = param_file[n]
311+
if type(value) != dict or 'ros__parameters' not in value:
312+
raise RuntimeError(f'YAML file is not a valid ROS parameter file for node {n}')
313+
param_dict.update(value['ros__parameters'])
314+
return _unpack_parameter_dict(namespace, param_dict)
315+
316+
317+
def _unpack_parameter_dict(namespace, parameter_dict):
318+
"""
319+
Flatten a parameter dictionary recursively.
320+
321+
:param namespace: The namespace to prepend to the parameter names.
322+
:param parameter_dict: A dictionary of parameters keyed by the parameter names
323+
:return: A dict of Parameter objects keyed by the parameter names
324+
"""
325+
parameters: Dict[str, ParameterMsg] = {}
326+
for param_name, param_value in parameter_dict.items():
327+
full_param_name = namespace + param_name
328+
# Unroll nested parameters
329+
if type(param_value) == dict:
330+
parameters.update(_unpack_parameter_dict(
331+
namespace=full_param_name + PARAMETER_SEPARATOR_STRING,
332+
parameter_dict=param_value))
333+
else:
334+
parameter = ParameterMsg()
335+
parameter.name = full_param_name
336+
parameter.value = get_parameter_value(str(param_value))
337+
parameters[full_param_name] = parameter
338+
return parameters

0 commit comments

Comments
 (0)