Skip to content

Commit

Permalink
Fix mypy errors on rolling
Browse files Browse the repository at this point in the history
  • Loading branch information
bjsowa committed Dec 17, 2024
1 parent 4e0ab97 commit dcc43c6
Show file tree
Hide file tree
Showing 3 changed files with 17 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
from rclpy.action import ActionServer
from rclpy.action.server import CancelResponse, ServerGoalHandle
from rclpy.callback_groups import ReentrantCallbackGroup
from rclpy.task import Future
from rosbridge_library.capability import Capability
from rosbridge_library.internal import message_conversion
from rosbridge_library.internal.ros_loader import get_action_class
Expand All @@ -51,7 +52,7 @@ class AdvertisedActionHandler:
def __init__(
self, action_name: str, action_type: str, protocol: Protocol, sleep_time: float = 0.001
) -> None:
self.goal_futures: dict[str, rclpy.task.Future] = {}
self.goal_futures: dict[str, Future] = {}
self.goal_handles: dict[str, Any] = {}
self.goal_statuses: dict[str, GoalStatus] = {}

Expand Down Expand Up @@ -79,7 +80,7 @@ async def execute_callback(self, goal: Any) -> Any:
# generate a unique ID
goal_id = f"action_goal:{self.action_name}:{self.next_id()}"

def done_callback(fut: rclpy.task.Future) -> None:
def done_callback(fut: Future) -> None:
if fut.cancelled():
goal.abort()
self.protocol.log("info", f"Aborted goal {goal_id}")
Expand All @@ -94,7 +95,7 @@ def done_callback(fut: rclpy.task.Future) -> None:
else:
goal.abort()

future = rclpy.task.Future()
future: Future = Future()
future.add_done_callback(done_callback)
self.goal_handles[goal_id] = goal
self.goal_futures[goal_id] = future
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ class TestActionFeedback(unittest.TestCase):

def goal_response_callback(self, future: Future):
goal_handle = future.result()
assert goal_handle is not None
if not goal_handle.accepted:
return
self.goal_result_future = goal_handle.get_result_async()
Expand Down
20 changes: 12 additions & 8 deletions rosbridge_server/test/websocket/common.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
from rcl_interfaces.srv import GetParameters
from rclpy.executors import SingleThreadedExecutor
from rclpy.node import Node
from rclpy.task import Future
from twisted.internet import reactor
from twisted.internet.endpoints import TCP4ClientEndpoint

Expand All @@ -24,7 +25,7 @@ class TestClientProtocol(WebSocketClientProtocol):

def __init__(self, *args, **kwargs):
self.received = []
self.connected_future = rclpy.task.Future()
self.connected_future = Future()
self.message_handler = lambda _: None
super().__init__(*args, **kwargs)

Expand Down Expand Up @@ -87,6 +88,7 @@ async def get_server_port(node: Node) -> int:
if not client.wait_for_service(5):
raise RuntimeError("GetParameters service not available")
port_param = await client.call_async(GetParameters.Request(names=["actual_port"]))
assert port_param is not None
return port_param.values[0].integer_value
finally:
node.destroy_client(client)
Expand All @@ -97,9 +99,10 @@ async def connect_to_server(node: Node) -> TestClientProtocol:
factory = WebSocketClientFactory("ws://127.0.0.1:" + str(port))
factory.protocol = TestClientProtocol

future = rclpy.task.Future()
assert node.executor is not None
future.add_done_callback(lambda _: node.executor.wake())
future: Future = Future()
executor = node.executor
assert executor is not None
future.add_done_callback(lambda _: executor.wake())

def connect():
TCP4ClientEndpoint(reactor, "127.0.0.1", port).connect(factory).addCallback(
Expand All @@ -108,8 +111,9 @@ def connect():

reactor.callFromThread(connect) # type: ignore[attr-defined]

protocol = await future
protocol.connected_future.add_done_callback(lambda _: node.executor.wake())
protocol: TestClientProtocol | None = await future
assert protocol is not None
protocol.connected_future.add_done_callback(lambda _: executor.wake())
await protocol.connected_future # wait for onOpen before proceeding
return protocol

Expand Down Expand Up @@ -142,7 +146,7 @@ def sleep(node: Node, duration: float) -> Awaitable[None]:
"""
Async-compatible delay function based on a ROS timer.
"""
future = rclpy.task.Future()
future: Future = Future()

def callback():
future.set_result(None)
Expand Down Expand Up @@ -171,7 +175,7 @@ def expect_messages(count: int, description: str, logger):
Convenience function to create a Future and a message handler function which gathers results
into a list and waits for the list to have the expected number of items.
"""
future = rclpy.Future()
future: Future = Future()
results = []

def handler(msg):
Expand Down

0 comments on commit dcc43c6

Please sign in to comment.