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

Improve wide string (de)serialization #113

Merged
merged 14 commits into from
Mar 20, 2024
Merged
Show file tree
Hide file tree
Changes from 7 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
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
// Copyright 2024 Proyectos y Sistemas de Mantenimiento SL (eProsima).
//
// 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.

#ifndef ROSIDL_TYPESUPPORT_FASTRTPS_C__SERIALIZATION_HELPERS_HPP_
#define ROSIDL_TYPESUPPORT_FASTRTPS_C__SERIALIZATION_HELPERS_HPP_

#include <limits>
#include <stdexcept>
#include <string>

#include "fastcdr/Cdr.h"
#include "fastcdr/exceptions/BadParamException.h"

#include "rosidl_runtime_c/u16string.h"
#include "rosidl_runtime_c/u16string_functions.h"

#include "rosidl_typesupport_fastrtps_c/visibility_control.h"

namespace rosidl_typesupport_fastrtps_c
{

inline void cdr_serialize(
eprosima::fastcdr::Cdr & cdr,
const rosidl_runtime_c__U16String & u16str)
{
if (u16str.size > std::numeric_limits<uint32_t>::max()) {
throw std::overflow_error("String length exceeds does not fit in CDR serialization format");
}
auto len = static_cast<uint32_t>(u16str.size);
clalancette marked this conversation as resolved.
Show resolved Hide resolved
cdr << len;
for (uint32_t i = 0; i < len; ++i) {
uint32_t c = static_cast<uint32_t>(u16str.data[i]);
Copy link
Contributor

Choose a reason for hiding this comment

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

Is there any particular reason to use uint32_t here? I know that rosidl_runtime_c__U16String uses uint_least16_t for the data, but on all platforms we support we have a true uint16_t. So it seems to me that we could change this to:

Suggested change
uint32_t c = static_cast<uint32_t>(u16str.data[i]);
uint16_t c = static_cast<uint16_t>(u16str.data[i]);

Copy link
Contributor Author

Choose a reason for hiding this comment

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

The main reason is interoperability / backward compatibility. The serialization of the wstring is using 4 bytes per character.

I initially did what you suggest, and used a uint16_t, but changed it when the tests in test_communication failed between rmw_cyclonedds and rmw_fastrtps for WStrings type.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Note: we can change this in the future if we don't mind breaking backward compatibility, but should do it at the same time in all DDS-based RMW implementations

Copy link
Contributor

Choose a reason for hiding this comment

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

Ah, got it. OK, interoperability is a really good reason.

In that case, I'm totally fine with leaving this as-is, but please put in a comment saying that we are using uint32_t for the interoperability reason.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

cdr << c;
}
}

inline bool cdr_deserialize(
eprosima::fastcdr::Cdr & cdr,
rosidl_runtime_c__U16String & u16str)
{
uint32_t len;
cdr >> len;
bool succeeded = rosidl_runtime_c__U16String__resize(&u16str, len);
if (!succeeded) {
return false;
}

for (uint32_t i = 0; i < len; ++i) {
uint32_t c;
cdr >> c;
if (c > std::numeric_limits<uint_least16_t>::max()) {
throw eprosima::fastcdr::exception::BadParamException("Character value exceeds maximum value");
}
u16str.data[i] = static_cast<uint_least16_t>(c);
}

return true;
}

} // namespace rosidl_typesupport_fastrtps_c

