Skip to content

Commit b434598

Browse files
committed
Add type hints
1 parent e4eb914 commit b434598

File tree

8 files changed

+106
-65
lines changed

8 files changed

+106
-65
lines changed

rosbridge_library/src/rosbridge_library/capabilities/action_feedback.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
3232

3333
from rosbridge_library.capability import Capability
3434
from rosbridge_library.internal import message_conversion, ros_loader
35+
from rosbridge_library.protocol import Protocol
3536

3637

3738
class ActionFeedback(Capability):
@@ -42,14 +43,14 @@ class ActionFeedback(Capability):
4243
(False, "values", dict),
4344
]
4445

45-
def __init__(self, protocol):
46+
def __init__(self, protocol: Protocol) -> None:
4647
# Call superclass constructor
4748
Capability.__init__(self, protocol)
4849

4950
# Register the operations that this capability provides
5051
protocol.register_operation("action_feedback", self.action_feedback)
5152

52-
def action_feedback(self, message):
53+
def action_feedback(self, message: dict) -> None:
5354
# Typecheck the args
5455
self.basic_type_check(message, self.action_feedback_msg_fields)
5556

rosbridge_library/src/rosbridge_library/capabilities/action_result.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
3232

3333
from rosbridge_library.capability import Capability
3434
from rosbridge_library.internal import message_conversion, ros_loader
35+
from rosbridge_library.protocol import Protocol
3536

3637

3738
class ActionResult(Capability):
@@ -43,14 +44,14 @@ class ActionResult(Capability):
4344
(True, "result", bool),
4445
]
4546

46-
def __init__(self, protocol):
47+
def __init__(self, protocol: Protocol) -> None:
4748
# Call superclass constructor
4849
Capability.__init__(self, protocol)
4950

5051
# Register the operations that this capability provides
5152
protocol.register_operation("action_result", self.action_result)
5253

53-
def action_result(self, message):
54+
def action_result(self, message: dict) -> None:
5455
# Typecheck the args
5556
self.basic_type_check(message, self.action_result_msg_fields)
5657

rosbridge_library/src/rosbridge_library/capabilities/advertise_action.py

Lines changed: 13 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -31,20 +31,24 @@
3131
# POSSIBILITY OF SUCH DAMAGE.
3232

3333
import fnmatch
34+
from typing import Any
3435

3536
import rclpy
3637
from rclpy.action import ActionServer
3738
from rclpy.callback_groups import ReentrantCallbackGroup
3839
from rosbridge_library.capability import Capability
3940
from rosbridge_library.internal import message_conversion
4041
from rosbridge_library.internal.ros_loader import get_action_class
42+
from rosbridge_library.protocol import Protocol
4143

4244

4345
class AdvertisedActionHandler:
4446

4547
id_counter = 1
4648

47-
def __init__(self, action_name, action_type, protocol, sleep_time=0.001):
49+
def __init__(
50+
self, action_name: str, action_type: str, protocol: Protocol, sleep_time: float = 0.001
51+
) -> None:
4852
self.goal_futures = {}
4953
self.goal_handles = {}
5054

@@ -61,12 +65,12 @@ def __init__(self, action_name, action_type, protocol, sleep_time=0.001):
6165
callback_group=ReentrantCallbackGroup(), # https://github.com/ros2/rclpy/issues/834#issuecomment-961331870
6266
)
6367

64-
def next_id(self):
68+
def next_id(self) -> int:
6569
id = self.id_counter
6670
self.id_counter += 1
6771
return id
6872

69-
async def execute_callback(self, goal):
73+
async def execute_callback(self, goal: Any) -> Any:
7074
# generate a unique ID
7175
goal_id = f"action_goal:{self.action_name}:{self.next_id()}"
7276

@@ -92,7 +96,7 @@ async def execute_callback(self, goal):
9296
del self.goal_futures[goal_id]
9397
del self.goal_handles[goal_id]
9498

95-
def handle_feedback(self, goal_id, feedback):
99+
def handle_feedback(self, goal_id: str, feedback: Any) -> None:
96100
"""
97101
Called by the ActionFeedback capability to handle action feedback from the external client.
98102
"""
@@ -101,16 +105,16 @@ def handle_feedback(self, goal_id, feedback):
101105
else:
102106
self.protocol.log("warning", f"Received action feedback for unrecognized id: {goal_id}")
103107

104-
def handle_result(self, goal_id, res):
108+
def handle_result(self, goal_id: str, result: Any) -> None:
105109
"""
106110
Called by the ActionResult capability to handle an action result from the external client.
107111
"""
108112
if goal_id in self.goal_futures:
109-
self.goal_futures[goal_id].set_result(res)
113+
self.goal_futures[goal_id].set_result(result)
110114
else:
111115
self.protocol.log("warning", f"Received action result for unrecognized id: {goal_id}")
112116

