Skip to content

Commit

Permalink
Support Fast CDR v2 (ros2#114)
Browse files Browse the repository at this point in the history
* Require fastcdr version 2

* Adapt for API breaks in rosidl_typesupport_fastrtps_cpp

* Adapt for API breaks in rosidl_typesupport_fastrtps_c

* Adapt for API breaks in tests.

Signed-off-by: Miguel Company <[email protected]>
  • Loading branch information
MiguelCompany authored Mar 26, 2024
1 parent b4f63c0 commit edf7835
Show file tree
Hide file tree
Showing 13 changed files with 34 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ endif()

find_package(ament_cmake_ros REQUIRED)
find_package(fastrtps_cmake_module QUIET)
find_package(fastcdr REQUIRED CONFIG)
find_package(fastcdr 2 REQUIRED CONFIG)
find_package(rosidl_typesupport_interface REQUIRED)
find_package(rosidl_typesupport_fastrtps_cpp REQUIRED)
find_package(rosidl_runtime_c REQUIRED)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -237,7 +237,7 @@ if isinstance(type_, AbstractNestedType):
}
}
@[ elif isinstance(member.type.value_type, BasicType)]@
cdr.serializeArray(array_ptr, size);
cdr.serialize_array(array_ptr, size);
@[ else]@
for (size_t i = 0; i < size; ++i) {
if (!callbacks->cdr_serialize(
Expand Down Expand Up @@ -379,7 +379,7 @@ else:
array_ptr[i] = static_cast<char16_t>(tmp);
}
@[ elif isinstance(member.type.value_type, BasicType)]@
cdr.deserializeArray(array_ptr, size);
cdr.deserialize_array(array_ptr, size);
@[ else]@
for (size_t i = 0; i < size; ++i) {
if (!callbacks->cdr_deserialize(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
# rosidl_typesupport_fastrtps_c/rosidl_typesupport_fastrtps_c-extras.cmake.in

find_package(fastrtps_cmake_module QUIET)
find_package(fastcdr REQUIRED CONFIG)
find_package(fastcdr 2 REQUIRED CONFIG)

if(NOT fastcdr_FOUND)
message(STATUS
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,8 @@ BENCHMARK_F(PerformanceTest, wstring_to_u16string)(benchmark::State & st)
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);
fastcdr::Cdr cdr(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::CdrVersion::XCDRv1);
cdr.set_encoding_flag(fastcdr::EncodingAlgorithmFlag::PLAIN_CDR);
cdr << wstring;

rosidl_runtime_c__U16String s;
Expand All @@ -65,7 +66,8 @@ BENCHMARK_F(PerformanceTest, u16string_to_wstring)(benchmark::State & st)
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);
fastcdr::Cdr cdr(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::CdrVersion::XCDRv1);
cdr.set_encoding_flag(fastcdr::EncodingAlgorithmFlag::PLAIN_CDR);
cdr << data;

rosidl_runtime_c__U16String s;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,13 +32,15 @@ void test_ser_des(const rosidl_runtime_c__U16String & input)

{
fastcdr::FastBuffer buffer(raw_buffer, sizeof(raw_buffer));
fastcdr::Cdr serializer(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::Cdr::DDS_CDR);
fastcdr::Cdr serializer(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::CdrVersion::XCDRv1);
serializer.set_encoding_flag(fastcdr::EncodingAlgorithmFlag::PLAIN_CDR);

cdr_serialize(serializer, input);
}

fastcdr::FastBuffer buffer(raw_buffer, sizeof(raw_buffer));
fastcdr::Cdr deserializer(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::Cdr::DDS_CDR);
fastcdr::Cdr deserializer(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::CdrVersion::XCDRv1);
deserializer.set_encoding_flag(fastcdr::EncodingAlgorithmFlag::PLAIN_CDR);

rosidl_runtime_c__U16String output;
ASSERT_TRUE(rosidl_runtime_c__U16String__init(&output));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@ TEST(test_wstring_conversion, u16string_resize_failure)
char raw_buffer[1024];
{
fastcdr::FastBuffer buffer(raw_buffer, sizeof(raw_buffer));
fastcdr::Cdr cdr(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::Cdr::DDS_CDR);
fastcdr::Cdr cdr(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::CdrVersion::XCDRv1);
cdr.set_encoding_flag(fastcdr::EncodingAlgorithmFlag::PLAIN_CDR);
cdr << wstring;
}

Expand All @@ -61,7 +62,8 @@ TEST(test_wstring_conversion, u16string_resize_failure)
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);
fastcdr::Cdr cdr(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::CdrVersion::XCDRv1);
cdr.set_encoding_flag(fastcdr::EncodingAlgorithmFlag::PLAIN_CDR);
EXPECT_NO_MEMORY_OPERATIONS(
{
EXPECT_FALSE(cdr_deserialize(cdr, u16string));
Expand Down
2 changes: 1 addition & 1 deletion rosidl_typesupport_fastrtps_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ endif()
find_package(ament_cmake_ros REQUIRED)

find_package(fastrtps_cmake_module QUIET)
find_package(fastcdr REQUIRED CONFIG)
find_package(fastcdr 2 REQUIRED CONFIG)
if(FASTRTPS_STATIC_DISABLE)
ament_package()
message(STATUS "fastrtps static rmw implementation explicitly disabled - skipping '${PROJECT_NAME}'")
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ endif()

find_package(ament_cmake_ros REQUIRED)
find_package(fastrtps_cmake_module QUIET)
find_package(fastcdr REQUIRED CONFIG)
find_package(fastcdr 2 REQUIRED CONFIG)
find_package(rmw REQUIRED)
find_package(rosidl_runtime_c REQUIRED)
find_package(rosidl_runtime_cpp REQUIRED)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ cdr_serialize(
cdr << static_cast<uint32_t>(size);
@[ if isinstance(member.type.value_type, BasicType) and member.type.value_type.typename not in ('boolean', 'wchar')]@
if (size > 0) {
cdr.serializeArray(&(ros_message.@(member.name)[0]), size);
cdr.serialize_array(&(ros_message.@(member.name)[0]), size);
}
@[ else]@
for (size_t i = 0; i < size; i++) {
Expand Down Expand Up @@ -210,7 +210,7 @@ cdr_deserialize(
ros_message.@(member.name).resize(size);
@[ if isinstance(member.type.value_type, BasicType) and member.type.value_type.typename not in ('boolean', 'wchar')]@
if (size > 0) {
cdr.deserializeArray(&(ros_message.@(member.name)[0]), size);
cdr.deserialize_array(&(ros_message.@(member.name)[0]), size);
}
@[ else]@
for (size_t i = 0; i < size; i++) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
# rosidl_typesupport_fastrtps_cpp-extras.cmake.in

find_package(fastrtps_cmake_module QUIET)
find_package(fastcdr REQUIRED CONFIG)
find_package(fastcdr 2 REQUIRED CONFIG)

if(NOT fastcdr_FOUND)
message(STATUS
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,9 @@ BENCHMARK_F(PerformanceTest, wstring_to_u16string)(benchmark::State & st)
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);
fastcdr::Cdr cdr(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::CdrVersion::XCDRv1);
cdr.set_encoding_flag(fastcdr::EncodingAlgorithmFlag::PLAIN_CDR);

cdr << wstring;

reset_heap_counters();
Expand All @@ -55,7 +57,8 @@ BENCHMARK_F(PerformanceTest, u16string_to_wstring)(benchmark::State & st)
std::u16string u16string(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);
fastcdr::Cdr cdr(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::CdrVersion::XCDRv1);
cdr.set_encoding_flag(fastcdr::EncodingAlgorithmFlag::PLAIN_CDR);

reset_heap_counters();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,13 +31,15 @@ void test_ser_des(const std::u16string & input)

{
fastcdr::FastBuffer buffer(raw_buffer, sizeof(raw_buffer));
fastcdr::Cdr serializer(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::Cdr::DDS_CDR);
fastcdr::Cdr serializer(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::CdrVersion::XCDRv1);
serializer.set_encoding_flag(fastcdr::EncodingAlgorithmFlag::PLAIN_CDR);

cdr_serialize(serializer, input);
}

fastcdr::FastBuffer buffer(raw_buffer, sizeof(raw_buffer));
fastcdr::Cdr deserializer(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::Cdr::DDS_CDR);
fastcdr::Cdr deserializer(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::CdrVersion::XCDRv1);
deserializer.set_encoding_flag(fastcdr::EncodingAlgorithmFlag::PLAIN_CDR);

std::u16string output;
ASSERT_TRUE(cdr_deserialize(deserializer, output));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,8 @@ TEST(test_wstring_conversion, u16string_resize_failure)
char raw_buffer[1024];
{
fastcdr::FastBuffer buffer(raw_buffer, sizeof(raw_buffer));
fastcdr::Cdr cdr(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::Cdr::DDS_CDR);
fastcdr::Cdr cdr(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::CdrVersion::XCDRv1);
cdr.set_encoding_flag(fastcdr::EncodingAlgorithmFlag::PLAIN_CDR);
cdr << wstring;
}

Expand All @@ -54,7 +55,8 @@ TEST(test_wstring_conversion, u16string_resize_failure)
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);
fastcdr::Cdr cdr(buffer, fastcdr::Cdr::DEFAULT_ENDIAN, fastcdr::CdrVersion::XCDRv1);
cdr.set_encoding_flag(fastcdr::EncodingAlgorithmFlag::PLAIN_CDR);
EXPECT_NO_MEMORY_OPERATIONS(
{
EXPECT_FALSE(cdr_deserialize(cdr, u16string));
Expand Down

0 comments on commit edf7835

Please sign in to comment.