-
Notifications
You must be signed in to change notification settings - Fork 217
/
node.py
2190 lines (1872 loc) · 92.4 KB
/
node.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
# Copyright 2016 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 math
import time
from typing import Any
from typing import Callable
from typing import Dict
from typing import Iterator
from typing import List
from typing import Optional
from typing import Sequence
from typing import Tuple
from typing import Type
from typing import TypeVar
from typing import Union
import warnings
import weakref
from rcl_interfaces.msg import FloatingPointRange
from rcl_interfaces.msg import IntegerRange
from rcl_interfaces.msg import Parameter as ParameterMsg
from rcl_interfaces.msg import ParameterDescriptor
from rcl_interfaces.msg import ParameterEvent
from rcl_interfaces.msg import ParameterType
from rcl_interfaces.msg import ParameterValue
from rcl_interfaces.msg import SetParametersResult
from rclpy.callback_groups import CallbackGroup
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup
from rclpy.callback_groups import ReentrantCallbackGroup
from rclpy.client import Client
from rclpy.clock import Clock
from rclpy.clock import ROSClock
from rclpy.constants import S_TO_NS
from rclpy.context import Context
from rclpy.event_handler import PublisherEventCallbacks
from rclpy.event_handler import SubscriptionEventCallbacks
from rclpy.exceptions import InvalidHandle
from rclpy.exceptions import InvalidParameterTypeException
from rclpy.exceptions import InvalidParameterValueException
from rclpy.exceptions import InvalidTopicNameException
from rclpy.exceptions import NotInitializedException
from rclpy.exceptions import ParameterAlreadyDeclaredException
from rclpy.exceptions import ParameterImmutableException
from rclpy.exceptions import ParameterNotDeclaredException
from rclpy.exceptions import ParameterUninitializedException
from rclpy.executors import Executor
from rclpy.expand_topic_name import expand_topic_name
from rclpy.guard_condition import GuardCondition
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
from rclpy.logging import get_logger
from rclpy.logging_service import LoggingService
from rclpy.parameter import Parameter, PARAMETER_SEPARATOR_STRING
from rclpy.parameter_service import ParameterService
from rclpy.publisher import Publisher
from rclpy.qos import qos_profile_parameter_events
from rclpy.qos import qos_profile_services_default
from rclpy.qos import QoSProfile
from rclpy.qos_overriding_options import _declare_qos_parameters
from rclpy.qos_overriding_options import QoSOverridingOptions
from rclpy.service import Service
from rclpy.subscription import Subscription
from rclpy.time_source import TimeSource
from rclpy.timer import Rate
from rclpy.timer import Timer
from rclpy.topic_endpoint_info import TopicEndpointInfo
from rclpy.type_description_service import TypeDescriptionService
from rclpy.type_support import check_is_valid_msg_type
from rclpy.type_support import check_is_valid_srv_type
from rclpy.utilities import get_default_context
from rclpy.validate_full_topic_name import validate_full_topic_name
from rclpy.validate_namespace import validate_namespace
from rclpy.validate_node_name import validate_node_name
from rclpy.validate_parameter_name import validate_parameter_name
from rclpy.validate_topic_name import validate_topic_name
from rclpy.waitable import Waitable
HIDDEN_NODE_PREFIX = '_'
# Used for documentation purposes only
MsgType = TypeVar('MsgType')
SrvType = TypeVar('SrvType')
SrvTypeRequest = TypeVar('SrvTypeRequest')
SrvTypeResponse = TypeVar('SrvTypeResponse')
# Re-export exception defined in _rclpy C extension.
# `Node.get_*_names_and_types_by_node` methods may raise this error.
NodeNameNonExistentError = _rclpy.NodeNameNonExistentError
class Node:
"""
A Node in the ROS graph.
A Node is the primary entrypoint in a ROS system for communication.
It can be used to create ROS entities such as publishers, subscribers, services, etc.
"""
PARAM_REL_TOL = 1e-6
"""
Relative tolerance for floating point parameter values' comparison.
See `math.isclose` documentation.
"""
def __init__(
self,
node_name: str,
*,
context: Context = None,
cli_args: List[str] = None,
namespace: str = None,
use_global_arguments: bool = True,
enable_rosout: bool = True,
start_parameter_services: bool = True,
parameter_overrides: Optional[List[Parameter]] = None,
allow_undeclared_parameters: bool = False,
automatically_declare_parameters_from_overrides: bool = False,
enable_logger_service: bool = False
) -> None:
"""
Create a Node.
:param node_name: A name to give to this node. Validated by :func:`validate_node_name`.
:param context: The context to be associated with, or ``None`` for the default global
context.
:param cli_args: A list of strings of command line args to be used only by this node.
These arguments are used to extract remappings used by the node and other ROS specific
settings, as well as user defined non-ROS arguments.
:param namespace: The namespace to which relative topic and service names will be prefixed.
Validated by :func:`validate_namespace`.
:param use_global_arguments: ``False`` if the node should ignore process-wide command line
args.
:param enable_rosout: ``False`` if the node should ignore rosout logging.
:param start_parameter_services: ``False`` if the node should not create parameter
services.
:param parameter_overrides: A list of overrides for initial values for parameters declared
on the node.
:param allow_undeclared_parameters: True if undeclared parameters are allowed.
This flag affects the behavior of parameter-related operations.
:param automatically_declare_parameters_from_overrides: If True, the "parameter overrides"
will be used to implicitly declare parameters on the node during creation.
:param enable_logger_service: ``True`` if ROS2 services are created to allow external nodes
to get and set logger levels of this node. Otherwise, logger levels are only managed
locally. That is, logger levels cannot be changed remotely.
"""
self.__handle = None
self._context = get_default_context() if context is None else context
self._parameters: dict = {}
self._publishers: List[Publisher] = []
self._subscriptions: List[Subscription] = []
self._clients: List[Client] = []
self._services: List[Service] = []
self._timers: List[Timer] = []
self._guards: List[GuardCondition] = []
self.__waitables: List[Waitable] = []
self._default_callback_group = MutuallyExclusiveCallbackGroup()
self._pre_set_parameters_callbacks: List[Callable[[List[Parameter]], List[Parameter]]] = []
self._on_set_parameters_callbacks: \
List[Callable[[List[Parameter]], SetParametersResult]] = []
self._post_set_parameters_callbacks: List[Callable[[List[Parameter]], None]] = []
self._rate_group = ReentrantCallbackGroup()
self._allow_undeclared_parameters = allow_undeclared_parameters
self._parameter_overrides = {}
self._descriptors = {}
namespace = namespace or ''
if not self._context.ok():
raise NotInitializedException('cannot create node')
with self._context.handle:
try:
self.__node = _rclpy.Node(
node_name,
namespace,
self._context.handle,
cli_args,
use_global_arguments,
enable_rosout
)
except ValueError:
# these will raise more specific errors if the name or namespace is bad
validate_node_name(node_name)
# emulate what rcl_node_init() does to accept '' and relative namespaces
if not namespace:
namespace = '/'
if not namespace.startswith('/'):
namespace = '/' + namespace
validate_namespace(namespace)
# Should not get to this point
raise RuntimeError('rclpy_create_node failed for unknown reason')
with self.handle:
self._logger = get_logger(self.__node.logger_name())
self.__executor_weakref = None
self._parameter_event_publisher = self.create_publisher(
ParameterEvent, '/parameter_events', qos_profile_parameter_events)
with self.handle:
self._parameter_overrides = self.__node.get_parameters(Parameter)
# Combine parameters from params files with those from the node constructor and
# use the set_parameters_atomically API so a parameter event is published.
if parameter_overrides is not None:
self._parameter_overrides.update({p.name: p for p in parameter_overrides})
# Clock that has support for ROS time.
self._clock = ROSClock()
if automatically_declare_parameters_from_overrides:
self.declare_parameters(
'',
[
(name, param.value, ParameterDescriptor())
for name, param in self._parameter_overrides.items()],
ignore_override=True,
)
# Init a time source.
# Note: parameter overrides and parameter event publisher need to be ready at this point
# to be able to declare 'use_sim_time' if it was not declared yet.
self._time_source = TimeSource(node=self)
self._time_source.attach_clock(self._clock)
if start_parameter_services:
self._parameter_service = ParameterService(self)
if enable_logger_service:
self._logger_service = LoggingService(self)
self._type_description_service = TypeDescriptionService(self)
@property
def publishers(self) -> Iterator[Publisher]:
"""Get publishers that have been created on this node."""
yield from self._publishers
@property
def subscriptions(self) -> Iterator[Subscription]:
"""Get subscriptions that have been created on this node."""
yield from self._subscriptions
@property
def clients(self) -> Iterator[Client]:
"""Get clients that have been created on this node."""
yield from self._clients
@property
def services(self) -> Iterator[Service]:
"""Get services that have been created on this node."""
yield from self._services
@property
def timers(self) -> Iterator[Timer]:
"""Get timers that have been created on this node."""
yield from self._timers
@property
def guards(self) -> Iterator[GuardCondition]:
"""Get guards that have been created on this node."""
yield from self._guards
@property
def waitables(self) -> Iterator[Waitable]:
"""Get waitables that have been created on this node."""
yield from self.__waitables
@property
def executor(self) -> Optional[Executor]:
"""Get the executor if the node has been added to one, else return ``None``."""
if self.__executor_weakref:
return self.__executor_weakref()
return None
@executor.setter
def executor(self, new_executor: Executor) -> None:
"""Set or change the executor the node belongs to."""
current_executor = self.executor
if current_executor == new_executor:
return
if current_executor is not None:
current_executor.remove_node(self)
if new_executor is None:
self.__executor_weakref = None
else:
new_executor.add_node(self)
self.__executor_weakref = weakref.ref(new_executor)
def _wake_executor(self):
executor = self.executor
if executor:
executor.wake()
@property
def context(self) -> Context:
"""Get the context associated with the node."""
return self._context
@property
def default_callback_group(self) -> CallbackGroup:
"""
Get the default callback group.
If no other callback group is provided when the a ROS entity is created with the node,
then it is added to the default callback group.
"""
return self._default_callback_group
@property
def handle(self):
"""
Get the handle to the underlying `rcl_node_t`.
Cannot be modified after node creation.
:raises: AttributeError if modified after creation.
"""
return self.__node
@handle.setter
def handle(self, value):
raise AttributeError('handle cannot be modified after node creation')
def get_name(self) -> str:
"""Get the name of the node."""
with self.handle:
return self.handle.get_node_name()
def get_namespace(self) -> str:
"""Get the namespace of the node."""
with self.handle:
return self.handle.get_namespace()
def get_clock(self) -> Clock:
"""Get the clock used by the node."""
return self._clock
def get_logger(self):
"""Get the nodes logger."""
return self._logger
def declare_parameter(
self,
name: str,
value: Any = None,
descriptor: Optional[ParameterDescriptor] = None,
ignore_override: bool = False
) -> Parameter:
"""
Declare and initialize a parameter.
This method, if successful, will result in any callback registered with
:func:`add_on_set_parameters_callback` and :func:`add_post_set_parameters_callback`
to be called.
The name and type in the given descriptor is ignored, and should be specified using
the name argument to this function and the default value's type instead.
:param name: Fully-qualified name of the parameter, including its namespace.
:param value: Value of the parameter to declare.
:param descriptor: Descriptor for the parameter to declare.
:param ignore_override: True if overrides shall not be taken into account; False otherwise.
:return: Parameter with the effectively assigned value.
:raises: ParameterAlreadyDeclaredException if the parameter had already been declared.
:raises: InvalidParameterException if the parameter name is invalid.
:raises: InvalidParameterValueException if the registered callback rejects the parameter.
"""
if value is None and descriptor is None:
# Temporal patch so we get deprecation warning if only a name is provided.
args = (name, )
else:
descriptor = ParameterDescriptor() if descriptor is None else descriptor
args = (name, value, descriptor)
return self.declare_parameters('', [args], ignore_override)[0]
def declare_parameters(
self,
namespace: str,
parameters: List[Union[
Tuple[str],
Tuple[str, Parameter.Type],
Tuple[str, Any, ParameterDescriptor],
]],
ignore_override: bool = False
) -> List[Parameter]:
"""
Declare a list of parameters.
The tuples in the given parameter list shall contain the name for each parameter,
optionally providing a value and a descriptor.
The name and type in the given descriptors are ignored, and should be specified using
the name argument to this function and the default value's type instead.
For each entry in the list, a parameter with a name of "namespace.name"
will be declared.
The resulting value for each declared parameter will be returned, considering
parameter overrides set upon node creation as the first choice,
or provided parameter values as the second one.
The name expansion is naive, so if you set the namespace to be "foo.",
then the resulting parameter names will be like "foo..name".
However, if the namespace is an empty string, then no leading '.' will be
placed before each name, which would have been the case when naively
expanding "namespace.name".
This allows you to declare several parameters at once without a namespace.
This method will result in any callback registered with
:func:`add_on_set_parameters_callback` and :func:`add_post_set_parameters_callback`
to be called once for each parameter.
If a callback was registered previously with :func:`add_on_set_parameters_callback`, it
will be called prior to setting the parameters for the node, once for each parameter.
If one of the calls due to :func:`add_on_set_parameters_callback` fail, an exception will
be raised and the remaining parameters will not be declared. Parameters declared up to that
point will not be undeclared.
If a callback was registered previously with :func:`add_post_set_parameters_callback`,
it will be called after setting the parameters successfully for the node,
once for each parameter.
This method will `not` result in any callbacks registered with
:func:`add_pre_set_parameters_callback` to be called.
:param namespace: Namespace for parameters.
:param parameters: List of tuples with parameters to declare.
:param ignore_override: True if overrides shall not be taken into account; False otherwise.
:return: Parameter list with the effectively assigned values for each of them.
:raises: ParameterAlreadyDeclaredException if the parameter had already been declared.
:raises: InvalidParameterException if the parameter name is invalid.
:raises: InvalidParameterValueException if the registered callback rejects any parameter.
:raises: TypeError if any tuple in **parameters** does not match the annotated type.
"""
parameter_list = []
descriptors = {}
for index, parameter_tuple in enumerate(parameters):
if len(parameter_tuple) < 1 or len(parameter_tuple) > 3:
raise TypeError(
'Invalid parameter tuple length at index {index} in parameters list: '
'{parameter_tuple}; expecting length between 1 and 3'.format_map(locals())
)
value = None
param_type = None
# Get the values from the tuple, checking its types.
# Use defaults if the tuple doesn't contain value and / or descriptor.
name = parameter_tuple[0]
second_arg = parameter_tuple[1] if 1 < len(parameter_tuple) else None
descriptor = parameter_tuple[2] if 2 < len(parameter_tuple) else ParameterDescriptor()
if not isinstance(name, str):
raise TypeError(
f'First element {name} at index {index} in parameters list '
'is not a str.')
if not isinstance(descriptor, ParameterDescriptor):
raise TypeError(
f'Third element {descriptor} at index {index} in parameters list '
'is not a ParameterDescriptor.'
)
if len(parameter_tuple) == 1:
warnings.warn(
f"when declaring parameter named '{name}', "
'declaring a parameter only providing its name is deprecated. '
'You have to either:\n'
'\t- Pass a name and a default value different to "PARAMETER NOT SET"'
' (and optionally a descriptor).\n'
'\t- Pass a name and a parameter type.\n'
'\t- Pass a name and a descriptor with `dynamic_typing=True')
descriptor.dynamic_typing = True
if isinstance(second_arg, Parameter.Type):
if second_arg == Parameter.Type.NOT_SET:
raise ValueError(
f'Cannot declare parameter {{{name}}} as statically typed of type NOT_SET')
if descriptor.dynamic_typing is True:
raise ValueError(
f'When declaring parameter {{{name}}} passing a descriptor with'
'`dynamic_typing=True` is not allowed when the parameter type is provided')
descriptor.type = second_arg.value
else:
value = second_arg
if not descriptor.dynamic_typing and value is not None:
# infer type from default value
if not isinstance(value, ParameterValue):
descriptor.type = Parameter.Type.from_parameter_value(value).value
else:
if value.type == ParameterType.PARAMETER_NOT_SET:
raise ValueError(
'Cannot declare a statically typed parameter with default value '
'of type PARAMETER_NOT_SET')
descriptor.type = value.type
# Get value from parameter overrides, of from tuple if it doesn't exist.
if not ignore_override and name in self._parameter_overrides:
value = self._parameter_overrides[name].value
if namespace:
name = f'{namespace}.{name}'
# Note(jubeira): declare_parameters verifies the name, but set_parameters doesn't.
validate_parameter_name(name)
parameter_list.append(Parameter(name, value=value))
descriptors.update({name: descriptor})
parameters_already_declared = [
parameter.name for parameter in parameter_list if parameter.name in self._parameters
]
if any(parameters_already_declared):
raise ParameterAlreadyDeclaredException(parameters_already_declared)
# Call the callback once for each of the parameters, using method that doesn't
# check whether the parameter was declared beforehand or not.
self._declare_parameter_common(
parameter_list,
descriptors
)
# Don't call get_parameters() to bypass check for NOT_SET parameters
return [self._parameters[parameter.name] for parameter in parameter_list]
def _declare_parameter_common(
self,
parameter_list: List[Parameter],
descriptors: Optional[Dict[str, ParameterDescriptor]] = None
) -> List[SetParametersResult]:
"""
Declare parameters for the node, and return the result for the declare action.
Method for internal usage; applies a setter method for each parameters in the list.
By default, it checks if the parameters were declared, raising an exception if at least
one of them was not.
This method will result in any callback registered with
:func:`add_on_set_parameters_callback` and :func:`add_post_set_parameters_callback`
to be called once for each parameter.
If a callback was registered previously with :func:`add_on_set_parameters_callback`, it
will be called prior to setting the parameters for the node, once for each parameter.
If the callback doesn't succeed for a given parameter an exception will be raised.
If a callback was registered previously with :func:`add_post_set_parameters_callback`,
it will be called after setting the parameters successfully for the node,
once for each parameter.
This method will `not` result in any callbacks registered with
:func:`add_pre_set_parameters_callback` to be called.
:param parameter_list: List of parameters to set.
:param descriptors: Descriptors to set to the given parameters.
If descriptors are given, each parameter in the list must have a corresponding one.
:return: The result for each set action as a list.
:raises: InvalidParameterValueException if the user-defined callback rejects the
parameter value.
:raises: ParameterNotDeclaredException if undeclared parameters are not allowed in this
method and at least one parameter in the list hadn't been declared beforehand.`
"""
if descriptors is not None:
assert all(parameter.name in descriptors for parameter in parameter_list)
results = []
for param in parameter_list:
# If undeclared parameters are allowed, parameters with type NOT_SET shall be stored.
result = self._set_parameters_atomically_common(
[param],
descriptors,
allow_not_set_type=True
)
if not result.successful:
if result.reason.startswith('Wrong parameter type'):
raise InvalidParameterTypeException(
param, Parameter.Type(descriptors[param._name].type).name)
raise InvalidParameterValueException(param.name, param.value, result.reason)
results.append(result)
return results
def undeclare_parameter(self, name: str):
"""
Undeclare a previously declared parameter.
This method will not cause a callback registered with any of the
:func:`add_pre_set_parameters_callback`,
and :func:`add_post_set_parameters_callback` to be called.
:param name: Fully-qualified name of the parameter, including its namespace.
:raises: ParameterNotDeclaredException if parameter had not been declared before.
:raises: ParameterImmutableException if the parameter was created as read-only.
"""
if self.has_parameter(name):
if self._descriptors[name].read_only:
raise ParameterImmutableException(name)
else:
del self._parameters[name]
del self._descriptors[name]
else:
raise ParameterNotDeclaredException(name)
def has_parameter(self, name: str) -> bool:
"""Return True if parameter is declared; False otherwise."""
return name in self._parameters
def get_parameter_types(self, names: List[str]) -> List[Parameter.Type]:
"""
Get a list of parameter types.
:param names: Fully-qualified names of the parameters to get, including their namespaces.
:return: The values for the given parameter types.
A default Parameter.Type.NOT_SET will be returned for undeclared parameters
if undeclared parameters are allowed.
:raises: ParameterNotDeclaredException if undeclared parameters are not allowed,
and at least one parameter hadn't been declared beforehand.
"""
if not all(isinstance(name, str) for name in names):
raise TypeError('All names must be instances of type str')
return [self.get_parameter_type(name) for name in names]
def get_parameter_type(self, name: str) -> Parameter.Type:
"""
Get a parameter type by name.
:param name: Fully-qualified name of the parameter, including its namespace.
:return: The type for the given parameter name.
A default Parameter.Type.NOT_SET will be returned for an undeclared parameter
if undeclared parameters are allowed.
:raises: ParameterNotDeclaredException if undeclared parameters are not allowed,
and the parameter hadn't been declared beforehand.
"""
if self.has_parameter(name):
return self._parameters[name].type_.value
elif self._allow_undeclared_parameters:
return Parameter.Type.NOT_SET
else:
raise ParameterNotDeclaredException(name)
def get_parameters(self, names: List[str]) -> List[Parameter]:
"""
Get a list of parameters.
:param names: Fully-qualified names of the parameters to get, including their namespaces.
:return: The values for the given parameter names.
A default Parameter will be returned for undeclared parameters if
undeclared parameters are allowed.
:raises: ParameterNotDeclaredException if undeclared parameters are not allowed,
and at least one parameter hadn't been declared beforehand.
:raises: ParameterUninitializedException if at least one parameter is statically typed and
uninitialized.
"""
if not all(isinstance(name, str) for name in names):
raise TypeError('All names must be instances of type str')
return [self.get_parameter(name) for name in names]
def get_parameter(self, name: str) -> Parameter:
"""
Get a parameter by name.
:param name: Fully-qualified name of the parameter, including its namespace.
:return: The value for the given parameter name.
A default Parameter will be returned for an undeclared parameter if
undeclared parameters are allowed.
:raises: ParameterNotDeclaredException if undeclared parameters are not allowed,
and the parameter hadn't been declared beforehand.
:raises: ParameterUninitializedException if the parameter is statically typed and
uninitialized.
"""
if self.has_parameter(name):
parameter = self._parameters[name]
if (
parameter.type_ != Parameter.Type.NOT_SET or
self._descriptors[name].dynamic_typing
):
return self._parameters[name]
# Statically typed, uninitialized parameter
raise ParameterUninitializedException(name)
elif self._allow_undeclared_parameters:
return Parameter(name, Parameter.Type.NOT_SET, None)
else:
raise ParameterNotDeclaredException(name)
def get_parameter_or(
self, name: str, alternative_value: Optional[Parameter] = None) -> Parameter:
"""
Get a parameter or the alternative value.
If the alternative value is None, a default Parameter with the given name and NOT_SET
type will be returned if the parameter was not declared.
:param name: Fully-qualified name of the parameter, including its namespace.
:param alternative_value: Alternative parameter to get if it had not been declared before.
:return: Requested parameter, or alternative value if it hadn't been declared before or is
an uninitialized statically typed parameter.
"""
if alternative_value is None:
alternative_value = Parameter(name, Parameter.Type.NOT_SET)
if not self.has_parameter(name):
return alternative_value
# Return alternative for uninitialized parameters
if (self._parameters[name].type_ == Parameter.Type.NOT_SET):
return alternative_value
return self._parameters[name]
def get_parameters_by_prefix(self, prefix: str) -> Dict[str, Optional[Union[
bool, int, float, str, bytes,
Sequence[bool], Sequence[int], Sequence[float], Sequence[str]
]]]:
"""
Get parameters that have a given prefix in their names as a dictionary.
The names which are used as keys in the returned dictionary have the prefix removed.
For example, if you use the prefix "foo" and the parameters "foo.ping", "foo.pong"
and "bar.baz" exist, then the returned dictionary will have the keys "ping" and "pong".
Note that the parameter separator is also removed from the parameter name to create the
keys.
An empty string for the prefix will match all parameters.
If no parameters with the prefix are found, an empty dictionary will be returned.
:param prefix: The prefix of the parameters to get.
:return: Dict of parameters with the given prefix.
"""
if prefix:
prefix = prefix + PARAMETER_SEPARATOR_STRING
prefix_len = len(prefix)
return {
param_name[prefix_len:]: param_value
for param_name, param_value in self._parameters.items()
if param_name.startswith(prefix)
}
def set_parameters(self, parameter_list: List[Parameter]) -> List[SetParametersResult]:
"""
Set parameters for the node, and return the result for the set action.
If any parameter in the list was not declared beforehand and undeclared parameters are not
allowed for the node, this method will raise a ParameterNotDeclaredException exception.
Parameters are set in the order they are declared in the list.
If setting a parameter fails due to not being declared, then the
parameters which have already been set will stay set, and no attempt will
be made to set the parameters which come after.
If undeclared parameters are allowed, then all the parameters will be implicitly
declared before being set even if they were not declared beforehand.
Parameter overrides are ignored by this method.
This method will result in any callback registered with
:func:`add_pre_set_parameters_callback`, :func:`add_on_set_parameters_callback` and
:func:`add_post_set_parameters_callback` to be called once for each parameter.
If a callback was registered previously with :func:`add_pre_set_parameters_callback`, it
will be called prior to the validation of parameters for the node, once for each parameter.
If this callback makes modified parameter list empty, then it will be reflected in the
returned result; no exceptions will be raised in this case.
If a callback was registered previously with :func:`add_on_set_parameters_callback`, it
will be called prior to setting the parameters for the node, once for each parameter.
If this callback prevents a parameter from being set, then it will be reflected in the
returned result; no exceptions will be raised in this case.
If a callback was registered previously with :func:`add_post_set_parameters_callback`,
it will be called after setting the parameters successfully for the node,
once for each parameter.
For each successfully set parameter, a :class:`ParameterEvent` message is
published.
If the value type of the parameter is NOT_SET, and the existing parameter type is
something else, then the parameter will be implicitly undeclared.
:param parameter_list: The list of parameters to set.
:return: The result for each set action as a list.
:raises: ParameterNotDeclaredException if undeclared parameters are not allowed,
and at least one parameter in the list hadn't been declared beforehand.
"""
results = []
for param in parameter_list:
result = self._set_parameters_atomically([param])
results.append(result)
return results
def set_parameters_atomically(self, parameter_list: List[Parameter]) -> SetParametersResult:
"""
Set the given parameters, all at one time, and then aggregate result.
If any parameter in the list was not declared beforehand and undeclared parameters are not
allowed for the node, this method will raise a ParameterNotDeclaredException exception.
Parameters are set all at once.
If setting a parameter fails due to not being declared, then no parameter will be set.
Either all of the parameters are set or none of them are set.
If undeclared parameters are allowed for the node, then all the parameters will be
implicitly declared before being set even if they were not declared beforehand.
This method will result in any callback registered with
:func:`add_pre_set_parameters_callback` :func:`add_on_set_parameters_callback` and
:func:`add_post_set_parameters_callback` to be called only once for all parameters.
If a callback was registered previously with :func:`add_pre_set_parameters_callback`, it
will be called prior to the validation of node parameters only once for all parameters.
If this callback makes modified parameter list empty, then it will be reflected in the
returned result; no exceptions will be raised in this case.
If a callback was registered previously with :func:`add_on_set_parameters_callback`, it
will be called prior to setting the parameters for the node only once for all parameters.
If the callback prevents the parameters from being set, then it will be reflected in the
returned result; no exceptions will be raised in this case.
If a callback was registered previously with :func:`add_post_set_parameters_callback`, it
will be called after setting the node parameters successfully only once for all parameters.
For each successfully set parameter, a :class:`ParameterEvent` message is published.
If the value type of the parameter is NOT_SET, and the existing parameter type is
something else, then the parameter will be implicitly undeclared.
:param parameter_list: The list of parameters to set.
:return: Aggregate result of setting all the parameters atomically.
:raises: ParameterNotDeclaredException if undeclared parameters are not allowed,
and at least one parameter in the list hadn't been declared beforehand.
"""
return self._set_parameters_atomically(parameter_list)
def _set_parameters_atomically(
self,
parameter_list: List[Parameter],
) -> SetParametersResult:
modified_parameter_list = self._call_pre_set_parameters_callback(parameter_list)
if modified_parameter_list is not None:
parameter_list = modified_parameter_list
if len(parameter_list) == 0:
result = SetParametersResult()
result.successful = False
result.reason = 'parameter list cannot be empty, this might be due to ' \
'pre_set_parameters_callback modifying the original parameters ' \
'list.'
return result
self._check_undeclared_parameters(parameter_list)
return self._set_parameters_atomically_common(parameter_list)
def _set_parameters_atomically_common(
self,
parameter_list: List[Parameter],
descriptors: Optional[Dict[str, ParameterDescriptor]] = None,
allow_not_set_type: bool = False
) -> SetParametersResult:
"""
Set the given parameters, all at one time, and then aggregate result.
This internal method does not reject undeclared parameters.
If :param:`allow_not_set_type` is False, a parameter with type NOT_SET will be undeclared.
This method will result in any callback registered with
:func:`add_on_set_parameters_callback` and :func:`add_post_set_parameters_callback`
to be called only once for all parameters.
If a callback was registered previously with :func:`add_on_set_parameters_callback`, it
will be called prior to setting the parameters for the node only once for all parameters.
If the callback prevents the parameters from being set, then it will be reflected in the
returned result; no exceptions will be raised in this case.
If a callback was registered previously with :func:`add_post_set_parameters_callback`,
it will be called after setting the node parameters successfully only once for all
parameters.
For each successfully set parameter, a :class:`ParameterEvent` message is
published.
:param parameter_list: The list of parameters to set.
:param descriptors: New descriptors to apply to the parameters before setting them.
If descriptors are given, each parameter in the list must have a corresponding one.
:param allow_not_set_type: False if parameters with NOT_SET type shall be undeclared,
True if they should be stored despite not having an actual value.
:return: Aggregate result of setting all the parameters atomically.
"""
if descriptors is not None:
# If new descriptors are provided, ensure every parameter has an assigned descriptor
# and do not check for read-only.
assert all(parameter.name in descriptors for parameter in parameter_list)
result = self._apply_descriptors(parameter_list, descriptors, False)
else:
# If new descriptors are not provided, use existing ones and check for read-only.
result = self._apply_descriptors(parameter_list, self._descriptors, True)
if not result.successful:
return result
elif self._on_set_parameters_callbacks:
for callback in self._on_set_parameters_callbacks:
result = callback(parameter_list)
if not result.successful:
return result
result = SetParametersResult(successful=True)
if result.successful:
parameter_event = ParameterEvent()
# Add fully qualified path of node to parameter event
if self.get_namespace() == '/':
parameter_event.node = self.get_namespace() + self.get_name()
else:
parameter_event.node = self.get_namespace() + '/' + self.get_name()
for param in parameter_list:
# If parameters without type and value are not allowed, they shall be undeclared.
if not allow_not_set_type and Parameter.Type.NOT_SET == param.type_:
# Parameter deleted. (Parameter had value and new value is not set).
parameter_event.deleted_parameters.append(param.to_parameter_msg())
# Delete any unset parameters regardless of their previous value.
if param.name in self._parameters:
del self._parameters[param.name]
if param.name in self._descriptors:
del self._descriptors[param.name]
else:
# Update descriptors; set a default if it doesn't exist.
# Don't update if it already exists for the current parameter and a new one
# was not specified in this method call.
if descriptors is not None:
self._descriptors[param.name] = descriptors[param.name]
elif param.name not in self._descriptors:
descriptor = ParameterDescriptor()
descriptor.dynamic_typing = True
self._descriptors[param.name] = descriptor
if Parameter.Type.NOT_SET == self.get_parameter_or(param.name).type_:
# Parameter is new. (Parameter had no value and new value is set)
parameter_event.new_parameters.append(param.to_parameter_msg())
else:
parameter_event.changed_parameters.append(
param.to_parameter_msg())
# Descriptors have already been applied by this point.
self._parameters[param.name] = param
parameter_event.stamp = self._clock.now().to_msg()
self._parameter_event_publisher.publish(parameter_event)
# call post set parameter registered callbacks
self._call_post_set_parameters_callback(parameter_list)
return result
def _check_undeclared_parameters(self, parameter_list: List[Parameter]):
"""
Check if parameter list has correct types and was declared beforehand.
:raises: ParameterNotDeclaredException if at least one parameter in the list was not
declared beforehand.
"""
if not all(isinstance(parameter, Parameter) for parameter in parameter_list):
raise TypeError("parameter must be instance of type '{}'".format(repr(Parameter)))
undeclared_parameters = (
param.name for param in parameter_list if param.name not in self._parameters
)
if not self._allow_undeclared_parameters and any(undeclared_parameters):
raise ParameterNotDeclaredException(list(undeclared_parameters))
def _call_pre_set_parameters_callback(self, parameter_list: [List[Parameter]]):
if self._pre_set_parameters_callbacks:
modified_parameter_list = []
for callback in self._pre_set_parameters_callbacks:
modified_parameter_list.extend(callback(parameter_list))
return modified_parameter_list
else:
return None
def _call_post_set_parameters_callback(self, parameter_list: [List[Parameter]]):
if self._post_set_parameters_callbacks:
for callback in self._post_set_parameters_callbacks:
callback(parameter_list)
def add_pre_set_parameters_callback(
self,
callback: Callable[[List[Parameter]], List[Parameter]]
) -> None:
"""
Add a callback gets triggered before parameters are validated.
Calling this function will add a callback in self._pre_set_parameter_callbacks list.
This callback can be used to modify the original list of parameters being
set by the user. The modified list of parameters is then forwarded to the