Skip to content

Commit 2acb59c

Browse files
committed
⚫ reformat tests and setup.py
1 parent 7cfeec8 commit 2acb59c

File tree

9 files changed

+111
-136
lines changed

9 files changed

+111
-136
lines changed

setup.py

Lines changed: 40 additions & 56 deletions
Original file line numberDiff line numberDiff line change
@@ -1,87 +1,71 @@
11
#!/usr/bin/env python
22
# -*- encoding: utf-8 -*-
3-
from __future__ import absolute_import
4-
from __future__ import print_function
3+
from __future__ import absolute_import, print_function
54

65
import io
76
import re
87
import sys
98
from glob import glob
10-
from os.path import abspath
11-
from os.path import basename
12-
from os.path import dirname
13-
from os.path import join
14-
from os.path import splitext
9+
from os.path import abspath, basename, dirname, join, splitext
1510

16-
from setuptools import find_packages
17-
from setuptools import setup
11+
from setuptools import find_packages, setup
1812

1913
here = abspath(dirname(__file__))
2014

2115
# If IronPython, we don't require autobahn/twisted
2216
if sys.platform == "cli":
2317
requirements = []
2418
else:
25-
requirements = [
26-
'autobahn>=17.10',
27-
'twisted>=17.9'
28-
]
19+
requirements = ["autobahn>=17.10", "twisted>=17.9"]
2920

3021

3122
def read(*names, **kwargs):
32-
return io.open(
33-
join(here, *names),
34-
encoding=kwargs.get('encoding', 'utf8')
35-
).read()
23+
return io.open(join(here, *names), encoding=kwargs.get("encoding", "utf8")).read()
3624

3725

3826
about = {}
39-
exec(read('src', 'roslibpy', '__version__.py'), about)
27+
exec(read("src", "roslibpy", "__version__.py"), about)
4028

