Skip to content

Commit b66dd79

Browse files
Ran pre-commit
1 parent 4721f11 commit b66dd79

File tree

3 files changed

+24
-18
lines changed

3 files changed

+24
-18
lines changed

src/ros_tcp_endpoint/client.py

Lines changed: 12 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -168,17 +168,17 @@ def send_ros_service_request(self, srv_id, destination, data):
168168
return
169169
else:
170170
ros_communicator = self.tcp_server.source_destination_dict[destination]
171-
service_thread = threading.Thread(target=self.service_call_thread, args=(srv_id, destination, data, ros_communicator))
171+
service_thread = threading.Thread(
172+
target=self.service_call_thread, args=(srv_id, destination, data, ros_communicator)
173+
)
172174
service_thread.daemon = True
173175
service_thread.start()
174176

175177
def service_call_thread(self, srv_id, destination, data, ros_communicator):
176178
response = ros_communicator.send(data)
177-
179+
178180
if not response:
179-
error_msg = "No response data from service '{}'!".format(
180-
destination
181-
)
181+
error_msg = "No response data from service '{}'!".format(destination)
182182
self.tcp_server.send_unity_error(error_msg)
183183
rospy.logerr(error_msg)
184184
# TODO: send a response to Unity anyway?
@@ -207,13 +207,17 @@ def run(self):
207207
try:
208208
while not halt_event.is_set():
209209
destination, data = self.read_message(self.conn)
210-
210+
211211
if self.tcp_server.pending_srv_id is not None:
212212
# if we've been told that the next message will be a service request/response, process it as such
213213
if self.tcp_server.pending_srv_is_request:
214-
self.send_ros_service_request(self.tcp_server.pending_srv_id, destination, data)
214+
self.send_ros_service_request(
215+
self.tcp_server.pending_srv_id, destination, data
216+
)
215217
else:
216-
self.tcp_server.send_unity_service_response(self.tcp_server.pending_srv_id, data)
218+
self.tcp_server.send_unity_service_response(
219+
self.tcp_server.pending_srv_id, data
220+
)
217221
self.tcp_server.pending_srv_id = None
218222
elif destination == "":
219223
# ignore this keepalive message, listen for more

src/ros_tcp_endpoint/server.py

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -104,15 +104,14 @@ def send_unity_service_response(self, srv_id, data):
104104
def handle_syscommand(self, topic, data):
105105
function = getattr(self.syscommands, topic[2:])
106106
if function is None:
107-
self.send_unity_error(
108-
"Don't understand SysCommand.'{}'".format(topic)
109-
)
107+
self.send_unity_error("Don't understand SysCommand.'{}'".format(topic))
110108
return
111109
else:
112110
message_json = data.decode("utf-8")
113111
params = json.loads(message_json)
114112
function(**params)
115113

114+
116115
class SysCommands:
117116
def __init__(self, tcp_server):
118117
self.tcp_server = tcp_server
@@ -218,13 +217,13 @@ def unity_service(self, topic, message_name):
218217
self.tcp_server.source_destination_dict[topic] = UnityService(
219218
topic, message_class, self.tcp_server
220219
)
221-
222-
def response(self, srv_id): # the next message is a service response
223-
self.tcp_server.pending_srv_id = srv_id
220+
221+
def response(self, srv_id): # the next message is a service response
222+
self.tcp_server.pending_srv_id = srv_id
224223
self.tcp_server.pending_srv_is_request = False
225224

226-
def request(self, srv_id): # the next message is a service request
227-
self.tcp_server.pending_srv_id = srv_id
225+
def request(self, srv_id): # the next message is a service request
226+
self.tcp_server.pending_srv_id = srv_id
228227
self.tcp_server.pending_srv_is_request = True
229228

230229
def topic_list(self):

src/ros_tcp_endpoint/tcp_sender.py

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ def send_unity_message(self, topic, message):
8686
def send_unity_service_request(self, topic, service_class, request):
8787
if self.queue is None:
8888
return None
89-
89+
9090
thread_pauser = ThreadPauser()
9191
with self.srv_lock:
9292
srv_id = self.next_srv_id
@@ -164,12 +164,15 @@ def sender_loop(self, conn, tid, halt_event):
164164
if self.queue is local_queue:
165165
self.queue = None
166166

167+
167168
class SysCommand_Log:
168169
text = ""
169170

171+
170172
class SysCommand_Service:
171173
srv_id = 0
172174

175+
173176
class SysCommand_TopicsResponse:
174177
topics = []
175-
types = []
178+
types = []

0 commit comments

Comments
 (0)