Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add types to parameter_client.py #1348

Merged
merged 3 commits into from
Sep 3, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
43 changes: 24 additions & 19 deletions rclpy/rclpy/parameter_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
from rclpy.qos import qos_profile_services_default
from rclpy.qos import QoSProfile
from rclpy.qos_overriding_options import QoSOverridingOptions
from rclpy.subscription import MessageInfo
from rclpy.subscription import Subscription
from rclpy.task import Future

Expand Down Expand Up @@ -136,8 +137,8 @@ def list_parameters(
self,
prefixes: Optional[List[str]] = None,
depth: Optional[int] = None,
callback: Optional[Callable] = None
) -> Future:
callback: Optional[Callable[[ListParameters.Response], None]] = None
) -> Future[ListParameters.Response]:
"""
List all parameters with given prefixes.

Expand All @@ -156,7 +157,9 @@ def list_parameters(
future.add_done_callback(callback)
return future

def get_parameters(self, names: List[str], callback: Optional[Callable] = None) -> Future:
def get_parameters(self, names: List[str],
callback: Optional[Callable[[GetParameters.Response], None]] = None
) -> Future[GetParameters.Response]:
"""
Get parameters given names.

Expand All @@ -174,8 +177,8 @@ def get_parameters(self, names: List[str], callback: Optional[Callable] = None)
def set_parameters(
self,
parameters: Sequence[Union[Parameter, ParameterMsg]],
callback: Optional[Callable] = None
) -> Future:
callback: Optional[Callable[[SetParameters.Response], None]] = None
) -> Future[SetParameters.Response]:
"""
Set parameters given a list of parameters.

Expand All @@ -200,8 +203,8 @@ def set_parameters(
def describe_parameters(
self,
names: List[str],
callback: Optional[Callable] = None
) -> Future:
callback: Optional[Callable[[DescribeParameters.Response], None]] = None
) -> Future[DescribeParameters.Response]:
"""
Describe parameters given names.

Expand All @@ -222,8 +225,8 @@ def describe_parameters(
def get_parameter_types(
self,
names: List[str],
callback: Optional[Callable] = None
) -> Future:
callback: Optional[Callable[[GetParameterTypes.Response], None]] = None
) -> Future[GetParameterTypes.Response]:
"""
Get parameter types given names.

Expand All @@ -246,8 +249,8 @@ def get_parameter_types(
def set_parameters_atomically(
self,
parameters: Sequence[Union[Parameter, ParameterMsg]],
callback: Optional[Callable] = None
) -> Future:
callback: Optional[Callable[[SetParametersAtomically.Response], None]] = None
) -> Future[SetParametersAtomically.Response]:
"""
Set parameters atomically.

Expand All @@ -270,8 +273,9 @@ def set_parameters_atomically(
return future

def delete_parameters(
self, names: List[str], callback: Optional[Callable] = None
) -> Future:
self, names: List[str],
callback: Optional[Callable[[SetParameters.Response], None]] = None
) -> Future[SetParameters.Response]:
"""
Unset parameters with given names.

Expand All @@ -295,8 +299,8 @@ def load_parameter_file(
self,
parameter_file: str,
use_wildcard: bool = False,
callback: Optional[Callable] = None
) -> Future:
callback: Optional[Callable[[SetParameters.Response], None]] = None
) -> Future[SetParameters.Response]:
"""
Load parameters from a yaml file.

