Skip to content

Commit 2462b82

Browse files
authored
Fix mypy errors (backport #1084) (#1085)
* Fix mypy errors (backport #1084) * Fix lint errors
1 parent cd982e5 commit 2462b82

File tree

12 files changed

+39
-35
lines changed

12 files changed

+39
-35
lines changed

rosapi/src/rosapi/params.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -141,7 +141,7 @@ async def _set_param(
141141

142142
assert _node is not None
143143
client = _node.create_client(
144-
SetParameters, # type: ignore[arg-type]
144+
SetParameters,
145145
f"{node_name}/set_parameters",
146146
callback_group=MutuallyExclusiveCallbackGroup(),
147147
)
@@ -202,7 +202,7 @@ async def _get_param(node_name: str, name: str) -> ParameterValue:
202202
"""
203203
assert _node is not None
204204
client = _node.create_client(
205-
GetParameters, # type: ignore[arg-type]
205+
GetParameters,
206206
f"{node_name}/get_parameters",
207207
callback_group=MutuallyExclusiveCallbackGroup(),
208208
)
@@ -278,7 +278,7 @@ async def get_param_names(params_glob: str | None) -> list[str]:
278278
continue
279279

280280
client = _node.create_client(
281-
ListParameters, # type: ignore[arg-type]
281+
ListParameters,
282282
f"{node_name}/list_parameters",
283283
callback_group=MutuallyExclusiveCallbackGroup(),
284284
)

rosbridge_library/test/capabilities/test_call_service.py

Lines changed: 15 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
import unittest
66
from json import dumps, loads
77
from threading import Thread
8-
from typing import Any
8+
from typing import TYPE_CHECKING, Any
99

1010
import rclpy
1111
from rclpy.callback_groups import ReentrantCallbackGroup
@@ -20,24 +20,27 @@
2020
)
2121
from rosbridge_library.protocol import Protocol
2222

23+
if TYPE_CHECKING:
24+
from std_srvs.srv import SetBool_Request, SetBool_Response, Trigger_Request, Trigger_Response
25+
2326

2427
class TestCallService(unittest.TestCase):
25-
def trigger_cb(self, _request: Trigger.Request, response: Trigger.Response) -> Trigger.Response:
28+
def trigger_cb(self, _request: Trigger_Request, response: Trigger_Response) -> Trigger_Response:
2629
"""Handle request for a test service with no arguments."""
2730
response.success = True
2831
response.message = "called trigger service successfully"
2932
return response
3033

3134
def trigger_long_cb(
32-
self, _request: Trigger.Request, response: Trigger.Response
33-
) -> Trigger.Response:
35+
self, _request: Trigger_Request, response: Trigger_Response
36+
) -> Trigger_Response:
3437
"""Handle request for a long running test service with no arguments."""
3538
time.sleep(0.5)
3639
response.success = True
3740
response.message = "called trigger service successfully"
3841
return response
3942

40-
def set_bool_cb(self, request: SetBool.Request, response: SetBool.Response) -> SetBool.Response:
43+
def set_bool_cb(self, request: SetBool_Request, response: SetBool_Response) -> SetBool_Response:
4144
"""Handle request for a test service with arguments."""
4245
response.success = request.data
4346
if request.data:
@@ -61,19 +64,19 @@ def setUp(self) -> None:
6164
# Create service servers with a separate callback group
6265
self.cb_group = ReentrantCallbackGroup()
6366
self.trigger_srv = self.node.create_service(
64-
Trigger, # type: ignore[arg-type]
67+
Trigger,
6568
self.node.get_name() + "/trigger",
6669
self.trigger_cb,
6770
callback_group=self.cb_group,
6871
)
6972
self.trigger_long_srv = self.node.create_service(
70-
Trigger, # type: ignore[arg-type]
73+
Trigger,
7174
self.node.get_name() + "/trigger_long",
7275
self.trigger_long_cb,
7376
callback_group=self.cb_group,
7477
)
7578
self.set_bool_srv = self.node.create_service(
76-
SetBool, # type: ignore[arg-type]
79+
SetBool,
7780
self.node.get_name() + "/set_bool",
7881
self.set_bool_cb,
7982
callback_group=self.cb_group,
@@ -104,7 +107,7 @@ def test_invalid_arguments(self) -> None:
104107

105108
def test_call_service_works(self) -> None:
106109
client = self.node.create_client(
107-
Trigger, # type: ignore[arg-type]
110+
Trigger,
108111
self.trigger_srv.srv_name,
109112
)
110113
assert client.wait_for_service(1.0)
@@ -135,7 +138,7 @@ def cb(
135138

136139
def test_call_service_args(self) -> None:
137140
client = self.node.create_client(
138-
SetBool, # type: ignore[arg-type]
141+
SetBool,
139142
self.set_bool_srv.srv_name,
140143
)
141144
assert client.wait_for_service(1.0)
@@ -173,7 +176,7 @@ def cb(
173176

174177
def test_call_service_fails(self) -> None:
175178
client = self.node.create_client(
176-
Trigger, # type: ignore[arg-type]
179+
Trigger,
177180
self.trigger_srv.srv_name,
178181
)
179182
assert client.wait_for_service(1.0)
@@ -210,7 +213,7 @@ def cb(
210213

211214
def test_call_service_timeout(self) -> None:
212215
client = self.node.create_client(
213-
Trigger, # type: ignore[arg-type]
216+
Trigger,
214217
self.trigger_long_srv.srv_name,
215218
)
216219
assert client.wait_for_service(1.0)

rosbridge_library/test/internal/actions/test_actions.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ def __init__(self, executor: Executor) -> None:
2929
self.executor.add_node(self.node)
3030
self.action_server = ActionServer(
3131
self.node,
32-
Fibonacci, # type: ignore[arg-type]
32+
Fibonacci,
3333
"get_fibonacci_sequence",
3434
self.execute_callback,
3535
)
@@ -156,7 +156,7 @@ def get_result_callback(future: Future) -> None:
156156
# First, call the action the 'proper' way
157157
client = ActionClient(
158158
self.node,
159-
Fibonacci, # type: ignore[arg-type]
159+
Fibonacci,
160160
"get_fibonacci_sequence",
161161
)
162162
client.wait_for_server()

rosbridge_library/test/internal/services/test_services.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -182,7 +182,7 @@ def test_service_call(self) -> None:
182182

183183
# First, call the service the 'proper' way
184184
p = self.node.create_client(
185-
ListParameters, # type: ignore[arg-type]
185+
ListParameters,
186186
self.node.get_name() + "/list_parameters",
187187
)
188188
p.wait_for_service(0.5)
@@ -212,7 +212,7 @@ def test_service_caller(self) -> None:
212212

213213
# First, call the service the 'proper' way
214214
p = self.node.create_client(
215-
ListParameters, # type: ignore[arg-type]
215+
ListParameters,
216216
self.node.get_name() + "/list_parameters",
217217
)
218218
p.wait_for_service(0.5)

rosbridge_library/test/internal/test_cbor_conversion.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -64,23 +64,23 @@ def test_numbers(self) -> None:
6464
# msg: ROSMessage
6565
# msg_type: type[ROSMessage]
6666
for msg_type in [Int8, Int16, Int32, Int64]:
67-
msg = msg_type(data=-5)
67+
msg = msg_type(data=-5) # type: ignore[abstract]
6868
assert isinstance(msg, Int8 | Int16 | Int32 | Int64)
6969
extracted = extract_cbor_values(msg)
7070

7171
self.assertEqual(extracted["data"], msg.data, f"type={msg_type}")
7272
self.assertEqual(type(extracted["data"]), int, f"type={msg_type}")
7373

7474
for msg_type in [UInt8, UInt16, UInt32, UInt64]:
75-
msg = msg_type(data=5)
75+
msg = msg_type(data=5) # type: ignore[abstract]
7676
assert isinstance(msg, UInt8 | UInt16 | UInt32 | UInt64)
7777
extracted = extract_cbor_values(msg)
7878

7979
self.assertEqual(extracted["data"], msg.data, f"type={msg_type}")
8080
self.assertEqual(type(extracted["data"]), int, f"type={msg_type}")
8181

8282
for msg_type in [Float32, Float64]:
83-
msg = msg_type(data=2.3)
83+
msg = msg_type(data=2.3) # type: ignore[abstract]
8484
assert isinstance(msg, Float32 | Float64)
8585
extracted = extract_cbor_values(msg)
8686

@@ -117,7 +117,7 @@ def test_integer_array(self) -> None:
117117
UInt32MultiArray,
118118
UInt64MultiArray,
119119
]:
120-
msg = msg_type(data=[0, 1, 2])
120+
msg = msg_type(data=[0, 1, 2]) # type: ignore[abstract]
121121
assert isinstance(
122122
msg,
123123
Int8MultiArray

rosbridge_server/test/websocket/advertise_action.test.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ async def test_two_concurrent_calls(
5959
)
6060
client: ActionClient = ActionClient(
6161
node,
62-
Fibonacci, # type: ignore[arg-type]
62+
Fibonacci,
6363
"/test_fibonacci_action",
6464
)
6565
client.wait_for_server()

rosbridge_server/test/websocket/advertise_action_feedback.test.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ async def test_feedback(
5757
)
5858
client: ActionClient = ActionClient(
5959
node,
60-
Fibonacci, # type: ignore[arg-type]
60+
Fibonacci,
6161
"/test_fibonacci_action",
6262
)
6363
client.wait_for_server()

rosbridge_server/test/websocket/advertise_service.test.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ async def test_two_concurrent_calls(
4040
}
4141
)
4242
client: Client = node.create_client(
43-
SetBool, # type: ignore[arg-type]
43+
SetBool,
4444
"/test_service",
4545
)
4646
client.wait_for_service()

rosbridge_server/test/websocket/advertise_service_duplicate.test.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ async def test_double_advertise(
4040
}
4141
)
4242
client: Client = node.create_client(
43-
SetBool, # type: ignore[arg-type]
43+
SetBool,
4444
"/test_service",
4545
)
4646
client.wait_for_service()

rosbridge_server/test/websocket/call_service.test.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020

2121
from common import TestClientProtocol
2222
from rclpy.node import Node
23-
# from rclpy.task import Future
23+
from std_srvs.srv import SetBool_Request, SetBool_Response
2424

2525
log.startLogging(sys.stderr)
2626

@@ -32,14 +32,14 @@ class TestCallService(unittest.TestCase):
3232
async def test_one_call(
3333
self, node: Node, make_client: Callable[[], Awaitable[TestClientProtocol]]
3434
) -> None:
35-
def service_cb(req: SetBool.Request, res: SetBool.Response) -> SetBool.Response:
35+
def service_cb(req: SetBool_Request, res: SetBool_Response) -> SetBool_Response:
3636
self.assertTrue(req.data)
3737
res.success = True
3838
res.message = "Hello, world!"
3939
return res
4040

4141
service = node.create_service(
42-
SetBool, # type: ignore[arg-type]
42+
SetBool,
4343
"/test_service",
4444
service_cb,
4545
callback_group=ReentrantCallbackGroup(),
@@ -72,15 +72,15 @@ def service_cb(req: SetBool.Request, res: SetBool.Response) -> SetBool.Response:
7272

7373
node.destroy_service(service)
7474

75-
def service_long_cb(req: SetBool.Request, res: SetBool.Response) -> SetBool.Response:
75+
def service_long_cb(req: SetBool_Request, res: SetBool_Response) -> SetBool_Response:
7676
time.sleep(0.2)
7777
self.assertTrue(req.data)
7878
res.success = True
7979
res.message = "Hello, world!"
8080
return res
8181

8282
service = node.create_service(
83-
SetBool, # type: ignore[arg-type]
83+
SetBool,
8484
"/test_service_long",
8585
service_long_cb,
8686
callback_group=ReentrantCallbackGroup(),

0 commit comments

Comments
 (0)