Skip to content

Commit c057875

Browse files
committed
formatting python code with black
1 parent a72e51f commit c057875

File tree

4 files changed

+32
-41
lines changed

4 files changed

+32
-41
lines changed
Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,2 +1 @@
1-
2-
from .node import Node
1+
from simple_node.node import Node

simple_node/simple_node/actions/action_client.py

Lines changed: 5 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ def __init__(
3030
node: Node,
3131
action_type: Type,
3232
action_name: str,
33-
feedback_cb: Callable = None
33+
feedback_cb: Callable = None,
3434
) -> None:
3535

3636
self._action_done_event = Event()
@@ -46,10 +46,7 @@ def __init__(
4646
self.feedback_cb = feedback_cb
4747

4848
super().__init__(
49-
node,
50-
action_type,
51-
action_name,
52-
callback_group=ReentrantCallbackGroup()
49+
node, action_type, action_name, callback_group=ReentrantCallbackGroup()
5350
)
5451

5552
def get_status(self) -> int:
@@ -74,7 +71,7 @@ def is_working(self) -> bool:
7471
return self._goal_handle is not None
7572

7673
def is_terminated(self) -> bool:
77-
return (self.is_succeeded() or self.is_canceled() or self.is_aborted())
74+
return self.is_succeeded() or self.is_canceled() or self.is_aborted()
7875

7976
def wait_for_result(self) -> None:
8077
self._action_done_event.clear()
@@ -94,8 +91,7 @@ def send_goal(self, goal, feedback_cb: Callable = None) -> None:
9491
if not feedback_cb is None:
9592
_feedback_cb = feedback_cb
9693

97-
send_goal_future = self.send_goal_async(
98-
goal, feedback_callback=_feedback_cb)
94+
send_goal_future = self.send_goal_async(goal, feedback_callback=_feedback_cb)
9995
send_goal_future.add_done_callback(self._goal_response_callback)
10096

10197
def _goal_response_callback(self, future) -> None:
@@ -113,8 +109,7 @@ def cancel_goal(self) -> None:
113109
with self._goal_handle_lock:
114110
if self._goal_handle is not None:
115111

116-
cancel_goal_future = self._cancel_goal_async(
117-
self._goal_handle)
112+
cancel_goal_future = self._cancel_goal_async(self._goal_handle)
118113
cancel_goal_future.add_done_callback(self._cancel_done)
119114

120115
self._cancel_done_event.clear()

simple_node/simple_node/actions/action_server.py

Lines changed: 12 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -27,15 +27,15 @@
2727

2828

2929
class ActionServer(ActionServer2):
30-
""" Action Server Class """
30+
"""Action Server Class"""
3131

3232
def __init__(
3333
self,
3434
node: Node,
3535
action_type,
3636
action_name: str,
3737
execute_callback: Callable,
38-
cancel_callback: Callable = None
38+
cancel_callback: Callable = None,
3939
) -> None:
4040

4141
self.__goal_lock = Lock()
@@ -46,27 +46,29 @@ def __init__(
4646
self.node = node
4747

4848
super().__init__(
49-
node, action_type, action_name,
49+
node,
50+
action_type,
51+
action_name,
5052
execute_callback=self.__execute_callback,
5153
goal_callback=self.__goal_callback,
5254
handle_accepted_callback=self.__handle_accepted_callback,
5355
cancel_callback=self.__cancel_callback,
54-
callback_group=ReentrantCallbackGroup()
56+
callback_group=ReentrantCallbackGroup(),
5557
)
5658

5759
def is_working(self) -> bool:
5860
return self._goal_handle is not None
5961

6062
def __goal_callback(self, goal_request) -> int:
61-
""" goal callback """
63+
"""goal callback"""
6264

6365
return GoalResponse.ACCEPT
6466

6567
def __handle_accepted_callback(self, goal_handle: ServerGoalHandle) -> None:
6668
"""
67-
handle accepted calback for a single goal server
68-
only one goal can be treated
69-
if other goal is send, old goal is aborted and replaced with the new one
69+
handle accepted calback for a single goal server
70+
only one goal can be treated
71+
if other goal is send, old goal is aborted and replaced with the new one
7072
"""
7173

7274
with self.__goal_lock:
@@ -77,7 +79,7 @@ def __handle_accepted_callback(self, goal_handle: ServerGoalHandle) -> None:
7779
self._goal_handle.execute()
7880

7981
def __cancel_callback(self, goal_handle: ServerGoalHandle) -> int:
80-
""" cancel calback """
82+
"""cancel calback"""
8183

8284
if self.__user_cancel_callback is not None:
8385
self.__cancel_thread = Thread(target=self.__user_cancel_callback)
@@ -87,7 +89,7 @@ def __cancel_callback(self, goal_handle: ServerGoalHandle) -> int:
8789

8890
def __execute_callback(self, goal_handle: ServerGoalHandle):
8991
"""
90-
execute callback
92+
execute callback
9193
"""
9294

9395
self.__cancel_thread = None

simple_node/simple_node/node.py

Lines changed: 14 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@
3434

3535

3636
class Node(Node2):
37-
""" Node Class """
37+
"""Node Class"""
3838

3939
def __init__(
4040
self,
@@ -48,7 +48,7 @@ def __init__(
4848
parameter_overrides: List[Parameter] = None,
4949
allow_undeclared_parameters: bool = False,
5050
automatically_declare_parameters_from_overrides: bool = False,
51-
executor: Executor = None
51+
executor: Executor = None,
5252
) -> None:
5353

5454
super().__init__(
@@ -61,7 +61,7 @@ def __init__(
6161
start_parameter_services=start_parameter_services,
6262
parameter_overrides=parameter_overrides,
6363
allow_undeclared_parameters=allow_undeclared_parameters,
64-
automatically_declare_parameters_from_overrides=automatically_declare_parameters_from_overrides
64+
automatically_declare_parameters_from_overrides=automatically_declare_parameters_from_overrides,
6565
)
6666

6767
if not executor:
@@ -76,7 +76,7 @@ def __init__(
7676
self._wake_thread.start()
7777

7878
def _run_executor(self) -> None:
79-
""" run an executer with self (node) """
79+
"""run an executer with self (node)"""
8080

8181
self._executor.add_node(self)
8282
try:
@@ -90,7 +90,7 @@ def _wake_node(self) -> None:
9090
time.sleep(1)
9191

9292
def join_spin(self) -> None:
93-
""" wait for spin thread """
93+
"""wait for spin thread"""
9494

9595
try:
9696
self._spin_thread.join()
@@ -99,20 +99,15 @@ def join_spin(self) -> None:
9999
self.get_logger().info("Destroying node " + self.get_name())
100100
self.destroy_node()
101101

102-
def create_client(
103-
self,
104-
srv_type: Type,
105-
srv_name: str
106-
) -> Client:
107-
return super().create_client(srv_type, srv_name, callback_group=ReentrantCallbackGroup())
102+
def create_client(self, srv_type: Type, srv_name: str) -> Client:
103+
return super().create_client(
104+
srv_type, srv_name, callback_group=ReentrantCallbackGroup()
105+
)
108106

109107
def create_action_client(
110-
self,
111-
action_type: Type,
112-
action_name: str,
113-
feedback_cb: Callable = None
108+
self, action_type: Type, action_name: str, feedback_cb: Callable = None
114109
) -> ActionClient:
115-
""" create action client from node
110+
"""create action client from node
116111
117112
Args:
118113
action_type ([type]): action type (msg action)
@@ -129,9 +124,9 @@ def create_action_server(
129124
action_type: Type,
130125
action_name: str,
131126
execute_callback: Callable,
132-
cancel_callback: Callable = None
127+
cancel_callback: Callable = None,
133128
) -> ActionServer:
134-
""" create action server from node
129+
"""create action server from node
135130
136131
Args:
137132
action_type ([type]): action type (msg action)
@@ -148,5 +143,5 @@ def create_action_server(
148143
action_type,
149144
action_name,
150145
execute_callback,
151-
cancel_callback=cancel_callback
146+
cancel_callback=cancel_callback,
152147
)

0 commit comments

Comments
 (0)