113-
def graceful_shutdown(self):
117+
def graceful_shutdown(self) -> None:
114118
"""
115119
Signal the AdvertisedActionHandler to shutdown.
116120
"""
@@ -132,14 +136,14 @@ class AdvertiseAction(Capability):
132136

133137
advertise_action_msg_fields = [(True, "action", str), (True, "type", str)]
134138

135-
def __init__(self, protocol):
139+
def __init__(self, protocol: Protocol) -> None:
136140
# Call superclass constructor
137141
Capability.__init__(self, protocol)
138142

139143
# Register the operations that this capability provides
140144
protocol.register_operation("advertise_action", self.advertise_action)
141145

142-
def advertise_action(self, message):
146+
def advertise_action(self, message: dict) -> None:
143147
# Typecheck the args
144148
self.basic_type_check(message, self.advertise_action_msg_fields)
145149

rosbridge_library/src/rosbridge_library/capabilities/send_action_goal.py

Lines changed: 12 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636

3737
from rosbridge_library.capability import Capability
3838
from rosbridge_library.internal.actions import ActionClientHandler
39+
from rosbridge_library.protocol import Protocol
3940

4041

4142
class SendActionGoal(Capability):
@@ -51,7 +52,7 @@ class SendActionGoal(Capability):
5152
actions_glob = None
5253
client_handler_list = {}
5354

54-
def __init__(self, protocol):
55+
def __init__(self, protocol: Protocol) -> None:
5556
# Call superclass constructor
5657
Capability.__init__(self, protocol)
5758

@@ -75,7 +76,7 @@ def __init__(self, protocol):
7576

7677
protocol.register_operation("cancel_action_goal", self.cancel_action_goal)
7778

78-
def send_action_goal(self, message):
79+
def send_action_goal(self, message: dict) -> None:
7980
# Pull out the ID
8081
cid = message.get("id", None)
8182

@@ -128,7 +129,7 @@ def send_action_goal(self, message):
128129
client_handler.run()
129130
del self.client_handler_list[cid]
130131

131-
def cancel_action_goal(self, message):
132+
def cancel_action_goal(self, message: dict) -> None:
132133
# Extract the args
133134
cid = message.get("id", None)
134135
action = message["action"]
@@ -146,7 +147,9 @@ def cancel_action_goal(self, message):
146147
if client_handler.send_goal_helper is not None:
147148
client_handler.send_goal_helper.cancel_goal()
148149

