Skip to content

fix(set_message): encode strings if field is bytes #30

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

Open
wants to merge 3 commits into
base: rolling
Choose a base branch
from
Open
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
8 changes: 6 additions & 2 deletions rosidl_runtime_py/set_message.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@


def set_message_fields(
msg: Any, values: Dict[str, str], expand_header_auto: bool = False,
msg: Any, values: Dict[str, Any], expand_header_auto: bool = False,
expand_time_now: bool = False) -> List[Any]:
"""
Set the fields of a ROS message.
Expand All @@ -52,7 +52,7 @@ def set_message_fields(
timestamp_fields = []

def set_message_fields_internal(
msg: Any, values: Dict[str, str],
msg: Any, values: Dict[str, Any],
timestamp_fields: List[Any]) -> List[Any]:
try:
items = values.items()
Expand All @@ -70,6 +70,10 @@ def set_message_fields_internal(
value = numpy.array(field_value, dtype=field.dtype)
elif type(field_value) is field_type:
value = field_value
elif field_type is bytes and type(field_value) is str:
# value = field_value.encode()
value = bytes([ord(c) for c in field_value])
# value = bytes(field_value, 'ascii', 'backslashreplace')
# We can't import these types directly, so we use the qualified class name to
# distinguish them from other fields
elif qualified_class_name == 'std_msgs.msg._header.Header' and \
Expand Down
15 changes: 14 additions & 1 deletion test/rosidl_runtime_py/test_set_message.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,12 @@

import builtins
import copy
import yaml

from builtin_interfaces.msg import Time
import pytest
import rosidl_parser.definition
from rosidl_runtime_py import set_message_fields
from rosidl_runtime_py import set_message_fields, message_to_yaml
from std_msgs.msg import Header
from test_msgs import message_fixtures

Expand Down Expand Up @@ -140,6 +141,18 @@ def test_set_message_fields_partial():
assert getattr(modified_msg, attr) == getattr(original_msg, attr)


def test_set_message_fields_from_yaml():
original_msg = message_fixtures.get_msg_basic_types()[1]
original_yaml = message_to_yaml(original_msg)
values = yaml.safe_load(original_yaml)

modified_msg = copy.copy(message_fixtures.get_msg_basic_types()[0])
set_message_fields(modified_msg, values)

for attr in original_msg.get_fields_and_field_types().keys():
assert getattr(modified_msg, attr) == getattr(original_msg, attr)


def test_set_message_fields_full():
msg_list = message_fixtures.get_msg_basic_types()
msg0 = msg_list[0]
Expand Down