Skip to content

Commit

Permalink
Improve wide string (de)serialization (ros2#113)
Browse files Browse the repository at this point in the history
* Added serialization helpers for char16_t strings in rosidl_typesupport_fastrtps_c.

* Change generated code in rosidl_typesupport_fastrtps_c

* Added serialization helpers for char16_t strings in rosidl_typesupport_fastrtps_cpp.

* Change generated code in rosidl_typesupport_fastrtps_cpp

* Throw overflow_error when size does not fit.

* Throw exception when deserialized char is too big.

* Deprecate unused methods

* Fix dependency on fastcdr

Signed-off-by: Miguel Company <[email protected]>
  • Loading branch information
MiguelCompany authored Mar 20, 2024
1 parent 0d4b6d6 commit b4f63c0
Show file tree
Hide file tree
Showing 13 changed files with 301 additions and 103 deletions.
3 changes: 3 additions & 0 deletions rosidl_typesupport_fastrtps_c/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,10 @@ endif()

find_package(ament_cmake_python REQUIRED)
find_package(rosidl_runtime_c REQUIRED)
find_package(fastcdr REQUIRED CONFIG)

ament_export_dependencies(rosidl_runtime_c)
ament_export_dependencies(fastcdr)

ament_python_install_package(${PROJECT_NAME})

Expand All @@ -49,6 +51,7 @@ target_include_directories(${PROJECT_NAME} PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
target_link_libraries(${PROJECT_NAME} PUBLIC
fastcdr
rosidl_runtime_c::rosidl_runtime_c)

# Export old-style CMake variables
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
// 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);
cdr << len;
for (uint32_t i = 0; i < len; ++i) {
// We are serializing a uint32_t for interoperability with other DDS-based implementations.
// We might change this to a uint16_t in the future if we don't mind breaking backward
// compatibility and we make the change for all the supported DDS implementations at the same
// time.
uint32_t c = static_cast<uint32_t>(u16str.data[i]);
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) {
// We are serializing a uint32_t for interoperability with other DDS-based implementations.
// If we change this to a uint16_t in the future, we could remove the check below, since all
// serialized values would fit in the destination type.
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 @@ -17,6 +17,7 @@

#include <string>

#include "rcutils/macros.h"
#include "rosidl_runtime_c/u16string.h"
#include "rosidl_typesupport_fastrtps_c/visibility_control.h"

Expand All @@ -29,6 +30,7 @@ namespace rosidl_typesupport_fastrtps_c
* \param[in,out] wstr The std::wstring to copy to.
*/
ROSIDL_TYPESUPPORT_FASTRTPS_C_PUBLIC
RCUTILS_DEPRECATED_WITH_MSG("not used by core packages")
void u16string_to_wstring(
const rosidl_runtime_c__U16String & u16str, std::wstring & wstr);

Expand All @@ -39,6 +41,7 @@ void u16string_to_wstring(
* \return true if resizing u16str and assignment succeeded, otherwise false.
*/
ROSIDL_TYPESUPPORT_FASTRTPS_C_PUBLIC
RCUTILS_DEPRECATED_WITH_MSG("not used by core packages")
bool wstring_to_u16string(
const std::wstring & wstr, rosidl_runtime_c__U16String & u16str);

Expand Down
16 changes: 5 additions & 11 deletions rosidl_typesupport_fastrtps_c/resource/msg__type_support_c.cpp.em
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
Expand Up @@ -14,12 +14,13 @@

#include <string>

#include "fastcdr/Cdr.h"
#include "rcutils/macros.h"

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

#include "rosidl_typesupport_fastrtps_c/wstring_conversion.hpp"
#include "rosidl_typesupport_fastrtps_c/serialization_helpers.hpp"

#include "performance_test_fixture/performance_test_fixture.hpp"

Expand All @@ -32,7 +33,13 @@ constexpr const uint64_t kSize = 1024;

BENCHMARK_F(PerformanceTest, wstring_to_u16string)(benchmark::State & st)
{
namespace fastcdr = eprosima::fastcdr;

std::wstring wstring(kSize, '*');
char raw_buffer[kSize * 4 + 4]; // 4 bytes per character + 4 bytes for the length
fastcdr::FastBuffer buffer(raw_buffer, sizeof(raw_buffer));
fastcdr::Cdr cdr(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::Cdr::DDS_CDR);
cdr << wstring;

rosidl_runtime_c__U16String s;
if (!rosidl_runtime_c__U16String__init(&s)) {
Expand All @@ -44,15 +51,22 @@ BENCHMARK_F(PerformanceTest, wstring_to_u16string)(benchmark::State & st)

for (auto _ : st) {
RCUTILS_UNUSED(_);
rosidl_typesupport_fastrtps_c::wstring_to_u16string(wstring, s);
cdr.reset();
rosidl_typesupport_fastrtps_c::cdr_deserialize(cdr, s);
}

rosidl_runtime_c__U16String__fini(&s);
}

BENCHMARK_F(PerformanceTest, u16string_to_wstring)(benchmark::State & st)
{
namespace fastcdr = eprosima::fastcdr;

std::wstring data(kSize, '*');
char raw_buffer[kSize * 4 + 4]; // 4 bytes per character + 4 bytes for the length
fastcdr::FastBuffer buffer(raw_buffer, sizeof(raw_buffer));
fastcdr::Cdr cdr(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::Cdr::DDS_CDR);
cdr << data;

rosidl_runtime_c__U16String s;
if (!rosidl_runtime_c__U16String__init(&s)) {
Expand All @@ -61,14 +75,15 @@ BENCHMARK_F(PerformanceTest, u16string_to_wstring)(benchmark::State & st)
}

// Just do a copy
rosidl_typesupport_fastrtps_c::wstring_to_u16string(data, s);
cdr.reset();
rosidl_typesupport_fastrtps_c::cdr_deserialize(cdr, s);

reset_heap_counters();

for (auto _ : st) {
RCUTILS_UNUSED(_);
std::wstring actual;
rosidl_typesupport_fastrtps_c::u16string_to_wstring(s, actual);
cdr.reset();
rosidl_typesupport_fastrtps_c::cdr_serialize(cdr, s);
}

rosidl_runtime_c__U16String__fini(&s);
Expand Down
53 changes: 28 additions & 25 deletions rosidl_typesupport_fastrtps_c/test/test_wstring_conversion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,37 +16,43 @@

#include "gtest/gtest.h"

#include "fastcdr/Cdr.h"
#include "rosidl_runtime_c/u16string_functions.h"
#include "osrf_testing_tools_cpp/scope_exit.hpp"

#include "rosidl_typesupport_fastrtps_c/wstring_conversion.hpp"
#include "rosidl_typesupport_fastrtps_c/serialization_helpers.hpp"

using rosidl_typesupport_fastrtps_c::u16string_to_wstring;
using rosidl_typesupport_fastrtps_c::wstring_to_u16string;
using rosidl_typesupport_fastrtps_c::cdr_serialize;
using rosidl_typesupport_fastrtps_c::cdr_deserialize;

TEST(test_wstring_conversion, wstring_to_u16string)
void test_ser_des(const rosidl_runtime_c__U16String & input)
{
rosidl_runtime_c__U16String actual;
ASSERT_TRUE(rosidl_runtime_c__U16String__init(&actual));
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
namespace fastcdr = eprosima::fastcdr;
char raw_buffer[1024];

{
rosidl_runtime_c__U16String__fini(&actual);
});
fastcdr::FastBuffer buffer(raw_buffer, sizeof(raw_buffer));
fastcdr::Cdr serializer(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::Cdr::DDS_CDR);

// Default string
EXPECT_TRUE(wstring_to_u16string(std::wstring(), actual));
EXPECT_EQ(0, memcmp(u"", actual.data, actual.size));
cdr_serialize(serializer, input);
}

// Empty string
EXPECT_TRUE(wstring_to_u16string(std::wstring(L""), actual));
EXPECT_EQ(0, memcmp(u"", actual.data, actual.size));
fastcdr::FastBuffer buffer(raw_buffer, sizeof(raw_buffer));
fastcdr::Cdr deserializer(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::Cdr::DDS_CDR);

// Non-empty string
EXPECT_TRUE(wstring_to_u16string(std::wstring(L"¡Hola, Mundo!"), actual));
EXPECT_EQ(0, memcmp(u"¡Hola, Mundo!", actual.data, actual.size));
rosidl_runtime_c__U16String output;
ASSERT_TRUE(rosidl_runtime_c__U16String__init(&output));
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rosidl_runtime_c__U16String__fini(&output);
});

ASSERT_TRUE(cdr_deserialize(deserializer, output));
EXPECT_EQ(input.size, output.size);
EXPECT_EQ(0, memcmp(input.data, output.data, input.size));
}

TEST(test_wstring_conversion, u16string_to_wstring)
TEST(test_wstring_conversion, serialize_deserialize)
{
std::wstring actual;
rosidl_runtime_c__U16String input;
Expand All @@ -57,16 +63,13 @@ TEST(test_wstring_conversion, u16string_to_wstring)
});

// Default string
u16string_to_wstring(input, actual);
EXPECT_EQ(std::wstring(), actual);
test_ser_des(input);

// Empty string
ASSERT_TRUE(rosidl_runtime_c__U16String__assign(&input, (const uint16_t *)u""));
u16string_to_wstring(input, actual);
EXPECT_EQ(std::wstring(L""), actual);
test_ser_des(input);

// Non-empty string
ASSERT_TRUE(rosidl_runtime_c__U16String__assign(&input, (const uint16_t *)u"¡Hola, Mundo!"));
u16string_to_wstring(input, actual);
EXPECT_EQ(std::wstring(L"¡Hola, Mundo!"), actual);
test_ser_des(input);
}
18 changes: 15 additions & 3 deletions rosidl_typesupport_fastrtps_c/test/test_wstring_conversion_mem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,23 +16,33 @@