#endif // ROSIDL_TYPESUPPORT_FASTRTPS_C__SERIALIZATION_HELPERS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ header_files = [
'string',
# Provides the rosidl_typesupport_fastrtps_c__identifier symbol declaration.
'rosidl_typesupport_fastrtps_c/identifier.h',
'rosidl_typesupport_fastrtps_c/serialization_helpers.hpp',
'rosidl_typesupport_fastrtps_c/wstring_conversion.hpp',
# Provides the definition of the message_type_support_callbacks_t struct.
'rosidl_typesupport_fastrtps_cpp/message_type_support.h',
Expand Down Expand Up @@ -215,7 +216,6 @@ if isinstance(type_, AbstractNestedType):
cdr << str->data;
}
@[ elif isinstance(member.type.value_type, AbstractWString)]@
std::wstring wstr;
for (size_t i = 0; i < size; ++i) {
const rosidl_runtime_c__U16String * str = &array_ptr[i];
if (str->capacity == 0 || str->capacity <= str->size) {
Expand All @@ -226,8 +226,7 @@ if isinstance(type_, AbstractNestedType):
fprintf(stderr, "string not null-terminated\n");
return false;
}
rosidl_typesupport_fastrtps_c::u16string_to_wstring(*str, wstr);
cdr << wstr;
rosidl_typesupport_fastrtps_c::cdr_serialize(cdr, *str);
}
@[ elif isinstance(member.type.value_type, BasicType) and member.type.value_type.typename == 'wchar']@
for (size_t i = 0; i < size; ++i) {
Expand Down Expand Up @@ -260,9 +259,7 @@ if isinstance(type_, AbstractNestedType):
}
cdr << str->data;
@[ elif isinstance(member.type, AbstractWString)]@
std::wstring wstr;
rosidl_typesupport_fastrtps_c::u16string_to_wstring(ros_message->@(member.name), wstr);
cdr << wstr;
rosidl_typesupport_fastrtps_c::cdr_serialize(cdr, ros_message->@(member.name));
@[ elif isinstance(member.type, BasicType) and member.type.typename == 'boolean']@
cdr << (ros_message->@(member.name) ? true : false);
@[ elif isinstance(member.type, BasicType) and member.type.typename == 'wchar']@
Expand Down Expand Up @@ -362,8 +359,7 @@ else:
if (!ros_i.data) {
rosidl_runtime_c__U16String__init(&ros_i);
}
cdr >> wstr;
bool succeeded = rosidl_typesupport_fastrtps_c::wstring_to_u16string(wstr, ros_i);
bool succeeded = rosidl_typesupport_fastrtps_c::cdr_deserialize(cdr, ros_i);
if (!succeeded) {
fprintf(stderr, "failed to create wstring from u16string\n");
rosidl_runtime_c__U16String__fini(&ros_i);
Expand Down Expand Up @@ -410,9 +406,7 @@ else:
if (!ros_message->@(member.name).data) {
rosidl_runtime_c__U16String__init(&ros_message->@(member.name));
}
std::wstring wstr;
cdr >> wstr;
bool succeeded = rosidl_typesupport_fastrtps_c::wstring_to_u16string(wstr, ros_message->@(member.name));
bool succeeded = rosidl_typesupport_fastrtps_c::cdr_deserialize(cdr, ros_message->@(member.name));
if (!succeeded) {
fprintf(stderr, "failed to create wstring from u16string\n");
rosidl_runtime_c__U16String__fini(&ros_message->@(member.name));
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
// Copyright 2024 Proyectos y Sistemas de Mantenimiento SL (eProsima).
//
// 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.

#ifndef ROSIDL_TYPESUPPORT_FASTRTPS_CPP__SERIALIZATION_HELPERS_HPP_
#define ROSIDL_TYPESUPPORT_FASTRTPS_CPP__SERIALIZATION_HELPERS_HPP_

#include <rosidl_typesupport_fastrtps_cpp/visibility_control.h>

#include <fastcdr/Cdr.h>
#include <fastcdr/exceptions/BadParamException.h>

#include <limits>
#include <stdexcept>
#include <string>

namespace rosidl_typesupport_fastrtps_cpp
{

inline void cdr_serialize(
eprosima::fastcdr::Cdr & cdr,
const std::u16string & u16str)
{
if (u16str.size() > std::numeric_limits<uint32_t>::max()) {
throw std::overflow_error("String length exceeds does not fit in CDR serialization format");
}
auto len = static_cast<uint32_t>(u16str.size());
clalancette marked this conversation as resolved.
Show resolved Hide resolved
cdr << len;
for (uint32_t i = 0; i < len; ++i) {
uint32_t c = static_cast<uint32_t>(u16str[i]);
clalancette marked this conversation as resolved.
Show resolved Hide resolved
cdr << c;
}
}

inline bool cdr_deserialize(
eprosima::fastcdr::Cdr & cdr,
std::u16string & u16str)
{
uint32_t len;
cdr >> len;
try {
u16str.resize(len);
} catch (...) {
return false;
}
for (uint32_t i = 0; i < len; ++i) {
uint32_t c;
clalancette marked this conversation as resolved.
Show resolved Hide resolved
cdr >> c;
if (c > std::numeric_limits<std::u16string::value_type>::max()) {
throw eprosima::fastcdr::exception::BadParamException("Character value exceeds maximum value");
}
u16str[i] = static_cast<std::u16string::value_type>(c);
}

return true;
}

} // namespace rosidl_typesupport_fastrtps_cpp

#endif // ROSIDL_TYPESUPPORT_FASTRTPS_CPP__SERIALIZATION_HELPERS_HPP_
39 changes: 10 additions & 29 deletions rosidl_typesupport_fastrtps_cpp/resource/msg__type_support.cpp.em
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ header_files = [
'rosidl_typesupport_fastrtps_cpp/identifier.hpp',
'rosidl_typesupport_fastrtps_cpp/message_type_support.h',
'rosidl_typesupport_fastrtps_cpp/message_type_support_decl.hpp',
'rosidl_typesupport_fastrtps_cpp/serialization_helpers.hpp',
'rosidl_typesupport_fastrtps_cpp/wstring_conversion.hpp',
'fastcdr/Cdr.h',
]
Expand Down Expand Up @@ -105,17 +106,13 @@ cdr_serialize(
@[ if not isinstance(member.type.value_type, (NamespacedType, AbstractWString))]@
cdr << ros_message.@(member.name);
@[ else]@
@[ if isinstance(member.type.value_type, AbstractWString)]@
std::wstring wstr;
@[ end if]@
for (size_t i = 0; i < @(member.type.size); i++) {
@[ if isinstance(member.type.value_type, NamespacedType)]@
@('::'.join(member.type.value_type.namespaces))::typesupport_fastrtps_cpp::cdr_serialize(
ros_message.@(member.name)[i],
cdr);
@[ else]@
rosidl_typesupport_fastrtps_cpp::u16string_to_wstring(ros_message.@(member.name)[i], wstr);
cdr << wstr;
rosidl_typesupport_fastrtps_cpp::cdr_serialize(cdr, ros_message.@(member.name)[i]);
@[ end if]@
}
@[ end if]@
Expand All @@ -137,17 +134,13 @@ cdr_serialize(
cdr.serializeArray(&(ros_message.@(member.name)[0]), size);
}
@[ else]@
@[ if isinstance(member.type.value_type, AbstractWString)]@
std::wstring wstr;
@[ end if]@
for (size_t i = 0; i < size; i++) {
@[ if isinstance(member.type.value_type, BasicType) and member.type.value_type.typename == 'boolean']@
cdr << (ros_message.@(member.name)[i] ? true : false);
@[ elif isinstance(member.type.value_type, BasicType) and member.type.value_type.typename == 'wchar']@
cdr << static_cast<wchar_t>(ros_message.@(member.name)[i]);
@[ elif isinstance(member.type.value_type, AbstractWString)]@
rosidl_typesupport_fastrtps_cpp::u16string_to_wstring(ros_message.@(member.name)[i], wstr);
cdr << wstr;
rosidl_typesupport_fastrtps_cpp::cdr_serialize(cdr, ros_message.@(member.name)[i]);
@[ elif not isinstance(member.type.value_type, NamespacedType)]@
cdr << ros_message.@(member.name)[i];
@[ else]@
Expand All @@ -166,9 +159,7 @@ cdr_serialize(
cdr << static_cast<wchar_t>(ros_message.@(member.name));
@[ elif isinstance(member.type, AbstractWString)]@
{
std::wstring wstr;
rosidl_typesupport_fastrtps_cpp::u16string_to_wstring(ros_message.@(member.name), wstr);
cdr << wstr;
rosidl_typesupport_fastrtps_cpp::cdr_serialize(cdr, ros_message.@(member.name));
}
@[ elif not isinstance(member.type, NamespacedType)]@
cdr << ros_message.@(member.name);
Expand All @@ -195,19 +186,15 @@ cdr_deserialize(
@[ if not isinstance(member.type.value_type, (NamespacedType, AbstractWString))]@
cdr >> ros_message.@(member.name);
@[ else]@
@[ if isinstance(member.type.value_type, AbstractWString)]@
std::wstring wstr;
@[ end if]@
for (size_t i = 0; i < @(member.type.size); i++) {
@[ if isinstance(member.type.value_type, NamespacedType)]@
@('::'.join(member.type.value_type.namespaces))::typesupport_fastrtps_cpp::cdr_deserialize(
cdr,
ros_message.@(member.name)[i]);
@[ else]@
cdr >> wstr;
bool succeeded = rosidl_typesupport_fastrtps_cpp::wstring_to_u16string(wstr, ros_message.@(member.name)[i]);
bool succeeded = rosidl_typesupport_fastrtps_cpp::cdr_deserialize(cdr, ros_message.@(member.name)[i]);
if (!succeeded) {
fprintf(stderr, "failed to create wstring from u16string\n");
fprintf(stderr, "failed to deserialize u16string\n");
return false;
}
@[ end if]@
Expand All @@ -226,9 +213,6 @@ cdr_deserialize(
cdr.deserializeArray(&(ros_message.@(member.name)[0]), size);
}
@[ else]@
@[ if isinstance(member.type.value_type, AbstractWString)]@
std::wstring wstr;
@[ end if]@
for (size_t i = 0; i < size; i++) {
@[ if isinstance(member.type.value_type, BasicType) and member.type.value_type.typename == 'boolean']@
uint8_t tmp;
Expand All @@ -239,10 +223,9 @@ cdr_deserialize(
cdr >> tmp;
ros_message.@(member.name)[i] = static_cast<char16_t>(tmp);
@[ elif isinstance(member.type.value_type, AbstractWString)]@
cdr >> wstr;
bool succeeded = rosidl_typesupport_fastrtps_cpp::wstring_to_u16string(wstr, ros_message.@(member.name)[i]);
bool succeeded = rosidl_typesupport_fastrtps_cpp::cdr_deserialize(cdr, ros_message.@(member.name)[i]);
if (!succeeded) {
fprintf(stderr, "failed to create wstring from u16string\n");
fprintf(stderr, "failed to deserialize u16string\n");
return false;
}
@[ elif not isinstance(member.type.value_type, NamespacedType)]@
Expand Down Expand Up @@ -270,11 +253,9 @@ cdr_deserialize(
}
@[ elif isinstance(member.type, AbstractWString)]@
{
std::wstring wstr;
cdr >> wstr;
bool succeeded = rosidl_typesupport_fastrtps_cpp::wstring_to_u16string(wstr, ros_message.@(member.name));
bool succeeded = rosidl_typesupport_fastrtps_cpp::cdr_deserialize(cdr, ros_message.@(member.name));
if (!succeeded) {
fprintf(stderr, "failed to create wstring from u16string\n");
fprintf(stderr, "failed to deserialize u16string\n");
return false;
}
}
Expand Down