Skip to content

Commit a5b9b30

Browse files
committed
Add the ROS tests, fix initial failures they caught
1 parent d16c3bf commit a5b9b30

File tree

5 files changed

+119
-47
lines changed

5 files changed

+119
-47
lines changed

open_sound_control_bridge/launch/osc_bridge.launch.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424
ARGUMENTS = [
2525
DeclareLaunchArgument(
2626
'osc_config',
27-
default_value=f'{get_package_share_directory("open_sound_control_bridge")}/config/example_config.yaml',
27+
default_value=f'{get_package_share_directory("open_sound_control_bridge")}/config/example_config.yaml', # noqa: E501
2828
description='Path to the OSC bridge configuration file',
2929
),
3030
DeclareLaunchArgument(

open_sound_control_bridge/open_sound_control_bridge/osc_bridge.py

Lines changed: 45 additions & 46 deletions
Original file line numberDiff line numberDiff line change
@@ -12,16 +12,20 @@
1212
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
1313
# See the License for the specific language governing permissions and
1414
# limitations under the License.
15-
16-
from ament_index_python.packages import get_package_share_directory
1715
import argparse
1816
import datetime
1917
import importlib
18+
import socket
19+
import struct
20+
import threading
21+
22+
from ament_index_python.packages import get_package_share_directory
23+
2024
from open_sound_control_msgs.msg import OscBlob, OscMessage
25+
2126
import rclpy
2227
from rclpy.node import Node
2328
from rclpy.qos import qos_profile_sensor_data
24-
import socket
2529
from std_msgs.msg import (
2630
Bool,
2731
ByteMultiArray,
@@ -33,33 +37,30 @@
3337
Int32,
3438
String,
3539
)
36-
import struct
37-
import threading
3840
import yaml
3941

40-
4142
epoch_ref = datetime.datetime(
42-
year = 1970,
43-
month = 1,
44-
day = 1,
45-
hour = 0,
46-
minute = 0,
47-
second = 0
43+
year=1970,
44+
month=1,
45+
day=1,
46+
hour=0,
47+
minute=0,
48+
second=0
4849
)
4950

5051
ntp_ref = datetime.datetime(
51-
year = 1900,
52-
month = 1,
53-
day = 1,
54-
hour = 0,
55-
minute = 0,
56-
second = 0
52+
year=1900,
53+
month=1,
54+
day=1,
55+
hour=0,
56+
minute=0,
57+
second=0
5758
)
5859

5960

6061
def ros_time_2_ntp_time(ros_time: rclpy.time.Time) -> float:
6162
"""
62-
Convert a ROS timestamp (linux epoch time) to NTP time
63+
Convert a ROS timestamp (linux epoch time) to NTP time.
6364
6465
@param ros_time The ROS timestamp to convert
6566
@return The elapsed seconds since 1 Jan 1900 00:00:00
@@ -74,21 +75,21 @@ def ros_time_2_ntp_time(ros_time: rclpy.time.Time) -> float:
7475

7576
def ntp_time_2_ros_time(ntp_time: float) -> rclpy.time.Time:
7677
"""
77-
Convert an NTP timestamp to a ROS timestamp
78+
Convert an NTP timestamp to a ROS timestamp.
7879
7980
@param ntp_time The number of seconds elapsed since Jan 1, 1900 00:00:00
8081
"""
8182
ntp_delta = datetime.timedelta(seconds=ntp_time)
8283
now = ntp_ref + ntp_delta
8384
epoch_delta = now - epoch_ref
8485
return rclpy.time.Time(
85-
nanoseconds = epoch_delta.total_seconds() * 1000000000
86+
nanoseconds=epoch_delta.total_seconds() * 1000000000
8687
)
8788

8889

8990
class Ros2OscRelay:
9091
"""
91-
Helper class that converts ROS data to OSC data
92+
Helper class that converts ROS data to OSC data.
9293
9394
The OscBridgeNode creates one of these for every listener topic defined in the config
9495
"""
@@ -104,7 +105,7 @@ def __init__(
104105
osc_type: str = None,
105106
):
106107
"""
107-
Create the ROS to OSC relay
108+
Create the ROS to OSC relay.
108109
109110
@param node The ROS node that owns this relay
110111
@param ros_topic The ROS topic we're subscribing to
@@ -152,7 +153,7 @@ def __init__(
152153

153154
def ros_callback(self, data):
154155
"""
155-
Callback function for receiving data on our ROS topic
156+
Process the incoming ROS message & republish it as an OSC message.
156157
157158
We convert the ROS data to its equivalent OSC packet and send it over
158159
our UDP socket to the specified destination. This being UDP there's no
@@ -165,9 +166,7 @@ def ros_callback(self, data):
165166
t = type(data)
166167

167168
def word_align(arr):
168-
"""
169-
Pad osc_data with extra null characters so it's 32-bit aligned
170-
"""
169+
"""Pad osc_data with extra null characters so it's 32-bit aligned."""
171170
for i in range((4 - (len(arr) % 4)) % 4):
172171
arr.append(0)
173172

@@ -271,6 +270,7 @@ def word_align(arr):
271270
msg = bytearray(osc_header)
272271
self.udp_socket.sendto(msg, (self.dest_ip, self.udp_port))
273272

273+
274274
class OscBridgeNode(Node):
275275
def __init__(
276276
self,
@@ -290,7 +290,7 @@ def __init__(
290290
)
291291
self.udp_socket.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
292292
self.udp_socket.settimeout(1)
293-
addr = socket.getaddrinfo("0.0.0.0", self.udp_port)[0][-1]
293+
addr = socket.getaddrinfo('0.0.0.0', self.udp_port)[0][-1]
294294
self.udp_socket.bind(addr)
295295

296296
# keep a dictionary of OSC -> ROS republishers keyed by their ROS topic name
@@ -313,20 +313,20 @@ def shutdown(self, *, context=None):
313313
super().shutdown(context=context)
314314

315315
def parse_config(self) -> None:
316-
"""Read the configuration file & create the ROS topic subscribers"""
316+
"""Read the configuration file & create the ROS topic subscribers."""
317317
try:
318318
with open(self.config_path, 'r') as yaml_in:
319319
cfg = yaml.load(yaml_in, yaml.SafeLoader)
320320
listeners = cfg.get('listeners', [])
321321

322322
self.ros_to_osc_subs = []
323-
for l in listeners:
324-
tstring = l['type']
323+
for listener in listeners:
324+
tstring = listener['type']
325325
parts = tstring.split('/')
326326
module = f'{parts[0]}.{parts[1]}'
327327
msg_name = parts[2]
328328
msg_type = getattr(importlib.import_module(module), msg_name)
329-
topic = l['topic']
329+
topic = listener['topic']
330330
self.get_logger().info(
331331
f'Creating subscriber {topic} ({msg_type})'
332332
)
@@ -335,14 +335,14 @@ def parse_config(self) -> None:
335335
self,
336336
topic,
337337
msg_type,
338-
l['osc_address'],
339-
l['host'],
340-
l['port'],
341-
osc_type=l.get('osc_type', None),
338+
listener['osc_address'],
339+
listener['host'],
340+
listener['port'],
341+
osc_type=listener.get('osc_type', None),
342342
)
343343
self.ros_to_osc_subs.append(sub)
344344
except KeyError as err:
345-
self.get_logger().warning(f'Failed to create subscriber: missing config key "{err}". Skipping.')
345+
self.get_logger().warning(f'Failed to create subscriber: missing config key "{err}". Skipping.') # noqa: E501
346346

347347
except Exception as err:
348348
self.get_logger().error(f'Failed to read config file {self.config_path}: {err}')
@@ -355,20 +355,20 @@ def read_socket(self):
355355
self.raw_publisher.publish(msg)
356356
except ValueError as err:
357357
self.get_logger().warning(f'Rejected packet: {err}')
358-
except OSError as err:
358+
except OSError:
359359
pass
360360
except Exception as err:
361361
self.get_logger().warning(f'Failed to process packet: {err}')
362362

363363
def osc2ros(self, osc_packet: bytes) -> OscMessage:
364364
"""
365-
Convert a raw OSC packet into its equivalent ROS message
365+
Convert a raw OSC packet into its equivalent ROS message.
366366
367367
@param osc_packet The raw byte data received from the socket
368368
"""
369369
def align_next_word(n):
370370
"""
371-
Return the index of the next word-alined byte
371+
Return the index of the next word-alined byte.
372372
373373
We assume 4-byte/32-bit words. If we're already word-aligned,
374374
we increment to the next one
@@ -383,8 +383,8 @@ def align_next_word(n):
383383

384384
address_end = osc_packet.index(b'\0', 0)
385385
msg.address = osc_packet[0:address_end].decode('utf-8')
386-
if msg.address.endswith("/"):
387-
msg.address = msg.address.rstrip("/")
386+
if msg.address.endswith('/'):
387+
msg.address = msg.address.rstrip('/')
388388

389389
type_start = osc_packet.index(b',', address_end)
390390
type_end = osc_packet.index(b'\0', type_start)
@@ -542,7 +542,7 @@ def align_next_word(n):
542542
elif t == OscMessage.B_TRUE or t == OscMessage.B_FALSE:
543543
ros_type = Bool
544544
# use a shared counter for both T and F
545-
ros_topic = f'{msg.address}/bool_{topic_counters['T_F']}'
545+
ros_topic = f'{msg.address}/bool_{topic_counters["T_F"]}'
546546
ros_value = Bool()
547547
if t == OscMessage.B_TRUE:
548548
ros_value.data = True
@@ -572,7 +572,7 @@ def align_next_word(n):
572572

573573
def sanitize_ros_topic(self, t: str):
574574
"""
575-
Sanitize the generated ROS topic
575+
Sanitize the generated ROS topic.
576576
577577
OSC allows leading integers, non-letter characters, etc... that are not compatible
578578
with ROS.
@@ -601,9 +601,8 @@ def sanitize_ros_topic(self, t: str):
601601
return '/'.join(ns)
602602

603603

604-
605604
def main():
606-
default_cfg = f'{get_package_share_directory("open_sound_control_bridge")}/config/example_config.yaml'
605+
default_cfg = f'{get_package_share_directory("open_sound_control_bridge")}/config/example_config.yaml' # noqa: E501
607606

608607
parser = argparse.ArgumentParser()
609608
parser.add_argument(
Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
# Copyright 2015 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
from ament_copyright.main import main
16+
import pytest
17+
18+
19+
# Remove the `skip` decorator once the source file(s) have a copyright header
20+
@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
21+
@pytest.mark.copyright
22+
@pytest.mark.linter
23+
def test_copyright():
24+
rc = main(argv=['.', 'test'])
25+
assert rc == 0, 'Found errors'
Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
# Copyright 2017 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
from ament_flake8.main import main_with_errors
16+
import pytest
17+
18+
19+
@pytest.mark.flake8
20+
@pytest.mark.linter
21+
def test_flake8():
22+
rc, errors = main_with_errors(argv=[])
23+
assert rc == 0, \
24+
'Found %d code style errors / warnings:\n' % len(errors) + \
25+
'\n'.join(errors)
Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
# Copyright 2015 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
from ament_pep257.main import main
16+
import pytest
17+
18+
19+
@pytest.mark.linter
20+
@pytest.mark.pep257
21+
def test_pep257():
22+
rc = main(argv=['.', 'test'])
23+
assert rc == 0, 'Found code style errors / warnings'

0 commit comments

Comments
 (0)