Skip to content

Commit 50c284a

Browse files
Add More Test Typings (#1472)
Signed-off-by: Michael Carlstrom <[email protected]>
1 parent 0fbd01a commit 50c284a

32 files changed

+296
-150
lines changed

rclpy/rclpy/__init__.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@
5555
from rclpy.signals import install_signal_handlers
5656
from rclpy.signals import SignalHandlerOptions
5757
from rclpy.signals import uninstall_signal_handlers
58-
from rclpy.task import Future
58+
from rclpy.task import Future as Future
5959
from rclpy.utilities import get_default_context as get_default_context
6060
from rclpy.utilities import get_rmw_implementation_identifier # noqa: F401
6161
from rclpy.utilities import ok as ok # noqa: F401 forwarding to this module
@@ -64,8 +64,8 @@
6464

6565
# Avoid loading extensions on module import
6666
if TYPE_CHECKING:
67-
from rclpy.executors import Executor # noqa: F401
68-
from rclpy.node import Node # noqa: F401
67+
from rclpy.executors import Executor
68+
from rclpy.node import Node
6969

7070

7171
class InitContextManager:

rclpy/rclpy/executors.py

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,9 @@
5353
from rclpy.subscription import Subscription
5454
from rclpy.task import Future
5555
from rclpy.task import Task
56-
from rclpy.timer import Timer, TimerInfo
56+
from rclpy.timer import Timer
57+
from rclpy.timer import TimerCallbackType
58+
from rclpy.timer import TimerInfo
5759
from rclpy.type_support import Msg
5860
from rclpy.utilities import get_default_context
5961
from rclpy.utilities import timeout_sec_to_nsec
@@ -431,8 +433,7 @@ def _take_timer(self, tmr: Timer) -> Optional[Callable[[], Coroutine[None, None,
431433
actual_call_time=info['actual_call_time'],
432434
clock_type=tmr.clock.clock_type)
433435

434-
def check_argument_type(callback_func: Union[Callable[[], None],
435-
Callable[[TimerInfo], None]],
436+
def check_argument_type(callback_func: TimerCallbackType,
436437
target_type: Type[TimerInfo]) -> Optional[str]:
437438
sig = inspect.signature(callback_func)
438439
for param in sig.parameters.values():

rclpy/rclpy/experimental/__init__.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,4 +12,4 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15-
from .events_executor import EventsExecutor # noqa: F401
15+
from .events_executor import EventsExecutor as EventsExecutor # noqa: F401

rclpy/rclpy/logging.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@
1717
from typing import Union
1818

1919
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
20-
from rclpy.impl.logging_severity import LoggingSeverity
20+
from rclpy.impl.logging_severity import LoggingSeverity as LoggingSeverity
2121
from rclpy.impl.rcutils_logger import RcutilsLogger
2222

2323

rclpy/rclpy/node.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -320,7 +320,7 @@ def executor(self) -> Optional[Executor]:
320320
return None
321321

322322
@executor.setter
323-
def executor(self, new_executor: Executor) -> None:
323+
def executor(self, new_executor: Optional[Executor]) -> None:
324324
"""Set or change the executor the node belongs to."""
325325
current_executor = self.executor
326326
if current_executor == new_executor:
@@ -1826,7 +1826,7 @@ def create_service(
18261826
def create_timer(
18271827
self,
18281828
timer_period_sec: float,
1829-
callback: TimerCallbackType,
1829+
callback: Optional[TimerCallbackType],
18301830
callback_group: Optional[CallbackGroup] = None,
18311831
clock: Optional[Clock] = None,
18321832
autostart: bool = True,

rclpy/rclpy/timer.py

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -67,15 +67,14 @@ def actual_call_time(self) -> Time:
6767

6868
TimerCallbackType: TypeAlias = Union[Callable[[], None],
6969
Callable[[TimerInfo], None],
70-
Callable[[], Coroutine[None, None, None]],
71-
None]
70+
Callable[[], Coroutine[None, None, None]]]
7271

7372

7473
class Timer:
7574

7675
def __init__(
7776
self,
78-
callback: TimerCallbackType,
77+
callback: Optional[TimerCallbackType],
7978
callback_group: Optional[CallbackGroup],
8079
timer_period_ns: int,
8180
clock: Clock,

rclpy/test/test_callback_group.py

Lines changed: 18 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -20,11 +20,19 @@
2020
import rclpy
2121
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup
2222
from rclpy.callback_groups import ReentrantCallbackGroup
23+
from rclpy.client import Client
2324
import rclpy.context
2425
from rclpy.executors import MultiThreadedExecutor
26+
from rclpy.service import Service
2527
from rclpy.task import Future
2628
from test_msgs.msg import BasicTypes, Empty
2729

30+
from typing_extensions import TypeAlias
31+
32+
33+
GetParametersClient: TypeAlias = Client[GetParameters.Request, GetParameters.Response]
34+
GetParametersService: TypeAlias = Service[GetParameters.Request, GetParameters.Response]
35+
2836

2937
class TestCallbackGroup(unittest.TestCase):
3038

@@ -33,13 +41,13 @@ class TestCallbackGroup(unittest.TestCase):
3341
node: rclpy.node.Node
3442

3543
@classmethod
36-
def setUpClass(cls):
44+
def setUpClass(cls) -> None:
3745
cls.context = rclpy.context.Context()
3846
rclpy.init(context=cls.context)
3947
cls.node = rclpy.create_node('TestCallbackGroup', namespace='/rclpy', context=cls.context)
4048

4149
@classmethod
42-
def tearDownClass(cls):
50+
def tearDownClass(cls) -> None:
4351
cls.node.destroy_node()
4452
rclpy.shutdown(context=cls.context)
4553

@@ -71,15 +79,15 @@ def test_reentrant_group_not_blocking(self) -> None:
7179

7280
# This callback is used to check if a callback can be received while another
7381
# long running callback is being executed
74-
def short_callback(msg):
82+
def short_callback(msg: Empty) -> None:
7583
nonlocal got_short_callback
7684
# Set flag so signal that the callback has been received
7785
got_short_callback = True
7886

7987
# This callback is as a long running callback
8088
# It will be checking that the short callback can
8189
# run in parallel to this long running one
82-
def long_callback(msg):
90+
def long_callback(msg: Empty) -> None:
8391
nonlocal received_short_callback_in_long_callback
8492
nonlocal future_up
8593
nonlocal future_down
@@ -170,17 +178,19 @@ def test_create_subscription_with_group(self) -> None:
170178
self.assertTrue(group.has_entity(sub2))
171179

172180
def test_create_client_with_group(self) -> None:
173-
cli1 = self.node.create_client(GetParameters, 'get/parameters')
181+
cli1: GetParametersClient = self.node.create_client(GetParameters, 'get/parameters')
174182
group = ReentrantCallbackGroup()
175-
cli2 = self.node.create_client(GetParameters, 'get/parameters', callback_group=group)
183+
cli2: GetParametersClient = self.node.create_client(GetParameters, 'get/parameters',
184+
callback_group=group)
176185

177186
self.assertFalse(group.has_entity(cli1))
178187
self.assertTrue(group.has_entity(cli2))
179188

180189
def test_create_service_with_group(self) -> None:
181-
srv1 = self.node.create_service(GetParameters, 'get/parameters', lambda req, res: None)
190+
srv1: GetParametersService = self.node.create_service(GetParameters, 'get/parameters',
191+
lambda req, res: None)
182192
group = ReentrantCallbackGroup()
183-
srv2 = self.node.create_service(
193+
srv2: GetParametersService = self.node.create_service(
184194
GetParameters, 'get/parameters', lambda req, res: None, callback_group=group)
185195

186196
self.assertFalse(group.has_entity(srv1))

rclpy/test/test_client.py

Lines changed: 42 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -16,20 +16,35 @@
1616
import threading
1717
import time
1818
import traceback
19+
from typing import List
20+
from typing import Optional
21+
from typing import Tuple
1922
from typing import TYPE_CHECKING
2023
import unittest
2124

2225
from rcl_interfaces.srv import GetParameters
2326
import rclpy
27+
from rclpy.client import Client
2428
import rclpy.context
2529
import rclpy.executors
2630
import rclpy.node
31+
from rclpy.service import Service
2732
from rclpy.utilities import get_rmw_implementation_identifier
2833
from test_msgs.srv import Empty
2934

35+
from typing_extensions import TypeAlias
36+
3037
# TODO(sloretz) Reduce fudge once wait_for_service uses node graph events
3138
TIME_FUDGE = 0.3
3239

40+
ClientGetParameters: TypeAlias = Client[GetParameters.Request,
41+
GetParameters.Response]
42+
43+
ServiceGetParameters: TypeAlias = Service[GetParameters.Request,
44+
GetParameters.Response]
45+
46+
TestServiceName: TypeAlias = List[Tuple[str, Optional[str], Optional[List[str]], str]]
47+
3348

3449
class TestClient(unittest.TestCase):
3550

@@ -38,26 +53,26 @@ class TestClient(unittest.TestCase):
3853
node: rclpy.node.Node
3954

4055
@classmethod
41-
def setUpClass(cls):
56+
def setUpClass(cls) -> None:
4257
cls.context = rclpy.context.Context()
4358
rclpy.init(context=cls.context)
4459
cls.node = rclpy.create_node('TestClient', context=cls.context)
4560

4661
@classmethod
47-
def tearDownClass(cls):
62+
def tearDownClass(cls) -> None:
4863
cls.node.destroy_node()
4964
rclpy.shutdown(context=cls.context)
5065

5166
@classmethod
52-
def do_test_service_name(cls, test_service_name_list):
67+
def do_test_service_name(cls, test_service_name_list: TestServiceName) -> None:
5368
for service_name, ns, cli_args, target_service_name in test_service_name_list:
5469
node = rclpy.create_node(
5570
node_name='node_name',
5671
context=cls.context,
5772
namespace=ns,
5873
cli_args=cli_args,
5974
start_parameter_services=False)
60-
client = node.create_client(
75+
client: Client[Empty.Request, Empty.Response] = node.create_client(
6176
srv_type=Empty,
6277
srv_name=service_name
6378
)
@@ -81,7 +96,7 @@ def _spin_rclpy_node(
8196
# rclpy_node.destroy_node()
8297

8398
def test_wait_for_service_5sec(self) -> None:
84-
cli = self.node.create_client(GetParameters, 'get/parameters')
99+
cli: ClientGetParameters = self.node.create_client(GetParameters, 'get/parameters')
85100
try:
86101
start = time.monotonic()
87102
self.assertFalse(cli.wait_for_service(timeout_sec=5.0))
@@ -92,7 +107,7 @@ def test_wait_for_service_5sec(self) -> None:
92107
self.node.destroy_client(cli)
93108

94109
def test_wait_for_service_nowait(self) -> None:
95-
cli = self.node.create_client(GetParameters, 'get/parameters')
110+
cli: ClientGetParameters = self.node.create_client(GetParameters, 'get/parameters')
96111
try:
97112
start = time.monotonic()
98113
self.assertFalse(cli.wait_for_service(timeout_sec=0))
@@ -103,9 +118,9 @@ def test_wait_for_service_nowait(self) -> None:
103118
self.node.destroy_client(cli)
104119

105120
def test_wait_for_service_exists(self) -> None:
106-
cli = self.node.create_client(GetParameters, 'test_wfs_exists')
107-
srv = self.node.create_service(GetParameters, 'test_wfs_exists',
108-
lambda request, response: None)
121+
cli: ClientGetParameters = self.node.create_client(GetParameters, 'test_wfs_exists')
122+
srv: ServiceGetParameters = self.node.create_service(GetParameters, 'test_wfs_exists',
123+
lambda request, response: None)
109124
try:
110125
start = time.monotonic()
111126
self.assertTrue(cli.wait_for_service(timeout_sec=1.0))
@@ -117,8 +132,8 @@ def test_wait_for_service_exists(self) -> None:
117132
self.node.destroy_service(srv)
118133

119134
def test_concurrent_calls_to_service(self) -> None:
120-
cli = self.node.create_client(GetParameters, 'get/parameters')
121-
srv = self.node.create_service(
135+
cli: ClientGetParameters = self.node.create_client(GetParameters, 'get/parameters')
136+
srv: ServiceGetParameters = self.node.create_service(
122137
GetParameters, 'get/parameters',
123138
lambda request, response: response)
124139
try:
@@ -138,8 +153,8 @@ def test_concurrent_calls_to_service(self) -> None:
138153
get_rmw_implementation_identifier() == 'rmw_connextdds' and platform.system() == 'Windows',
139154
reason='Source timestamp not implemented for Connext on Windows')
140155
def test_service_timestamps(self) -> None:
141-
cli = self.node.create_client(GetParameters, 'get/parameters')
142-
srv = self.node.create_service(
156+
cli: ClientGetParameters = self.node.create_client(GetParameters, 'get/parameters')
157+
srv: ServiceGetParameters = self.node.create_service(
143158
GetParameters, 'get/parameters',
144159
lambda request, response: response)
145160
try:
@@ -150,6 +165,7 @@ def test_service_timestamps(self) -> None:
150165
result = srv.handle.service_take_request(srv.srv_type.Request)
151166
if result != (None, None):
152167
request, header = result
168+
assert header is not None
153169
self.assertTrue(header is not None)
154170
self.assertNotEqual(0, header.source_timestamp)
155171
return
@@ -161,8 +177,8 @@ def test_service_timestamps(self) -> None:
161177
self.node.destroy_service(srv)
162178

163179
def test_different_type_raises(self) -> None:
164-
cli = self.node.create_client(GetParameters, 'get/parameters')
165-
srv = self.node.create_service(
180+
cli: ClientGetParameters = self.node.create_client(GetParameters, 'get/parameters')
181+
srv: ServiceGetParameters = self.node.create_service(
166182
GetParameters, 'get/parameters',
167183
lambda request, response: 'different response type')
168184
try:
@@ -180,7 +196,7 @@ def test_different_type_raises(self) -> None:
180196
self.node.destroy_service(srv)
181197

182198
def test_get_service_name(self) -> None:
183-
test_service_name_list = [
199+
test_service_name_list: TestServiceName = [
184200
# test_service_name, namespace, cli_args for remap, expected service name
185201
# No namespaces
186202
('service', None, None, '/service'),
@@ -197,7 +213,7 @@ def test_get_service_name(self) -> None:
197213
TestClient.do_test_service_name(test_service_name_list)
198214

199215
def test_get_service_name_after_remapping(self) -> None:
200-
test_service_name_list = [
216+
test_service_name_list: TestServiceName = [
201217
('service', None, ['--ros-args', '--remap', 'service:=new_service'], '/new_service'),
202218
('service', 'ns', ['--ros-args', '--remap', 'service:=new_service'],
203219
'/ns/new_service'),
@@ -209,9 +225,10 @@ def test_get_service_name_after_remapping(self) -> None:
209225
TestClient.do_test_service_name(test_service_name_list)
210226

211227
def test_sync_call(self) -> None:
212-
def _service(request, response):
228+
def _service(request: GetParameters.Request,
229+
response: GetParameters.Response) -> GetParameters.Response:
213230
return response
214-
cli = self.node.create_client(GetParameters, 'get/parameters')
231+
cli: ClientGetParameters = self.node.create_client(GetParameters, 'get/parameters')
215232
srv = self.node.create_service(GetParameters, 'get/parameters', _service)
216233
try:
217234
self.assertTrue(cli.wait_for_service(timeout_sec=20))
@@ -231,10 +248,11 @@ def _service(request, response):
231248
self.node.destroy_service(srv)
232249

233250
def test_sync_call_timeout(self) -> None:
234-
def _service(request, response):
251+
def _service(request: GetParameters.Request,
252+
response: GetParameters.Response) -> GetParameters.Response:
235253
time.sleep(1)
236254
return response
237-
cli = self.node.create_client(GetParameters, 'get/parameters')
255+
cli: ClientGetParameters = self.node.create_client(GetParameters, 'get/parameters')
238256
srv = self.node.create_service(GetParameters, 'get/parameters', _service)
239257
try:
240258
self.assertTrue(cli.wait_for_service(timeout_sec=20))
@@ -254,8 +272,10 @@ def _service(request, response):
254272
self.node.destroy_service(srv)
255273

256274
def test_sync_call_context_manager(self) -> None:
257-
def _service(request, response):
275+
def _service(request: GetParameters.Request,
276+
response: GetParameters.Response) -> GetParameters.Response:
258277
return response
278+
cli: ClientGetParameters
259279
with self.node.create_client(GetParameters, 'get/parameters') as cli:
260280
with self.node.create_service(GetParameters, 'get/parameters', _service):
261281
self.assertTrue(cli.wait_for_service(timeout_sec=20))

0 commit comments

Comments
 (0)