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

Fix echo sometimes printing ..... #135

Merged
merged 1 commit into from
Aug 16, 2018
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
47 changes: 19 additions & 28 deletions ros2topic/ros2topic/verb/echo.py
Original file line number Diff line number Diff line change
Expand Up @@ -208,40 +208,31 @@ def msg_to_ordereddict(msg, truncate_length=None):


def _convert_value(value, truncate_length=None):
if any(isinstance(value, t) for t in (bytes, list, str, tuple)):
# truncate value if requested
if isinstance(value, bytes):
if truncate_length is not None and len(value) > truncate_length:
value = value[:truncate_length]
if any(isinstance(value, t) for t in [list, tuple]):
value.append('...')
elif isinstance(value, bytes):
value += b'...'
elif isinstance(value, str):
value += '...'
else:
assert False

if any(isinstance(value, t) for t in (dict, OrderedDict)):
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 isinstance(value, tuple) or isinstance(value, 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 = type(value)([_convert_value(v, truncate_length) for v in value] + ['...'])
else:
# Truncate every item in the list
value = type(value)([_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():
new_value[_convert_value(k)] = _convert_value(
new_value[_convert_value(k, truncate_length=truncate_length)] = _convert_value(
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I do see a major problem with this change: the keys in dictionary are now also being truncated which was not the case before. This will potentially lead to different keys being reduce to the same shortened key and therefore "loose" data.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

good point !

v, truncate_length=truncate_length)
value = new_value

elif any(isinstance(value, t) for t in (list, tuple)):
# convert each item in the array
value = [_convert_value(v, truncate_length=truncate_length) for v in value]
if isinstance(value, tuple):
value = tuple(value)

elif isinstance(value, bytes):
# show string representation of bytes
value = str(value)

elif not any(isinstance(value, t) for t in (
bool, bytes, float, int, str
)):
elif not any(isinstance(value, t) for t in (bool, float, int)):
# assuming value is a message
# since it is neither a collection nor a primitive type
value = msg_to_ordereddict(value, truncate_length=truncate_length)
Expand Down
85 changes: 85 additions & 0 deletions ros2topic/test/test_echo.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,85 @@
# Copyright 2018 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 ros2topic.verb.echo import _convert_value


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...'), ('2...', '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...', '2...': 'b...'} == _convert_value(
{1: 'abc', '234': 'bcd'}, truncate_length=1)