Skip to content

Commit eed0f8d

Browse files
committed
run black skipping string normalization
1 parent ec71e47 commit eed0f8d

File tree

8 files changed

+209
-250
lines changed

8 files changed

+209
-250
lines changed

src/roslibpy/__init__.py

Lines changed: 3 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -98,22 +98,10 @@ class and are passed around via :class:`Topics <Topic>` using a **publish/subscr
9898
__license__,
9999
__title__,
100100
__url__,
101-
__version__
102-
)
103-
from .core import (
104-
Header,
105-
Message,
106-
Param,
107-
Service,
108-
ServiceRequest,
109-
ServiceResponse,
110-
Time,
111-
Topic
112-
)
113-
from .ros import (
114-
set_rosapi_timeout,
115-
Ros
101+
__version__,
116102
)
103+
from .core import Header, Message, Param, Service, ServiceRequest, ServiceResponse, Time, Topic
104+
from .ros import set_rosapi_timeout, Ros
117105

118106
__all__ = [
119107
'__author__',
@@ -124,7 +112,6 @@ class and are passed around via :class:`Topics <Topic>` using a **publish/subscr
124112
'__title__',
125113
'__url__',
126114
'__version__',
127-
128115
'Header',
129116
'Message',
130117
'Param',
@@ -133,7 +120,6 @@ class and are passed around via :class:`Topics <Topic>` using a **publish/subscr
133120
'ServiceResponse',
134121
'Time',
135122
'Topic',
136-
137123
'set_rosapi_timeout',
138124
'Ros',
139125
]

src/roslibpy/actionlib.py

Lines changed: 26 additions & 49 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,7 @@ def _is_earlier(t1, t2):
5353

5454
class GoalStatus:
5555
"""Valid goal statuses."""
56+
5657
PENDING = 0
5758
ACTIVE = 1
5859
PREEMPTED = 2
@@ -93,16 +94,9 @@ def __init__(self, action_client, goal_message):
9394
self.status = None
9495
self.feedback = None
9596

96-
self.goal_message = Message({
97-
'goal_id': {
98-
'stamp': {
99-
'secs': 0,
100-
'nsecs': 0
101-
},
102-
'id': self.goal_id
103-
},
104-
'goal': dict(self.goal_message)
105-
})
97+
self.goal_message = Message(
98+
{'goal_id': {'stamp': {'secs': 0, 'nsecs': 0}, 'id': self.goal_id}, 'goal': dict(self.goal_message)}
99+
)
106100

107101
self.action_client.add_goal(self)
108102

@@ -167,8 +161,7 @@ def _set_feedback(self, feedback):
167161
def is_active(self):
168162
if self.status is None:
169163
return False
170-
return (self.status['status'] == GoalStatus.ACTIVE or
171-
self.status['status'] == GoalStatus.PENDING)
164+
return self.status['status'] == GoalStatus.ACTIVE or self.status['status'] == GoalStatus.PENDING
172165

173166
@property
174167
def is_finished(self):
@@ -190,8 +183,9 @@ class ActionClient(EventEmitterMixin):
190183
timeout (:obj:`int`): **Deprecated.** Connection timeout, expressed in seconds.
191184
"""
192185

193-
def __init__(self, ros, server_name, action_name, timeout=None,
194-
omit_feedback=False, omit_status=False, omit_result=False):
186+
def __init__(
187+
self, ros, server_name, action_name, timeout=None, omit_feedback=False, omit_status=False, omit_result=False
188+
):
195189
super(ActionClient, self).__init__()
196190
self.ros = ros
197191
self.server_name = server_name
@@ -226,7 +220,8 @@ def __init__(self, ros, server_name, action_name, timeout=None,
226220

227221
if timeout:
228222
LOGGER.warn(
229-
'Deprecation warning: timeout parameter is ignored, and replaced by the DEFAULT_CONNECTION_TIMEOUT constant.')
223+
'Deprecation warning: timeout parameter is ignored, and replaced by the DEFAULT_CONNECTION_TIMEOUT constant.'
224+
)
230225

231226
self.wait_status = threading.Event()
232227

@@ -295,7 +290,8 @@ class SimpleActionServer(EventEmitterMixin):
295290
server_name (:obj:`str`): Action server name, e.g. ``/fibonacci``.
296291
action_name (:obj:`str`): Action message name, e.g. ``actionlib_tutorials/FibonacciAction``.
297292
"""
298-
STATUS_PUBLISH_INTERVAL = 0.5 # In seconds
293+
294+
STATUS_PUBLISH_INTERVAL = 0.5 # In seconds
299295

