Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add rosidl_runtime_py package #34

Merged
merged 2 commits into from
Mar 28, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
24 changes: 24 additions & 0 deletions rosidl_runtime_py/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>rosidl_runtime_py</name>
<version>0.6.2</version>
<description>Runtime utilities for working with generated ROS interfaces in Python.</description>
<maintainer email="[email protected]">Jacob Perron</maintainer>
<license>Apache License 2.0</license>

<author email="[email protected]">Dirk Thomas</author>

<exec_depend>python3-numpy</exec_depend>
<exec_depend>python3-yaml</exec_depend>

<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>
<test_depend>test_msgs</test_depend>

<export>
<build_type>ament_python</build_type>
</export>
</package>
26 changes: 26 additions & 0 deletions rosidl_runtime_py/rosidl_runtime_py/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
# Copyright 2019 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from .convert import message_to_csv
from .convert import message_to_ordereddict
from .convert import message_to_yaml
from .set_message import set_message_fields


__all__ = [
'message_to_csv',
'message_to_ordereddict',
'message_to_yaml',
'set_message_fields',
]
158 changes: 158 additions & 0 deletions rosidl_runtime_py/rosidl_runtime_py/convert.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,158 @@
# Copyright 2016-2019 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import array
from collections import OrderedDict
import sys
from typing import Any

import numpy
import yaml


__yaml_representer_registered = False


# Custom representer for getting clean YAML output that preserves the order in an OrderedDict.
# Inspired by: http://stackoverflow.com/a/16782282/7169408
def __represent_ordereddict(dumper, data):
items = []
for k, v in data.items():
items.append((dumper.represent_data(k), dumper.represent_data(v)))
return yaml.nodes.MappingNode(u'tag:yaml.org,2002:map', items)


def message_to_yaml(msg: Any, truncate_length: int = None) -> str:
"""
Convert a ROS message to a YAML string.

:param msg: The ROS message to convert.
:param truncate_length: Truncate values for all message fields to this length.
This does not truncate the list of message fields.
:returns: A YAML string representation of the input ROS message.
"""
global __yaml_representer_registered

# Register our custom representer for YAML output
if not __yaml_representer_registered:
yaml.add_representer(OrderedDict, __represent_ordereddict)
__yaml_representer_registered = True

return yaml.dump(
message_to_ordereddict(msg, truncate_length=truncate_length),
width=sys.maxsize,
)


def message_to_csv(msg: Any, truncate_length: int = None) -> str:
"""
Convert a ROS message to string of comma-separated values.

:param msg: The ROS message to convert.
:param truncate_length: Truncate values for all message fields to this length.
This does not truncate the list of message fields.
:returns: A string of comma-separated values representing the input message.
"""
def to_string(val):
nonlocal truncate_length
r = ''
if any(isinstance(val, t) for t in [list, tuple, array.array, numpy.ndarray]):
for i, v in enumerate(val):
if r:
r += ','
if truncate_length is not None and i >= truncate_length:
r += '...'
break
r += to_string(v)
elif any(isinstance(val, t) for t in [bool, bytes, float, int, str, numpy.number]):
if any(isinstance(val, t) for t in [bytes, str]):
if truncate_length is not None and len(val) > truncate_length:
val = val[:truncate_length]
if isinstance(val, bytes):
val += b'...'
else:
val += '...'
r = str(val)
else:
r = message_to_csv(val, truncate_length)
return r
result = ''
# We rely on __slots__ retaining the order of the fields in the .msg file.
for field_name in msg.__slots__:
value = getattr(msg, field_name)
if result:
result += ','
result += to_string(value)
return result


# Convert a msg to an OrderedDict. We do this instead of implementing a generic __dict__() method
# in the msg because we want to preserve order of fields from the .msg file(s).
def message_to_ordereddict(msg: Any, truncate_length: int = None) -> OrderedDict:
"""
Convert a ROS message to an OrderedDict.

:param msg: The ROS message to convert.
:param truncate_length: Truncate values for all message fields to this length.
This does not truncate the list of fields (ie. the dictionary keys).
:returns: An OrderedDict where the keys are the ROS message fields and the values are
set to the values of the input message.
"""
d = OrderedDict()
# We rely on __slots__ retaining the order of the fields in the .msg file.
for field_name in msg.__slots__:
value = getattr(msg, field_name, None)
value = _convert_value(value, truncate_length=truncate_length)
# Remove leading underscore from field name
d[field_name[1:]] = value
return d