Expand All @@ -317,8 +321,8 @@ def load_parameter_file_atomically(
self,
parameter_file: str,
use_wildcard: bool = False,
callback: Optional[Callable] = None
) -> Future:
callback: Optional[Callable[[SetParameters.Response], None]] = None
) -> Future[SetParameters.Response]:
"""
Load parameters from a yaml file atomically.

Expand All @@ -336,14 +340,15 @@ def load_parameter_file_atomically(
return future

def on_parameter_event(
self, callback: Callable,
self, callback: Union[Callable[[ParameterEvent], None],
Callable[[ParameterEvent, MessageInfo], None]],
qos_profile: QoSProfile = qos_profile_parameter_events,
*,
callback_group: Optional[CallbackGroup] = None,
event_callbacks: Optional[SubscriptionEventCallbacks] = None,
qos_overriding_options: Optional[QoSOverridingOptions] = None,
raw: bool = False
) -> Subscription:
) -> Subscription[ParameterEvent]:
return self.node.create_subscription(
ParameterEvent,
'/parameter_events',
Expand Down
37 changes: 19 additions & 18 deletions rclpy/test/test_parameter_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
import unittest

import rcl_interfaces.msg
from rcl_interfaces.msg import ParameterEvent
from rcl_interfaces.msg import ParameterType
import rcl_interfaces.srv
import rclpy
Expand All @@ -28,7 +29,7 @@

class TestParameterClient(unittest.TestCase):

def setUp(self):
def setUp(self) -> None:
self.context = rclpy.context.Context()
rclpy.init(context=self.context)
self.client_node = rclpy.create_node(
Expand All @@ -48,13 +49,13 @@ def setUp(self):
self.executor.add_node(self.client_node)
self.executor.add_node(self.target_node)

def tearDown(self):
def tearDown(self) -> None:
self.executor.shutdown()
self.client_node.destroy_node()
self.target_node.destroy_node()
rclpy.shutdown(context=self.context)

def test_set_parameter(self):
def test_set_parameter(self) -> None:
future = self.client.set_parameters([
Parameter('int_param', Parameter.Type.INTEGER, 88).to_parameter_msg(),
Parameter('string.param', Parameter.Type.STRING, 'hello world'),
Expand All @@ -66,7 +67,7 @@ def test_set_parameter(self):
res = [i.successful for i in results.results]
assert all(res)

def test_get_parameter(self):
def test_get_parameter(self) -> None:
future = self.client.get_parameters(['int_arr_param', 'float.param..'])
self.executor.spin_until_future_complete(future)
results = future.result()
Expand All @@ -75,7 +76,7 @@ def test_get_parameter(self):
assert list(results.values[0].integer_array_value) == [1, 2, 3]
assert results.values[1].double_value == 3.14

def test_list_parameters(self):
def test_list_parameters(self) -> None:
future = self.client.list_parameters()
self.executor.spin_until_future_complete(future)
results = future.result()
Expand All @@ -91,7 +92,7 @@ def test_list_parameters(self):
assert 'float.param..' in results.result.names
assert 'float.param.' in results.result.prefixes

def test_describe_parameters(self):
def test_describe_parameters(self) -> None:
future = self.client.describe_parameters(['int_arr_param'])
self.executor.spin_until_future_complete(future)
results = future.result()
Expand All @@ -100,15 +101,15 @@ def test_describe_parameters(self):
assert results.descriptors[0].type == ParameterType.PARAMETER_INTEGER_ARRAY
assert results.descriptors[0].name == 'int_arr_param'

def test_get_paramter_types(self):
def test_get_paramter_types(self) -> None:
future = self.client.get_parameter_types(['int_arr_param'])
self.executor.spin_until_future_complete(future)
results = future.result()
assert results is not None
assert len(results.types) == 1
assert results.types[0] == ParameterType.PARAMETER_INTEGER_ARRAY

def test_set_parameters_atomically(self):
def test_set_parameters_atomically(self) -> None:
future = self.client.set_parameters_atomically([
Parameter('int_param', Parameter.Type.INTEGER, 888),
Parameter('string.param', Parameter.Type.STRING, 'Hello World').to_parameter_msg(),
Expand All @@ -118,7 +119,7 @@ def test_set_parameters_atomically(self):
assert results is not None
assert results.result.successful

def test_delete_parameters(self):
def test_delete_parameters(self) -> None:
self.target_node.declare_parameter('delete_param', 10)
descriptor = rcl_interfaces.msg.ParameterDescriptor(dynamic_typing=True)
self.target_node.declare_parameter('delete_param_dynamic', 10, descriptor=descriptor)
Expand All @@ -138,7 +139,7 @@ def test_delete_parameters(self):
assert len(result.results) == 1
assert result.results[0].successful

def test_load_parameter_file(self):
def test_load_parameter_file(self) -> None:
yaml_string = """/param_test_target:
ros__parameters:
param_1: 1
Expand All @@ -159,7 +160,7 @@ def test_load_parameter_file(self):
if os.path.exists(f.name):
os.unlink(f.name)

def test_load_parameter_file_atomically(self):
def test_load_parameter_file_atomically(self) -> None:
yaml_string = """/param_test_target:
ros__parameters:
param_1: 1
Expand All @@ -179,7 +180,7 @@ def test_load_parameter_file_atomically(self):
if os.path.exists(f.name):
os.unlink(f.name)

def test_get_uninitialized_parameter(self):
def test_get_uninitialized_parameter(self) -> None:
self.target_node.declare_parameter('uninitialized_parameter', Parameter.Type.STRING)

# The type in description should be STRING
Expand All @@ -200,8 +201,8 @@ def test_get_uninitialized_parameter(self):

self.target_node.undeclare_parameter('uninitialized_parameter')

def test_on_parameter_event_new(self):
def on_new_parameter_event(msg):
def test_on_parameter_event_new(self) -> None:
def on_new_parameter_event(msg: ParameterEvent) -> None:
assert msg.node == '/rclpy/test_parameter_client_target'
assert len(msg.new_parameters) == 1
assert msg.new_parameters[0].name == 'int_param'
Expand All @@ -223,7 +224,7 @@ def on_new_parameter_event(msg):

param_event_sub.destroy()

def test_on_parameter_event_changed(self):
def test_on_parameter_event_changed(self) -> None:
future = self.client.set_parameters([
Parameter('int_param', Parameter.Type.INTEGER, 88).to_parameter_msg(),
])
Expand All @@ -234,7 +235,7 @@ def test_on_parameter_event_changed(self):
res = [i.successful for i in results.results]
assert all(res)

def on_changed_parameter_event(msg):
def on_changed_parameter_event(msg: ParameterEvent) -> None:
assert msg.node == '/rclpy/test_parameter_client_target'
assert len(msg.new_parameters) == 0
assert len(msg.changed_parameters) == 1
Expand All @@ -256,7 +257,7 @@ def on_changed_parameter_event(msg):

param_event_sub.destroy()

def test_on_parameter_event_deleted(self):
def test_on_parameter_event_deleted(self) -> None:
future = self.client.set_parameters([
Parameter('int_param', Parameter.Type.INTEGER, 88).to_parameter_msg(),
])
Expand All @@ -267,7 +268,7 @@ def test_on_parameter_event_deleted(self):
res = [i.successful for i in results.results]
assert all(res)

def on_deleted_parameter_event(msg):
def on_deleted_parameter_event(msg: ParameterEvent) -> None:
assert msg.node == '/rclpy/test_parameter_client_target'
assert len(msg.new_parameters) == 0
assert len(msg.changed_parameters) == 0
Expand Down