300296
def __init__(self, ros, server_name, action_name):
301297
super(SimpleActionServer, self).__init__()
@@ -318,17 +314,11 @@ def __init__(self, ros, server_name, action_name):
318314
self.result_publisher.advertise()
319315

320316
# Track the goals and their status in order to publish status
321-
self.status_message = Message(dict(
322-
header=dict(
323-
stamp=dict(secs=0, nsecs=100),
324-
frame_id=''
325-
),
326-
status_list=[]
327-
))
317+
self.status_message = Message(dict(header=dict(stamp=dict(secs=0, nsecs=100), frame_id=''), status_list=[]))
328318

329319
# Needed for handling preemption prompted by a new goal being received
330-
self.current_goal = None # currently tracked goal
331-
self.next_goal = None # the one that'll be preempting
320+
self.current_goal = None # currently tracked goal
321+
self.next_goal = None # the one that'll be preempting
332322
self.preempt_request = False
333323

334324
self.goal_listener.subscribe(self._on_goal_message)
@@ -381,8 +371,7 @@ def _on_goal_message(self, message):
381371
# needs to happen AFTER rest is set up
382372
will_cancel = True
383373
else:
384-
self.status_message['status_list'] = [
385-
dict(goal_id=message['goal_id'], status=GoalStatus.ACTIVE)]
374+
self.status_message['status_list'] = [dict(goal_id=message['goal_id'], status=GoalStatus.ACTIVE)]
386375
self.current_goal = message
387376
will_emit_goal = message['goal']
388377

@@ -435,17 +424,12 @@ def set_succeeded(self, result):
435424
Args:
436425
result (:obj:`dict`): Dictionary of key/values to set as the result of the action.
437426
"""
438-
LOGGER.info(
439-
'Action server {} setting current goal to SUCCEEDED'.format(self.server_name))
427+
LOGGER.info('Action server {} setting current goal to SUCCEEDED'.format(self.server_name))
440428

441429
with self._lock:
442-
result_message = Message({
443-
'status': {
444-
'goal_id': self.current_goal['goal_id'],
445-
'status': GoalStatus.SUCCEEDED
446-
},
447-
'result': result
448-
})
430+
result_message = Message(
431+
{'status': {'goal_id': self.current_goal['goal_id'], 'status': GoalStatus.SUCCEEDED}, 'result': result}
432+
)
449433

450434
self.result_publisher.publish(result_message)
451435

@@ -469,13 +453,9 @@ def send_feedback(self, feedback):
469453
Args:
470454
feedback (:obj:`dict`): Dictionary of key/values of the feedback message.
471455
"""
472-
feedback_message = Message({
473-
'status': {
474-
'goal_id': self.current_goal['goal_id'],
475-
'status': GoalStatus.ACTIVE
476-
},
477-
'feedback': feedback
478-
})
456+
feedback_message = Message(
457+
{'status': {'goal_id': self.current_goal['goal_id'], 'status': GoalStatus.ACTIVE}, 'feedback': feedback}
458+
)
479459

480460
self.feedback_publisher.publish(feedback_message)
481461

@@ -485,12 +465,9 @@ def set_preempted(self):
485465

486466
with self._lock:
487467
self.status_message['status_list'] = []
488-
result_message = Message({
489-
'status': {
490-
'goal_id': self.current_goal['goal_id'],
491-
'status': GoalStatus.PREEMPTED
492-
}
493-
})
468+
result_message = Message(
469+
{'status': {'goal_id': self.current_goal['goal_id'], 'status': GoalStatus.PREEMPTED}}
470+
)
494471

495472
self.result_publisher.publish(result_message)
496473

src/roslibpy/comm/comm.py

Lines changed: 5 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212

1313
class RosBridgeException(Exception):
1414
"""Exception raised on the ROS bridge communication."""
15+
1516
pass
1617

1718

@@ -33,8 +34,7 @@ def on_message(self, payload):
3334
message = Message(json.loads(payload.decode('utf8')))
3435
handler = self._message_handlers.get(message['op'], None)
3536
if not handler:
36-
raise RosBridgeException(
37-
'No handler registered for operation "%s"' % message['op'])
37+
raise RosBridgeException('No handler registered for operation "%s"' % message['op'])
3838

