diff --git a/rclpy/rclpy/parameter_service.py b/rclpy/rclpy/parameter_service.py index 70830facf..6a8803fef 100644 --- a/rclpy/rclpy/parameter_service.py +++ b/rclpy/rclpy/parameter_service.py @@ -12,6 +12,8 @@ # See the License for the specific language governing permissions and # limitations under the License. + +from typing import TYPE_CHECKING import weakref from rcl_interfaces.msg import ListParametersResult @@ -23,10 +25,13 @@ from rclpy.qos import qos_profile_parameters from rclpy.validate_topic_name import TOPIC_SEPARATOR_STRING +if TYPE_CHECKING: + from rclpy.node import Node + class ParameterService: - def __init__(self, node): + def __init__(self, node: 'Node'): self._node_weak_ref = weakref.ref(node) nodename = node.get_name() @@ -65,7 +70,11 @@ def __init__(self, node): qos_profile=qos_profile_parameters ) - def _describe_parameters_callback(self, request, response): + def _describe_parameters_callback( + self, + request: DescribeParameters.Request, + response: DescribeParameters.Response + ) -> DescribeParameters.Response: node = self._get_node() for name in request.names: try: @@ -76,7 +85,11 @@ def _describe_parameters_callback(self, request, response): response.descriptors.append(descriptor) return response - def _get_parameters_callback(self, request, response): + def _get_parameters_callback( + self, + request: GetParameters.Request, + response: GetParameters.Response + ) -> GetParameters.Response: node = self._get_node() for name in request.names: try: @@ -87,7 +100,11 @@ def _get_parameters_callback(self, request, response): response.values.append(param.get_parameter_value()) return response - def _get_parameter_types_callback(self, request, response): + def _get_parameter_types_callback( + self, + request: GetParameterTypes.Request, + response: GetParameterTypes.Response + ) -> GetParameterTypes.Response: node = self._get_node() for name in request.names: try: @@ -98,7 +115,11 @@ def _get_parameter_types_callback(self, request, response): response.types.append(value) return response - def _list_parameters_callback(self, request, response): + def _list_parameters_callback( + self, + request: ListParameters.Response, + response: ListParameters.Response + ) -> ListParameters.Response: node = self._get_node() try: response.result = node.list_parameters(request.prefixes, request.depth) @@ -106,7 +127,11 @@ def _list_parameters_callback(self, request, response): response.result = ListParametersResult() return response - def _set_parameters_callback(self, request, response): + def _set_parameters_callback( + self, + request: SetParameters.Request, + response: SetParameters.Response + ) -> SetParameters.Response: node = self._get_node() for p in request.parameters: param = Parameter.from_parameter_msg(p) @@ -120,7 +145,11 @@ def _set_parameters_callback(self, request, response): response.results.append(result) return response - def _set_parameters_atomically_callback(self, request, response): + def _set_parameters_atomically_callback( + self, + request: SetParametersAtomically.Request, + response: SetParametersAtomically.Response + ) -> SetParametersAtomically.Response: node = self._get_node() try: response.result = node.set_parameters_atomically([ @@ -132,7 +161,7 @@ def _set_parameters_atomically_callback(self, request, response): ) return response - def _get_node(self): + def _get_node(self) -> 'Node': node = self._node_weak_ref() if node is None: raise ReferenceError('Expected valid node weak reference')