#include "gtest/gtest.h"

#include "fastcdr/Cdr.h"
#include "rosidl_runtime_c/u16string_functions.h"
#include "osrf_testing_tools_cpp/memory_tools/memory_tools.hpp"
#include "osrf_testing_tools_cpp/scope_exit.hpp"

#include "rosidl_typesupport_fastrtps_c/wstring_conversion.hpp"
#include "rosidl_typesupport_fastrtps_c/serialization_helpers.hpp"

using rosidl_typesupport_fastrtps_c::wstring_to_u16string;
using rosidl_typesupport_fastrtps_c::cdr_deserialize;

TEST(test_wstring_conversion, u16string_resize_failure)
{
namespace fastcdr = eprosima::fastcdr;

osrf_testing_tools_cpp::memory_tools::initialize();
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
osrf_testing_tools_cpp::memory_tools::uninitialize();
});

std::wstring wstring(L"¡Hola, Mundo!");
char raw_buffer[1024];
{
fastcdr::FastBuffer buffer(raw_buffer, sizeof(raw_buffer));
fastcdr::Cdr cdr(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::Cdr::DDS_CDR);
cdr << wstring;
}

rosidl_runtime_c__U16String u16string;
ASSERT_TRUE(rosidl_runtime_c__U16String__init(&u16string));

Expand All @@ -50,8 +60,10 @@ TEST(test_wstring_conversion, u16string_resize_failure)
osrf_testing_tools_cpp::memory_tools::on_unexpected_realloc(on_unexpected_operation);
osrf_testing_tools_cpp::memory_tools::enable_monitoring();

fastcdr::FastBuffer buffer(raw_buffer, sizeof(raw_buffer));
fastcdr::Cdr cdr(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::Cdr::DDS_CDR);
EXPECT_NO_MEMORY_OPERATIONS(
{
EXPECT_FALSE(wstring_to_u16string(wstring, u16string));
EXPECT_FALSE(cdr_deserialize(cdr, u16string));
});
}
Loading

0 comments on commit b4f63c0

Please sign in to comment.