4129
setup(
42-
name=about['__title__'],
43-
version=about['__version__'],
44-
license=about['__license__'],
45-
description=about['__description__'],
46-
author=about['__author__'],
47-
author_email=about['__author_email__'],
48-
url=about['__url__'],
49-
long_description='%s\n%s' % (
50-
re.compile('^.. start-badges.*^.. end-badges', re.M |
51-
re.S).sub('', read('README.rst')),
52-
re.sub(':[a-z]+:`~?(.*?)`', r'``\1``', read('CHANGELOG.rst'))
30+
name=about["__title__"],
31+
version=about["__version__"],
32+
license=about["__license__"],
33+
description=about["__description__"],
34+
author=about["__author__"],
35+
author_email=about["__author_email__"],
36+
url=about["__url__"],
37+
long_description="%s\n%s"
38+
% (
39+
re.compile("^.. start-badges.*^.. end-badges", re.M | re.S).sub("", read("README.rst")),
40+
re.sub(":[a-z]+:`~?(.*?)`", r"``\1``", read("CHANGELOG.rst")),
5341
),
54-
packages=find_packages('src'),
55-
package_dir={'': 'src'},
56-
py_modules=[splitext(basename(path))[0] for path in glob('src/*.py')],
42+
packages=find_packages("src"),
43+
package_dir={"": "src"},
44+
py_modules=[splitext(basename(path))[0] for path in glob("src/*.py")],
5745
include_package_data=True,
5846
zip_safe=False,
5947
classifiers=[
60-
'Development Status :: 4 - Beta',
61-
'Intended Audience :: Developers',
62-
'Intended Audience :: Science/Research',
63-
'License :: OSI Approved :: MIT License',
64-
'Operating System :: Unix',
65-
'Operating System :: POSIX',
66-
'Operating System :: Microsoft :: Windows',
67-
'Programming Language :: Python',
68-
'Programming Language :: Python :: 3',
69-
'Programming Language :: Python :: 3.3',
70-
'Programming Language :: Python :: 3.4',
71-
'Programming Language :: Python :: 3.5',
72-
'Programming Language :: Python :: 3.6',
73-
'Programming Language :: Python :: 3.7',
74-
'Programming Language :: Python :: 3.8',
75-
'Programming Language :: Python :: Implementation :: CPython',
76-
'Programming Language :: Python :: Implementation :: IronPython',
77-
'Topic :: Scientific/Engineering',
48+
"Development Status :: 4 - Beta",
49+
"Intended Audience :: Developers",
50+
"Intended Audience :: Science/Research",
51+
"License :: OSI Approved :: MIT License",
52+
"Operating System :: Unix",
53+
"Operating System :: POSIX",
54+
"Operating System :: Microsoft :: Windows",
55+
"Programming Language :: Python",
56+
"Programming Language :: Python :: 3",
57+
"Programming Language :: Python :: 3.3",
58+
"Programming Language :: Python :: 3.4",
59+
"Programming Language :: Python :: 3.5",
60+
"Programming Language :: Python :: 3.6",
61+
"Programming Language :: Python :: 3.7",
62+
"Programming Language :: Python :: 3.8",
63+
"Programming Language :: Python :: Implementation :: CPython",
64+
"Programming Language :: Python :: Implementation :: IronPython",
65+
"Topic :: Scientific/Engineering",
7866
],
79-
keywords=['ros', 'ros-bridge', 'robotics', 'websockets'],
67+
keywords=["ros", "ros-bridge", "robotics", "websockets"],
8068
install_requires=requirements,
8169
extras_require={},
82-
entry_points={
83-
'console_scripts': [
84-
'roslibpy=roslibpy.__main__:main'
85-
]
86-
},
70+
entry_points={"console_scripts": ["roslibpy=roslibpy.__main__:main"]},
8771
)

tests/ipy_test_runner.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,5 +14,5 @@
1414

1515
HERE = os.path.dirname(__file__)
1616

17-
if __name__ == '__main__':
17+
if __name__ == "__main__":
1818
pytest.run(HERE)

tests/test_core.py

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,6 @@
11
import pytest
22

3-
from roslibpy import Header
4-
from roslibpy import Time
3+
from roslibpy import Header, Time
54

65
REF_FLOAT_SECS_TIME = 1610122759.677662
76

@@ -29,16 +28,16 @@ def test_is_zero():
2928

3029
def test_header_ctor_supports_time():
3130
header = Header(seq=1, stamp=Time.from_sec(REF_FLOAT_SECS_TIME))
32-
assert header['stamp']['secs'] == 1610122759
33-
assert header['stamp']['secs'] == header['stamp'].secs
34-
assert header['stamp'].to_sec() == REF_FLOAT_SECS_TIME
31+
assert header["stamp"]["secs"] == 1610122759
32+
assert header["stamp"]["secs"] == header["stamp"].secs
33+
assert header["stamp"].to_sec() == REF_FLOAT_SECS_TIME
3534

3635

3736
def test_header_ctor_supports_dict():
3837
header = Header(seq=1, stamp=dict(secs=1610122759, nsecs=677661895))
39-
assert header['stamp']['secs'] == 1610122759
40-
assert header['stamp']['secs'] == header['stamp'].secs
41-
assert header['stamp'].to_sec() == REF_FLOAT_SECS_TIME
38+
assert header["stamp"]["secs"] == 1610122759
39+
assert header["stamp"]["secs"] == header["stamp"].secs
40+
assert header["stamp"].to_sec() == REF_FLOAT_SECS_TIME
4241

4342

4443
def test_time_accepts_only_ints():

tests/test_param.py

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,15 @@
1-
from roslibpy import Param
2-
from roslibpy import Ros
1+
from roslibpy import Param, Ros
32

43

54
def test_param_manipulation():
6-
ros = Ros('127.0.0.1', 9090)
5+
ros = Ros("127.0.0.1", 9090)
76
ros.run()
87

9-
param = Param(ros, 'test_param')
8+
param = Param(ros, "test_param")
109
assert param.get() is None
1110

12-
param.set('test_value')
13-
assert param.get() == 'test_value'
11+
param.set("test_value")
12+
assert param.get() == "test_value"
1413

1514
param.delete()
1615
assert param.get() is None

tests/test_ros.py

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -5,9 +5,9 @@
55

66
from roslibpy import Ros
77

8-
host = '127.0.0.1'
8+
host = "127.0.0.1"
99
port = 9090
10-
url = u'ws://%s:%d' % (host, port)
10+
url = "ws://%s:%d" % (host, port)
1111

1212

1313
def test_reconnect_does_not_trigger_on_client_close():
@@ -17,7 +17,7 @@ def test_reconnect_does_not_trigger_on_client_close():
1717
assert ros.is_connected, "ROS initially connected"
1818
time.sleep(0.5)
1919
event = threading.Event()
20-
ros.on('close', lambda m: event.set())
20+
ros.on("close", lambda m: event.set())
2121
ros.close()
2222
event.wait(5)
2323

@@ -45,16 +45,16 @@ def test_closing_event():
4545
ctx = dict(closing_event_called=False, was_still_connected=False)
4646

4747
def handle_closing():
48-
ctx['closing_event_called'] = True
49-
ctx['was_still_connected'] = ros.is_connected
48+
ctx["closing_event_called"] = True
49+
ctx["was_still_connected"] = ros.is_connected
5050
time.sleep(1.5)
5151

5252
ts_start = time.time()
53-
ros.on('closing', handle_closing)
53+
ros.on("closing", handle_closing)
5454
ros.close()
5555
ts_end = time.time()
5656
closing_was_handled_synchronously_before_close = ts_end - ts_start >= 1.5
5757

58-
assert ctx['closing_event_called']
59-
assert ctx['was_still_connected']
58+
assert ctx["closing_event_called"]
59+
assert ctx["was_still_connected"]
6060
assert closing_was_handled_synchronously_before_close

tests/test_rosapi.py

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -4,9 +4,9 @@
44

55
from roslibpy import Ros
66

7-
host = '127.0.0.1'
7+
host = "127.0.0.1"
88
port = 9090
9-
url = u'ws://%s:%d' % (host, port)
9+
url = "ws://%s:%d" % (host, port)
1010

1111

1212
def test_rosapi_topics():
@@ -15,14 +15,14 @@ def test_rosapi_topics():
1515
ros.run()
1616

1717
def callback(topic_list):
18-
context['result'] = topic_list
19-
context['wait'].set()
18+
context["result"] = topic_list
19+
context["wait"].set()
2020

2121
ros.get_topics(callback)
22-
if not context['wait'].wait(5):
22+
if not context["wait"].wait(5):
2323
raise Exception
2424

25-
assert('/rosout' in context['result']['topics'])
25+
assert "/rosout" in context["result"]["topics"]
2626
ros.close()
2727

2828

@@ -32,7 +32,7 @@ def test_rosapi_topics_blocking():
3232
topic_list = ros.get_topics()
3333

3434
print(topic_list)
35-
assert('/rosout' in topic_list)
35+
assert "/rosout" in topic_list
3636

3737
ros.close()
3838

@@ -44,4 +44,4 @@ def test_connection_fails_when_missing_port():
4444

4545
def test_connection_fails_when_schema_not_ws():
4646
with pytest.raises(Exception):
47-
Ros(u'http://%s:%d' % (host, port))
47+
Ros("http://%s:%d" % (host, port))

tests/test_service.py

Lines changed: 10 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -2,44 +2,42 @@
22

33
import time
44

5-
from roslibpy import Ros
6-
from roslibpy import Service
7-
from roslibpy import ServiceRequest
5+
from roslibpy import Ros, Service, ServiceRequest
86

97

108
def test_add_two_ints_service():
11-
ros = Ros('127.0.0.1', 9090)
9+
ros = Ros("127.0.0.1", 9090)
1210
ros.run()
1311

1412
def add_two_ints(request, response):
15-
response['sum'] = request['a'] + request['b']
13+
response["sum"] = request["a"] + request["b"]
1614

1715
return False
1816

19-
service_name = '/test_sum_service'
20-
service_type = 'rospy_tutorials/AddTwoInts'
17+
service_name = "/test_sum_service"
18+
service_type = "rospy_tutorials/AddTwoInts"
2119
service = Service(ros, service_name, service_type)
2220
service.advertise(add_two_ints)
2321
time.sleep(1)
2422

2523
client = Service(ros, service_name, service_type)
26-
result = client.call(ServiceRequest({'a': 2, 'b': 40}))
27-
assert(result['sum'] == 42)
24+
result = client.call(ServiceRequest({"a": 2, "b": 40}))
25+
assert result["sum"] == 42
2826

2927
service.unadvertise()
3028
time.sleep(2)
3129
ros.close()
3230

3331

3432
def test_empty_service():
35-
ros = Ros('127.0.0.1', 9090)
33+
ros = Ros("127.0.0.1", 9090)
3634
ros.run()
3735

38-
service = Service(ros, '/test_empty_service', 'std_srvs/Empty')
36+
service = Service(ros, "/test_empty_service", "std_srvs/Empty")
3937
service.advertise(lambda req, resp: True)
4038
time.sleep(1)
4139

42-
client = Service(ros, '/test_empty_service', 'std_srvs/Empty')
40+
client = Service(ros, "/test_empty_service", "std_srvs/Empty")
4341
client.call(ServiceRequest())
4442

4543
service.unadvertise()

tests/test_tf.py

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -6,21 +6,21 @@
66

77
def test_tf_test():
88
context = dict(wait=threading.Event(), counter=0)
9-
ros = Ros('127.0.0.1', 9090)
9+
ros = Ros("127.0.0.1", 9090)
1010
ros.run()
1111

12-
tf_client = TFClient(ros, fixed_frame='world')
12+
tf_client = TFClient(ros, fixed_frame="world")
1313

1414
def callback(message):
15-
context['message'] = message
16-
context['counter'] += 1
17-
context['wait'].set()
15+
context["message"] = message
16+
context["counter"] += 1
17+
context["wait"].set()
1818

19-
tf_client.subscribe(frame_id='/world', callback=callback)
20-
if not context['wait'].wait(5):
19+
tf_client.subscribe(frame_id="/world", callback=callback)
20+
if not context["wait"].wait(5):
2121
raise Exception
2222

23-
assert context['counter'] > 0
24-
assert context['message']['translation'] == dict(x=0.0, y=0.0, z=0.0), 'Unexpected translation received'
25-
assert context['message']['rotation'] == dict(x=0.0, y=0.0, z=0.0, w=1.0), 'Unexpected rotation received'
23+
assert context["counter"] > 0
24+
assert context["message"]["translation"] == dict(x=0.0, y=0.0, z=0.0), "Unexpected translation received"
25+
assert context["message"]["rotation"] == dict(x=0.0, y=0.0, z=0.0, w=1.0), "Unexpected rotation received"
2626
ros.close()

0 commit comments

Comments
 (0)