3939
handler(message)
4040

@@ -62,8 +62,7 @@ def register_message_handlers(self, operation, handler):
6262
handler: Callback to handle the message.
6363
"""
6464
if operation in self._message_handlers:
65-
raise RosBridgeException(
66-
'Only one handler can be registered per operation')
65+
raise RosBridgeException('Only one handler can be registered per operation')
6766

6867
self._message_handlers[operation] = handler
6968

@@ -91,8 +90,7 @@ def _handle_service_response(self, message):
9190
service_handlers = self._pending_service_requests.get(request_id, None)
9291

9392
if not service_handlers:
94-
raise RosBridgeException(
95-
'No handler registered for service request ID: "%s"' % request_id)
93+
raise RosBridgeException('No handler registered for service request ID: "%s"' % request_id)
9694

9795
callback, errback = service_handlers
9896
del self._pending_service_requests[request_id]
@@ -106,7 +104,6 @@ def _handle_service_response(self, message):
106104

107105
def _handle_service_request(self, message):
108106
if 'service' not in message:
109-
raise ValueError(
110-
'Expected service name missing in service request')
107+
raise ValueError('Expected service name missing in service request')
111108

112109
self.factory.emit(message['service'], message)

src/roslibpy/comm/comm_autobahn.py

Lines changed: 14 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -38,14 +38,18 @@ def onMessage(self, payload, isBinary):
3838
try:
3939
self.on_message(payload)
4040
except Exception:
41-
LOGGER.exception('Exception on start_listening while trying to handle message received.' +
42-
'It could indicate a bug in user code on message handlers. Message skipped.')
41+
LOGGER.exception(
42+
'Exception on start_listening while trying to handle message received.'
43+
+ 'It could indicate a bug in user code on message handlers. Message skipped.'
44+
)
4345

4446
def onClose(self, wasClean, code, reason):
4547
LOGGER.info('WebSocket connection closed: Code=%s, Reason=%s', str(code), reason)
4648

4749
def send_message(self, payload):
48-
return reactor.callFromThread(self.sendMessage, payload, isBinary=False, fragmentSize=None, sync=False, doNotCompress=False)
50+
return reactor.callFromThread(
51+
self.sendMessage, payload, isBinary=False, fragmentSize=None, sync=False, doNotCompress=False
52+
)
4953

5054
def send_close(self):
5155
self._manual_disconnect = True
@@ -54,6 +58,7 @@ def send_close(self):
5458

5559
class AutobahnRosBridgeClientFactory(EventEmitterMixin, ReconnectingClientFactory, WebSocketClientFactory):
5660
"""Factory to create instances of the ROS Bridge protocol built on top of Autobahn/Twisted."""
61+
5762
protocol = AutobahnRosBridgeProtocol
5863

5964
def __init__(self, *args, **kwargs):
@@ -100,8 +105,7 @@ def clientConnectionLost(self, connector, reason):
100105

101106
def clientConnectionFailed(self, connector, reason):
102107
LOGGER.debug('Connection failed. Reason: %s', reason)
103-
ReconnectingClientFactory.clientConnectionFailed(
104-
self, connector, reason)
108+
ReconnectingClientFactory.clientConnectionFailed(self, connector, reason)
105109
self._proto = None
106110

107111
@property
@@ -159,6 +163,7 @@ class TwistedEventLoopManager(object):
159163
event loop handlers that might be more fitting for different
160164
execution environments.
161165
"""
166+
162167
def __init__(self):
163168
self._log_observer = log.PythonLoggingObserver()
164169
self._log_observer.start()
@@ -238,8 +243,10 @@ def get_inner_callback(self, result_placeholder):
238243
Returns:
239244
A callable which provides result_placeholder with the result in the case of success.
240245
"""
246+
241247
def inner_callback(result):
242248
result_placeholder.callback({'result': result})
249+
243250
return inner_callback
244251

245252
def get_inner_errback(self, result_placeholder):
@@ -251,8 +258,10 @@ def get_inner_errback(self, result_placeholder):
251258
Returns:
252259
A callable which provides result_placeholder with the error in the case of failure.
253260
"""
261+
254262
def inner_errback(error):
255263
result_placeholder.callback({'exception': error})
264+
256265
return inner_errback
257266

258267
def terminate(self):

0 commit comments

Comments
 (0)