|
| 1 | +# Copyright 2020 Open Source Robotics Foundation, Inc. |
| 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 typing import Callable |
| 16 | +from typing import Iterable |
| 17 | +from typing import Optional |
| 18 | +from typing import Text |
| 19 | +from typing import Type |
| 20 | +from typing import TYPE_CHECKING |
| 21 | +from typing import Union |
| 22 | + |
| 23 | +from rcl_interfaces.msg import ParameterDescriptor |
| 24 | +from rcl_interfaces.msg import SetParametersResult |
| 25 | + |
| 26 | +import rclpy |
| 27 | +from rclpy.duration import Duration |
| 28 | +from rclpy.exceptions import ParameterAlreadyDeclaredException |
| 29 | +from rclpy.parameter import Parameter |
| 30 | +from rclpy.publisher import Publisher |
| 31 | +from rclpy.qos import QoSPolicyKind |
| 32 | +from rclpy.qos import QoSProfile |
| 33 | +from rclpy.subscription import Subscription |
| 34 | + |
| 35 | +if TYPE_CHECKING: |
| 36 | + from rclpy.node import Node |
| 37 | + |
| 38 | + |
| 39 | +class InvalidQosOverridesError(Exception): |
| 40 | + pass |
| 41 | + |
| 42 | + |
| 43 | +# Return type of qos validation callbacks |
| 44 | +QosCallbackResult = SetParametersResult |
| 45 | +# Qos callback type annotation |
| 46 | +QosCallbackType = Callable[[QoSProfile], QosCallbackResult] |
| 47 | + |
| 48 | + |
| 49 | +class QoSOverridingOptions: |
| 50 | + """Options to customize QoS parameter overrides.""" |
| 51 | + |
| 52 | + def __init__( |
| 53 | + self, |
| 54 | + policy_kinds: Iterable[QoSPolicyKind], |
| 55 | + *, |
| 56 | + callback: Optional[QosCallbackType] = None, |
| 57 | + entity_id: Optional[Text] = None |
| 58 | + ): |
| 59 | + """ |
| 60 | + Construct a QoSOverridingOptions object. |
| 61 | +
|
| 62 | + :param policy_kinds: QoS kinds that will have a declared parameter. |
| 63 | + :param callback: Callback that will be used to validate the QoS profile |
| 64 | + after the paramter overrides get applied. |
| 65 | + :param entity_id: Optional identifier, to disambiguate in the case that different QoS |
| 66 | + policies for the same topic are desired. |
| 67 | + """ |
| 68 | + self._policy_kinds = policy_kinds |
| 69 | + self._callback = callback |
| 70 | + self._entity_id = entity_id |
| 71 | + |
| 72 | + @property |
| 73 | + def policy_kinds(self) -> Iterable[QoSPolicyKind]: |
| 74 | + """Get QoS policy kinds that will have a parameter override.""" |
| 75 | + return self._policy_kinds |
| 76 | + |
| 77 | + @property |
| 78 | + def callback(self) -> Optional[QosCallbackType]: |
| 79 | + """Get the validation callback.""" |
| 80 | + return self._callback |
| 81 | + |
| 82 | + @property |
| 83 | + def entity_id(self) -> Optional[Text]: |
| 84 | + """Get the optional entity ID.""" |
| 85 | + return self._entity_id |
| 86 | + |
| 87 | + @classmethod |
| 88 | + def with_default_policies( |
| 89 | + cls, *, |
| 90 | + callback: Optional[QosCallbackType] = None, |
| 91 | + entity_id: Optional[Text] = None |
| 92 | + ) -> 'QoSOverridingOptions': |
| 93 | + return cls( |
| 94 | + policy_kinds=(QoSPolicyKind.HISTORY, QoSPolicyKind.DEPTH, QoSPolicyKind.RELIABILITY), |
| 95 | + callback=callback, |
| 96 | + entity_id=entity_id, |
| 97 | + ) |
| 98 | + |
| 99 | + |
| 100 | +def _declare_qos_parameters( |
| 101 | + entity_type: Union[Type[Publisher], Type[Subscription]], |
| 102 | + node: 'Node', |
| 103 | + topic_name: Text, |
| 104 | + qos: QoSProfile, |
| 105 | + options: QoSOverridingOptions |
| 106 | +) -> QoSProfile: |
| 107 | + """ |
| 108 | + Declare QoS parameters for a Publisher or a Subscription. |
| 109 | +
|
| 110 | + :param entity_type: Either `rclpy.node.Publisher` or `rclpy.node.Subscription`. |
| 111 | + :param node: Node used to declare the parameters. |
| 112 | + :param topic_name: Topic name of the entity being created. |
| 113 | + :param qos: Default QoS settings of the entity being created, that will be overridden |
| 114 | + with the user provided QoS parameter overrides. |
| 115 | + :param options: Options that indicates which parameters are going to be declared. |
| 116 | + """ |
| 117 | + if not issubclass(entity_type, (Publisher, Subscription)): |
| 118 | + raise TypeError('Argument `entity_type` should be a subclass of Publisher or Subscription') |
| 119 | + entity_type_str = 'publisher' if issubclass(entity_type, Publisher) else 'subscription' |
| 120 | + id_suffix = '' if options.entity_id is None else f'_{options.entity_id}' |
| 121 | + name = f'qos_overrides.{topic_name}.{entity_type_str}{id_suffix}.' '{}' |
| 122 | + description = '{}' f' for {entity_type_str} `{topic_name}` with id `{options.entity_id}`' |
| 123 | + allowed_policies = _get_allowed_policies(entity_type) |
| 124 | + for policy in options.policy_kinds: |
| 125 | + if policy not in allowed_policies: |
| 126 | + continue |
| 127 | + policy_name = policy.name.lower() |
| 128 | + descriptor = ParameterDescriptor() |
| 129 | + descriptor.description = description.format(policy_name) |
| 130 | + descriptor.read_only = True |
| 131 | + try: |
| 132 | + param = node.declare_parameter( |
| 133 | + name.format(policy_name), |
| 134 | + _get_qos_policy_parameter(qos, policy), |
| 135 | + descriptor) |
| 136 | + except ParameterAlreadyDeclaredException: |
| 137 | + param = node.get_parameter(name.format(policy_name)) |
| 138 | + _override_qos_policy_with_param(qos, policy, param) |
| 139 | + if options.callback is not None: |
| 140 | + result = options.callback(qos) |
| 141 | + if not result.successful: |
| 142 | + raise InvalidQosOverridesError( |
| 143 | + f"{description.format('Provided QoS overrides')}, are not valid: {result.reason}") |
| 144 | + |
| 145 | + |
| 146 | +def _get_allowed_policies(entity_type: Union[Type[Publisher], Type[Subscription]]): |
| 147 | + allowed_policies = list(QoSPolicyKind.__members__.values()) |
| 148 | + if issubclass(entity_type, Subscription): |
| 149 | + allowed_policies.remove(QoSPolicyKind.LIFESPAN) |
| 150 | + return allowed_policies |
| 151 | + |
| 152 | + |
| 153 | +def _get_qos_policy_parameter(qos: QoSProfile, policy: QoSPolicyKind) -> Union[str, int, bool]: |
| 154 | + value = getattr(qos, policy.name.lower()) |
| 155 | + if policy in ( |
| 156 | + QoSPolicyKind.LIVELINESS, QoSPolicyKind.RELIABILITY, |
| 157 | + QoSPolicyKind.HISTORY, QoSPolicyKind.DURABILITY |
| 158 | + ): |
| 159 | + value = value.name.lower() |
| 160 | + if value == 'unknown': |
| 161 | + raise ValueError('User provided QoS profile is invalid') |
| 162 | + if policy in ( |
| 163 | + QoSPolicyKind.LIFESPAN, QoSPolicyKind.DEADLINE, QoSPolicyKind.LIVELINESS_LEASE_DURATION |
| 164 | + ): |
| 165 | + value = value.nanoseconds() |
| 166 | + return value |
| 167 | + |
| 168 | + |
| 169 | +def _override_qos_policy_with_param(qos: QoSProfile, policy: QoSPolicyKind, param: Parameter): |
| 170 | + value = param.value |
| 171 | + policy_name = policy.name.lower() |
| 172 | + if policy in ( |
| 173 | + QoSPolicyKind.LIVELINESS, QoSPolicyKind.RELIABILITY, |
| 174 | + QoSPolicyKind.HISTORY, QoSPolicyKind.DURABILITY |
| 175 | + ): |
| 176 | + def capitalize_first_letter(x): |
| 177 | + return x[0].upper() + x[1:] |
| 178 | + # e.g. `policy=QosPolicyKind.LIVELINESS` -> `policy_enum_class=rclpy.qos.LivelinessPolicy` |
| 179 | + policy_enum_class = getattr( |
| 180 | + rclpy.qos, f'{capitalize_first_letter(policy_name)}Policy') |
| 181 | + try: |
| 182 | + value = policy_enum_class[value.upper()] |
| 183 | + except KeyError: |
| 184 | + raise RuntimeError( |
| 185 | + f'Unexpected QoS override for policy `{policy.name.lower()}`: `{value}`') |
| 186 | + if policy in ( |
| 187 | + QoSPolicyKind.LIFESPAN, QoSPolicyKind.DEADLINE, QoSPolicyKind.LIVELINESS_LEASE_DURATION |
| 188 | + ): |
| 189 | + value = Duration(nanoseconds=value) |
| 190 | + setattr(qos, policy.name.lower(), value) |
0 commit comments