def _convert_value(value, truncate_length=None):
if isinstance(value, bytes):
if truncate_length is not None and len(value) > truncate_length:
value = ''.join([chr(c) for c in value[:truncate_length]]) + '...'
else:
value = ''.join([chr(c) for c in value])
elif isinstance(value, str):
if truncate_length is not None and len(value) > truncate_length:
value = value[:truncate_length] + '...'
elif (any(
isinstance(value, t) for t in [list, tuple, array.array, numpy.ndarray]
)):
# Since arrays and ndarrays can't contain mixed types convert to list
typename = tuple if isinstance(value, tuple) else list
if truncate_length is not None and len(value) > truncate_length:
# Truncate the sequence
value = value[:truncate_length]
# Truncate every item in the sequence
value = typename(
[_convert_value(v, truncate_length) for v in value] + ['...'])
else:
# Truncate every item in the list
value = typename(
[_convert_value(v, truncate_length) for v in value])
elif isinstance(value, dict) or isinstance(value, OrderedDict):
# Convert each key and value in the mapping
new_value = {} if isinstance(value, dict) else OrderedDict()
for k, v in value.items():
# Don't truncate keys because that could result in key collisions and data loss
new_value[_convert_value(k)] = _convert_value(v, truncate_length=truncate_length)
value = new_value
elif (
not any(isinstance(value, t) for t in (bool, float, int, numpy.number))
):
# Assuming value is a message since it is neither a collection nor a primitive type
value = message_to_ordereddict(value, truncate_length=truncate_length)
return value
36 changes: 36 additions & 0 deletions rosidl_runtime_py/rosidl_runtime_py/set_message.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
# Copyright 2017-2019 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from typing import Any
from typing import Dict


def set_message_fields(msg: Any, values: Dict[str, str]) -> None:
"""
Set the fields of a ROS message.

:param msg: The ROS message to populate.
:param values: The values to set in the ROS message. The keys of the dictionary represent
fields of the message.
:raises AttributeError: If the message does not have a field provided in the input dictionary.
:raises ValueError: If a message value does not match its field type.
"""
for field_name, field_value in values.items():
field_type = type(getattr(msg, field_name))
try:
value = field_type(field_value)
except TypeError:
value = field_type()
set_message_fields(value, field_value)
setattr(msg, field_name, value)
28 changes: 28 additions & 0 deletions rosidl_runtime_py/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
from setuptools import find_packages
from setuptools import setup

setup(
name='rosidl_runtime_py',
version='0.6.2',
packages=find_packages(exclude=['test']),
zip_safe=False,
author='Dirk Thomas',
author_email='[email protected]',
maintainer='Jacob Perron',
maintainer_email='[email protected]',
url='https://github.com/ros2/rosidl_python/tree/master/rosidl_runtime_py',
download_url='https://github.com/ros2/rosidl_python/releases',
keywords=[],
classifiers=[
'Environment :: Console',
'Intended Audience :: Developers',
'License :: OSI Approved :: Apache Software License',
'Programming Language :: Python',
],
description='Runtime utilities for working with generated ROS interfaces in Python.',
long_description=(
'This package provides functions for operations such as populating ROS messages '
'and converting messages to different representations.'),
license='Apache License, Version 2.0',
tests_require=['pytest'],
)
113 changes: 113 additions & 0 deletions rosidl_runtime_py/test/rosidl_runtime_py/test_convert.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,113 @@
# Copyright 2017-2019 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from collections import OrderedDict

from rosidl_runtime_py import message_to_csv
from rosidl_runtime_py import message_to_ordereddict
from rosidl_runtime_py import message_to_yaml
from rosidl_runtime_py.convert import _convert_value

from test_msgs import message_fixtures