149-
def _success(self, cid, action, fragment_size, compression, message):
150+
def _success(
151+
self, cid: str, action: str, fragment_size: int, compression: bool, message: dict
152+
) -> None:
150153
outgoing_message = {
151154
"op": "action_result",
152155
"action": action,
@@ -158,8 +161,8 @@ def _success(self, cid, action, fragment_size, compression, message):
158161
# TODO: fragmentation, compression
159162
self.protocol.send(outgoing_message)
160163

161-
def _failure(self, cid, action, exc):
162-
self.protocol.log("error", "send_action_goal %s: %s" % (type(exc).__name__, str(exc)), cid)
164+
def _failure(self, cid: str, action: str, exc: Exception) -> None:
165+
self.protocol.log("error", f"send_action_goal {type(exc).__name__}: {cid}")
163166
# send response with result: false
164167
outgoing_message = {
165168
"op": "action_result",
@@ -171,7 +174,7 @@ def _failure(self, cid, action, exc):
171174
outgoing_message["id"] = cid
172175
self.protocol.send(outgoing_message)
173176

174-
def _feedback(self, cid, action, message):
177+
def _feedback(self, cid: str, action: str, message: dict) -> None:
175178
outgoing_message = {
176179
"op": "action_feedback",
177180
"action": action,
@@ -183,13 +186,13 @@ def _feedback(self, cid, action, message):
183186
self.protocol.send(outgoing_message)
184187

185188

186-
def trim_action_name(action):
189+
def trim_action_name(action: str) -> str:
187190
if "#" in action:
188191
return action[: action.find("#")]
189192
return action
190193

191194

192-
def extract_id(action, cid):
195+
def extract_id(action: str, cid: str) -> str:
193196
if cid is not None:
194197
return cid
195198
elif "#" in action:

rosbridge_library/src/rosbridge_library/capabilities/unadvertise_action.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -33,20 +33,21 @@
3333
import fnmatch
3434

3535
from rosbridge_library.capability import Capability
36+
from rosbridge_library.protocol import Protocol
3637

3738

3839
class UnadvertiseAction(Capability):
3940

4041
actions_glob = None
4142

42-
def __init__(self, protocol):
43+
def __init__(self, protocol: Protocol) -> None:
4344
# Call superclass constructor
4445
Capability.__init__(self, protocol)
4546

4647
# Register the operations that this capability provides
4748
protocol.register_operation("unadvertise_action", self.unadvertise_action)
4849

49-
def unadvertise_action(self, message):
50+
def unadvertise_action(self, message: dict) -> None:
5051
# parse the message
5152
action_name = message["action"]
5253

rosbridge_library/src/rosbridge_library/internal/actions.py

Lines changed: 26 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -32,9 +32,12 @@
3232

3333
import time
3434
from threading import Thread
35+
from typing import Any, Callable, Optional, Union
3536

3637
from rclpy.action import ActionClient
3738
from rclpy.expand_topic_name import expand_topic_name
39+
from rclpy.node import Node
40+
from rclpy.task import Future
3841
from rosbridge_library.internal.message_conversion import (
3942
extract_values,
4043
populate_instance,
@@ -46,21 +49,21 @@
4649

4750

4851
class InvalidActionException(Exception):
49-
def __init__(self, action_name):
52+
def __init__(self, action_name) -> None:
5053
Exception.__init__(self, f"Action {action_name} does not exist")
5154

5255

5356
class ActionClientHandler(Thread):
5457
def __init__(
5558
self,
56-
action,
57-
action_type,
58-
args,
59-
success_callback,
60-
error_callback,
61-
feedback_callback,
62-
node_handle,
63-
):
59+
action: str,
60+
action_type: str,
61+
args: dict,
62+
success_callback: Callable[[str, str, int, bool, dict], None],
63+
error_callback: Callable[[str, str, Exception], None],
64+
feedback_callback: Callable[[str, str, dict], None],
65+
node_handle: Node,
66+
) -> None:
6467
"""
6568
Create a client handler for the specified action.
6669
Use start() to start in a separate thread or run() to run in this thread.
@@ -89,7 +92,7 @@ def __init__(
8992
self.node_handle = node_handle
9093
self.send_goal_helper = None
9194

92-
def run(self):
95+
def run(self) -> None:
9396
try:
9497
# Call the service and pass the result to the success handler
9598
self.send_goal_helper = SendGoal()
@@ -107,7 +110,7 @@ def run(self):
107110
self.error(e)
108111

109112

110-
def args_to_action_goal_instance(action, inst, args):
113+
def args_to_action_goal_instance(action: str, inst: Any, args: Union[list, dict]) -> Any:
111114
""" "
112115
Populate an action goal instance with the provided args
113116
@@ -128,23 +131,30 @@ def args_to_action_goal_instance(action, inst, args):
128131
class SendGoal:
129132
"""Helper class to send action goals."""
130133

131-
def __init__(self, server_timeout_time=1.0, sleep_time=0.001):
134+
def __init__(self, server_timeout_time: float = 1.0, sleep_time: float = 0.001) -> None:
132135
self.server_timeout_time = server_timeout_time
133136
self.sleep_time = sleep_time
134137
self.goal_handle = None
135138
self.goal_canceled = False
136139

137-
def get_result_cb(self, future):
140+
def get_result_cb(self, future: Future) -> None:
138141
self.result = future.result()
139142

140-
def goal_response_cb(self, future):
143+
def goal_response_cb(self, future: Future) -> None:
141144
self.goal_handle = future.result()
142145
if not self.goal_handle.accepted:
143146
raise Exception("Action goal was rejected")
144147
result_future = self.goal_handle.get_result_async()
145148
result_future.add_done_callback(self.get_result_cb)
146149

147-
def send_goal(self, node_handle, action, action_type, args=None, feedback_cb=None):
150+
def send_goal(
151+
self,
152+
node_handle: Node,
153+
action: str,
154+
action_type: str,
155+
args: Optional[dict] = None,
156+
feedback_cb: Optional[Callable[[str, str, dict], None]] = None,
157+
) -> dict:
148158
# Given the action name and type, fetch a request instance
149159
action_name = expand_topic_name(action, node_handle.get_name(), node_handle.get_namespace())
150160
action_class = get_action_class(action_type)
@@ -171,7 +181,7 @@ def send_goal(self, node_handle, action, action_type, args=None, feedback_cb=Non
171181

172182
return json_response
173183

174-
def cancel_goal(self):
184+
def cancel_goal(self) -> None:
175185
if self.goal_handle is None:
176186
return
177187

0 commit comments

Comments
 (0)