Skip to content

Commit 7a94bf3

Browse files
committed
typing fixed
1 parent 7201d87 commit 7a94bf3

File tree

3 files changed

+45
-30
lines changed

3 files changed

+45
-30
lines changed

simple_node/simple_node/actions/action_client.py

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414
# along with this program. If not, see <https://www.gnu.org/licenses/>.
1515

1616

17-
from typing import Callable
17+
from typing import Callable, Type, Any
1818
import time
1919
from threading import Thread, Lock
2020
from action_msgs.msg import GoalStatus
@@ -25,7 +25,7 @@
2525

2626
class ActionClient(ActionClient2):
2727

28-
def __init__(self, node: Node, action_type, action_name: str, feedback_cb: Callable = None):
28+
def __init__(self, node: Node, action_type: Type, action_name: str, feedback_cb: Callable = None) -> None:
2929
self._status = GoalStatus.STATUS_UNKNOWN
3030
self.__status_lock = Lock()
3131
self.__goal_handle = None
@@ -39,7 +39,7 @@ def get_status(self) -> int:
3939
with self.__status_lock:
4040
return self._status
4141

42-
def _set_status(self, status: int):
42+
def _set_status(self, status: int) -> None:
4343
with self.__status_lock:
4444
self._status = status
4545

@@ -67,13 +67,13 @@ def is_working(self) -> bool:
6767
def is_terminated(self) -> bool:
6868
return (self.is_succeeded() or self.is_canceled() or self.is_aborted())
6969

70-
def wait_for_result(self):
70+
def wait_for_result(self) -> None:
7171
self.__goal_thread.join()
7272

73-
def get_result(self):
73+
def get_result(self) -> Any:
7474
return self.__result
7575

76-
def __send_goal(self, goal, feedback_cb: Callable = None):
76+
def __send_goal(self, goal, feedback_cb: Callable = None) -> None:
7777

7878
self.__result = None
7979

@@ -118,7 +118,7 @@ def __send_goal(self, goal, feedback_cb: Callable = None):
118118
self._set_status(get_result_future.result().status)
119119
self.__result = get_result_future.result().result
120120

121-
def send_goal(self, goal, feedback_cb: Callable = None):
121+
def send_goal(self, goal, feedback_cb: Callable = None) -> None:
122122

123123
_feedback_cb = self.feedback_cb
124124

simple_node/simple_node/actions/action_server.py

Lines changed: 8 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -31,12 +31,14 @@
3131
class ActionServer(ActionServer2):
3232
""" Action Server Class """
3333

34-
def __init__(self,
35-
node: Node,
36-
action_type,
37-
action_name: str,
38-
execute_callback: Callable,
39-
cancel_callback: Callable = None):
34+
def __init__(
35+
self,
36+
node: Node,
37+
action_type,
38+
action_name: str,
39+
execute_callback: Callable,
40+
cancel_callback: Callable = None
41+
) -> None:
4042

4143
self.__goal_lock = Lock()
4244
self.__user_execute_callback = execute_callback

simple_node/simple_node/node.py

Lines changed: 30 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919

2020
import time
2121
from threading import Thread
22-
from typing import Callable
22+
from typing import Callable, Type
2323

2424
import rclpy
2525
from rclpy.node import Node as Node2
@@ -34,7 +34,7 @@
3434
class Node(Node2):
3535
""" Node Class """
3636

37-
def __init__(self, node_name: str, namespace: str = "", executor: Executor = None):
37+
def __init__(self, node_name: str, namespace: str = "", executor: Executor = None) -> None:
3838

3939
super().__init__(node_name, namespace=namespace)
4040

@@ -49,7 +49,7 @@ def __init__(self, node_name: str, namespace: str = "", executor: Executor = Non
4949
self._wake_thread = Thread(target=self._wake_node, daemon=True)
5050
self._wake_thread.start()
5151

52-
def _run_executor(self):
52+
def _run_executor(self) -> None:
5353
""" run an executer with self (node) """
5454

5555
self._executor.add_node(self)
@@ -58,12 +58,12 @@ def _run_executor(self):
5858
finally:
5959
self._executor.shutdown()
6060

61-
def _wake_node(self):
61+
def _wake_node(self) -> None:
6262
while rclpy.ok():
6363
self._executor.wake()
6464
time.sleep(1)
6565

66-
def join_spin(self):
66+
def join_spin(self) -> None:
6767
""" wait for spin thread """
6868

6969
try:
@@ -73,10 +73,19 @@ def join_spin(self):
7373
self.get_logger().info("Destroying node " + self.get_name())
7474
self.destroy_node()
7575

76-
def create_client(self, srv_type, srv_name: str) -> Client:
76+
def create_client(
77+
self,
78+
srv_type: Type,
79+
srv_name: str
80+
) -> Client:
7781
return super().create_client(srv_type, srv_name, callback_group=ReentrantCallbackGroup())
7882

79-
def create_action_client(self, action_type, action_name: str, feedback_cb: Callable = None) -> ActionClient:
83+
def create_action_client(
84+
self,
85+
action_type: Type,
86+
action_name: str,
87+
feedback_cb: Callable = None
88+
) -> ActionClient:
8089
""" create action client from node
8190
8291
Args:
@@ -89,11 +98,13 @@ def create_action_client(self, action_type, action_name: str, feedback_cb: Calla
8998

9099
return ActionClient(self, action_type, action_name, feedback_cb)
91100

92-
def create_action_server(self,
93-
action_type,
94-
action_name: str,
95-
execute_callback: Callable,
96-
cancel_callback: Callable = None) -> ActionServer:
101+
def create_action_server(
102+
self,
103+
action_type: Type,
104+
action_name: str,
105+
execute_callback: Callable,
106+
cancel_callback: Callable = None
107+
) -> ActionServer:
97108
""" create action server from node
98109
99110
Args:
@@ -106,8 +117,10 @@ def create_action_server(self,
106117
ActionSingleServer: server created
107118
"""
108119

109-
return ActionServer(self,
110-
action_type,
111-
action_name,
112-
execute_callback,
113-
cancel_callback=cancel_callback)
120+
return ActionServer(
121+
self,
122+
action_type,
123+
action_name,
124+
execute_callback,
125+
cancel_callback=cancel_callback
126+
)

0 commit comments

Comments
 (0)