Skip to content

Commit

Permalink
Default values should be bytestrings in python 3
Browse files Browse the repository at this point in the history
And so `chr` is also not safe. `b'\0' works fine in both versions.
  • Loading branch information
eric-wieser committed Apr 20, 2016
1 parent 29f01da commit 8e2ab04
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 6 deletions.
5 changes: 2 additions & 3 deletions src/genpy/generator.py
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,6 @@ def default_value(msg_context, field_type, default_package):
elif field_type in ['float32', 'float64']:
return '0.'
elif field_type == 'string':
# strings, char[], and uint8s are all optimized to be strings
return "''"
elif field_type == 'bool':
return 'False'
Expand All @@ -152,9 +151,9 @@ def default_value(msg_context, field_type, default_package):
if base_type in ['char', 'uint8']:
# strings, char[], and uint8s are all optimized to be strings
if array_len is not None:
return "chr(0)*%s"%array_len
return r"b'\0'*%s"%array_len
else:
return "''"
return "b''"
elif array_len is None: #var-length
return '[]'
else: # fixed-length, fill values
Expand Down
6 changes: 3 additions & 3 deletions test/test_genpy_generator.py
Original file line number Diff line number Diff line change
Expand Up @@ -156,7 +156,7 @@ def test_default_value():
assert '[]' == val, "[%s]: %s"%(t, val)
assert '[]' == default_value(msg_context, t+'[]', 'roslib')

assert "''" == default_value(msg_context, 'uint8[]', 'roslib')
assert b'' == eval(default_value(msg_context, 'uint8[]', 'roslib'))

# fixed-length arrays should be zero-filled... except for byte and uint8 which are strings
for t in ['float32', 'float64']:
Expand All @@ -166,8 +166,8 @@ def test_default_value():
assert '[0,0,0,0]' == default_value(msg_context, t+'[4]', 'std_msgs')
assert '[0]' == default_value(msg_context, t+'[1]', 'roslib')

assert "chr(0)*1" == default_value(msg_context, 'uint8[1]', 'roslib')
assert "chr(0)*4" == default_value(msg_context, 'uint8[4]', 'roslib')
assert b'\0' == eval(default_value(msg_context, 'uint8[1]', 'roslib'))
assert b'\0\0\0\0' == eval(default_value(msg_context, 'uint8[4]', 'roslib'))

assert '[]' == default_value(msg_context, 'fake_msgs/String[]', 'std_msgs')
assert '[fake_msgs.msg.String(),fake_msgs.msg.String()]' == default_value(msg_context, 'fake_msgs/String[2]', 'std_msgs')
Expand Down

0 comments on commit 8e2ab04

Please sign in to comment.