def test_primitives():
# Smoke-test the formatters on a bunch of messages
msgs = []
msgs.extend(message_fixtures.get_msg_bounded_array_nested())
msgs.extend(message_fixtures.get_msg_bounded_array_primitives())
msgs.extend(message_fixtures.get_msg_builtins())
msgs.extend(message_fixtures.get_msg_dynamic_array_nested())
msgs.extend(message_fixtures.get_msg_dynamic_array_primitives())
msgs.extend(message_fixtures.get_msg_dynamic_array_primitives_nested())
msgs.extend(message_fixtures.get_msg_empty())
msgs.extend(message_fixtures.get_msg_nested())
msgs.extend(message_fixtures.get_msg_primitives())
msgs.extend(message_fixtures.get_msg_static_array_nested())
msgs.extend(message_fixtures.get_msg_static_array_primitives())
for m in msgs:
message_to_csv(m, 100)
message_to_csv(m, None)
message_to_ordereddict(m, 100)
message_to_ordereddict(m, None)
message_to_yaml(m, 100)
message_to_yaml(m, None)


def test_convert_primitives():
assert 5 == _convert_value(5)
assert 5 == _convert_value(5, truncate_length=0)
assert 5 == _convert_value(5, truncate_length=1)
assert 5 == _convert_value(5, truncate_length=10000)
assert 42.0 == _convert_value(42.0)
assert 42.0 == _convert_value(42.0, truncate_length=0)
assert 42.0 == _convert_value(42.0, truncate_length=1)
assert 42.0 == _convert_value(42.0, truncate_length=10000)
assert True is _convert_value(True)
assert True is _convert_value(True, truncate_length=0)
assert True is _convert_value(True, truncate_length=1)
assert True is _convert_value(True, truncate_length=10000)
assert False is _convert_value(False)
assert False is _convert_value(False, truncate_length=0)
assert False is _convert_value(False, truncate_length=1)
assert False is _convert_value(False, truncate_length=10000)


def test_convert_tuple():
assert (1, 2, 3) == _convert_value((1, 2, 3))
assert ('...',) == _convert_value((1, 2, 3), truncate_length=0)
assert (1, 2, '...') == _convert_value((1, 2, 3), truncate_length=2)
assert ('123', '456', '789') == _convert_value(('123', '456', '789'))
assert ('12...', '45...', '...') == _convert_value(('123', '456', '789'), truncate_length=2)
assert ('123', '456', '789') == _convert_value(('123', '456', '789'), truncate_length=5)


def test_convert_list():
assert [1, 2, 3] == _convert_value([1, 2, 3])
assert ['...'] == _convert_value([1, 2, 3], truncate_length=0)
assert [1, 2, '...'] == _convert_value([1, 2, 3], truncate_length=2)
assert ['123', '456', '789'] == _convert_value(['123', '456', '789'])
assert ['12...', '45...', '...'] == _convert_value(['123', '456', '789'], truncate_length=2)
assert ['123', '456', '789'] == _convert_value(['123', '456', '789'], truncate_length=5)


def test_convert_str():
assert 'hello world' == _convert_value('hello world')
assert 'hello...' == _convert_value('hello world', truncate_length=5)
assert 'hello world' == _convert_value('hello world', truncate_length=1000)


def test_convert_bytes():
assert 'hello world' == _convert_value(b'hello world')
assert 'hello...' == _convert_value(b'hello world', truncate_length=5)
assert 'hello world' == _convert_value(b'hello world', truncate_length=1000)


def test_convert_ordered_dict():
assert OrderedDict([(1, 'a'), ('2', 'b')]) == _convert_value(
OrderedDict([(1, 'a'), ('2', 'b')]))
assert OrderedDict([(1, 'a'), ('2', 'b')]) == _convert_value(
OrderedDict([(1, 'a'), ('2', 'b')]), truncate_length=1)
assert OrderedDict([(1, 'a'), ('2', 'b')]) == _convert_value(
OrderedDict([(1, 'a'), ('2', 'b')]), truncate_length=1000)
assert OrderedDict([(1, 'a...'), ('234', 'b...')]) == _convert_value(
OrderedDict([(1, 'abc'), ('234', 'bcd')]), truncate_length=1)


def test_convert_dict():
assert {1: 'a', '2': 'b'} == _convert_value({1: 'a', '2': 'b'})
assert {1: 'a', '2': 'b'} == _convert_value({1: 'a', '2': 'b'}, truncate_length=1)
assert {1: 'a', '2': 'b'} == _convert_value({1: 'a', '2': 'b'}, truncate_length=1000)
assert {1: 'a...', '234': 'b...'} == _convert_value(
{1: 'abc', '234': 'bcd'}, truncate_length=1)
Loading