diff --git a/rosbag2_cpp/CMakeLists.txt b/rosbag2_cpp/CMakeLists.txt index 8ddddf2239..aa68597920 100644 --- a/rosbag2_cpp/CMakeLists.txt +++ b/rosbag2_cpp/CMakeLists.txt @@ -29,7 +29,7 @@ option(DISABLE_SANITIZERS "disables the use of gcc sanitizers" ON) if(NOT DISABLE_SANITIZERS AND CMAKE_COMPILER_IS_GNUCXX) include(CheckCXXSourceRuns) set(OLD_CMAKE_REQUIRED_FLAGS ${CMAKE_REQUIRED_FLAGS}) - set(CMAKE_REQUIRED_FLAGS "${OLD_CMAKE_REQUIRED_FLAGS} -fsanitize=leak") + set(CMAKE_REQUIRED_FLAGS "${OLD_CMAKE_REQUIRED_FLAGS} -fsanitize=address,leak,undefined") check_cxx_source_runs("int main() {}" HAVE_SANITIZERS) set(CMAKE_REQUIRED_FLAGS ${OLD_CMAKE_REQUIRED_FLAGS}) if(NOT HAVE_SANITIZERS) @@ -131,7 +131,13 @@ ament_export_dependencies( if(BUILD_TESTING) find_package(ament_cmake_gmock REQUIRED) find_package(ament_lint_auto REQUIRED) + find_package(std_msgs REQUIRED) find_package(test_msgs REQUIRED) +<<<<<<< HEAD +======= + find_package(rosbag2_test_msgdefs REQUIRED) + find_package(rmw_implementation_cmake REQUIRED) +>>>>>>> a269cd4 ([iron] Bugfix for rosbag2_cpp serialization converter (backport #1814) (#1823)) ament_lint_auto_find_test_dependencies() add_library( @@ -227,6 +233,32 @@ if(BUILD_TESTING) target_link_libraries(test_sequential_writer ${PROJECT_NAME}) endif() + function(test_serialization_converter_for_rmw_implementation) + set(rmw_implementation_env_var RMW_IMPLEMENTATION=${rmw_implementation}) + ament_add_gmock(test_serialization_converter${target_suffix} + test/rosbag2_cpp/test_serialization_converter.cpp + ENV ${rmw_implementation_env_var} + ) + if(TARGET test_serialization_converter${target_suffix}) + if(NOT DISABLE_SANITIZERS) + target_compile_options(test_serialization_converter${target_suffix} + PUBLIC $<$:-fsanitize=address,leak,undefined> + ) + target_link_libraries(test_serialization_converter${target_suffix} + $<$:-fsanitize=address,leak,undefined> + ) + endif() + target_link_libraries(test_serialization_converter${target_suffix} + ${PROJECT_NAME} + rosbag2_storage::rosbag2_storage + ${std_msgs_TARGETS} + ) + endif() + endfunction() + # Run test_serialization_converter for each rmw implementation because default serialization + # converter uses rmw specific functions for serialization and deserialization. + call_for_each_rmw_implementation(test_serialization_converter_for_rmw_implementation) + ament_add_gmock(test_multifile_reader test/rosbag2_cpp/test_multifile_reader.cpp) if(TARGET test_multifile_reader) diff --git a/rosbag2_cpp/include/rosbag2_cpp/converter_interfaces/serialization_format_converter.hpp b/rosbag2_cpp/include/rosbag2_cpp/converter_interfaces/serialization_format_converter.hpp index 151c491702..c456f042d9 100644 --- a/rosbag2_cpp/include/rosbag2_cpp/converter_interfaces/serialization_format_converter.hpp +++ b/rosbag2_cpp/include/rosbag2_cpp/converter_interfaces/serialization_format_converter.hpp @@ -20,6 +20,7 @@ #include "rosbag2_cpp/converter_interfaces/serialization_format_serializer.hpp" #include "rosbag2_cpp/converter_interfaces/serialization_format_deserializer.hpp" +#include "rosbag2_cpp/visibility_control.hpp" /** * This is a convenience class for plugin developers. @@ -31,7 +32,7 @@ namespace rosbag2_cpp namespace converter_interfaces { -class SerializationFormatConverter +class ROSBAG2_CPP_PUBLIC SerializationFormatConverter : public SerializationFormatSerializer, public SerializationFormatDeserializer { public: diff --git a/rosbag2_cpp/include/rosbag2_cpp/converter_interfaces/serialization_format_deserializer.hpp b/rosbag2_cpp/include/rosbag2_cpp/converter_interfaces/serialization_format_deserializer.hpp index 4153a99ea3..1edaee9bcd 100644 --- a/rosbag2_cpp/include/rosbag2_cpp/converter_interfaces/serialization_format_deserializer.hpp +++ b/rosbag2_cpp/include/rosbag2_cpp/converter_interfaces/serialization_format_deserializer.hpp @@ -19,17 +19,16 @@ #include #include "rosbag2_cpp/types/introspection_message.hpp" - #include "rosbag2_storage/serialized_bag_message.hpp" - #include "rosidl_runtime_c/message_type_support_struct.h" +#include "rosbag2_cpp/visibility_control.hpp" namespace rosbag2_cpp { namespace converter_interfaces { -class SerializationFormatDeserializer +class ROSBAG2_CPP_PUBLIC SerializationFormatDeserializer { public: virtual ~SerializationFormatDeserializer() = default; diff --git a/rosbag2_cpp/include/rosbag2_cpp/converter_interfaces/serialization_format_serializer.hpp b/rosbag2_cpp/include/rosbag2_cpp/converter_interfaces/serialization_format_serializer.hpp index a0cd686c19..c4c6a642a5 100644 --- a/rosbag2_cpp/include/rosbag2_cpp/converter_interfaces/serialization_format_serializer.hpp +++ b/rosbag2_cpp/include/rosbag2_cpp/converter_interfaces/serialization_format_serializer.hpp @@ -19,17 +19,16 @@ #include #include "rosbag2_cpp/types/introspection_message.hpp" - #include "rosbag2_storage/serialized_bag_message.hpp" - #include "rosidl_runtime_c/message_type_support_struct.h" +#include "rosbag2_cpp/visibility_control.hpp" namespace rosbag2_cpp { namespace converter_interfaces { -class SerializationFormatSerializer +class ROSBAG2_CPP_PUBLIC SerializationFormatSerializer { public: virtual ~SerializationFormatSerializer() = default; diff --git a/rosbag2_cpp/src/rosbag2_cpp/rmw_implemented_serialization_format_converter.hpp b/rosbag2_cpp/include/rosbag2_cpp/rmw_implemented_serialization_format_converter.hpp similarity index 85% rename from rosbag2_cpp/src/rosbag2_cpp/rmw_implemented_serialization_format_converter.hpp rename to rosbag2_cpp/include/rosbag2_cpp/rmw_implemented_serialization_format_converter.hpp index bcefe5a370..2b69b66311 100644 --- a/rosbag2_cpp/src/rosbag2_cpp/rmw_implemented_serialization_format_converter.hpp +++ b/rosbag2_cpp/include/rosbag2_cpp/rmw_implemented_serialization_format_converter.hpp @@ -19,6 +19,15 @@ #include #include "rosbag2_cpp/converter_interfaces/serialization_format_converter.hpp" +#include "rosbag2_cpp/visibility_control.hpp" + +// This is necessary because of using stl types here. It is completely safe, because +// a) the member is not accessible from the outside +// b) there are no inline functions. +#ifdef _WIN32 +# pragma warning(push) +# pragma warning(disable:4251) +#endif namespace rosbag2_cpp { @@ -31,7 +40,7 @@ class RMWImplementedConverterImpl; * searches the system for an installed RMW implementation that understands the requested format, * loads that library if found, and uses its implementation for serialization. */ -class RMWImplementedConverter +class ROSBAG2_CPP_PUBLIC RMWImplementedConverter : public rosbag2_cpp::converter_interfaces::SerializationFormatConverter { public: @@ -40,7 +49,7 @@ class RMWImplementedConverter * \throws std::runtime_error if no RMW implementation was found supporting the format. */ explicit RMWImplementedConverter(const std::string & format); - virtual ~RMWImplementedConverter(); + ~RMWImplementedConverter() override; void deserialize( std::shared_ptr serialized_message, diff --git a/rosbag2_cpp/package.xml b/rosbag2_cpp/package.xml index 5ccedb89c9..bf3c619501 100644 --- a/rosbag2_cpp/package.xml +++ b/rosbag2_cpp/package.xml @@ -33,6 +33,8 @@ ament_cmake_gmock ament_lint_auto ament_lint_common + rmw_implementation_cmake + std_msgs test_msgs rosbag2_test_common diff --git a/rosbag2_cpp/src/rosbag2_cpp/converter.cpp b/rosbag2_cpp/src/rosbag2_cpp/converter.cpp index e12859f5a5..5b5d042a83 100644 --- a/rosbag2_cpp/src/rosbag2_cpp/converter.cpp +++ b/rosbag2_cpp/src/rosbag2_cpp/converter.cpp @@ -67,22 +67,23 @@ std::shared_ptr Converter::convert( std::shared_ptr message) { auto introspection_ts = topics_and_types_.at(message->topic_name).introspection_type_support; + auto rmw_ts = topics_and_types_.at(message->topic_name).rmw_type_support; auto allocator = rcutils_get_default_allocator(); std::shared_ptr allocated_ros_message = allocate_introspection_message(introspection_ts, &allocator); - auto output_message = std::make_shared(); // deserialize rosbag2_cpp::introspection_message_set_topic_name( allocated_ros_message.get(), message->topic_name.c_str()); allocated_ros_message->time_stamp = message->time_stamp; - input_converter_->deserialize(message, introspection_ts, allocated_ros_message); + input_converter_->deserialize(message, rmw_ts, allocated_ros_message); - // re-serialize + // re-serialize with the new serializer + auto output_message = std::make_shared(); output_message->serialized_data = rosbag2_storage::make_empty_serialized_message(0); output_message->topic_name = std::string(allocated_ros_message->topic_name); output_message->time_stamp = allocated_ros_message->time_stamp; - output_converter_->serialize(allocated_ros_message, introspection_ts, output_message); + output_converter_->serialize(allocated_ros_message, rmw_ts, output_message); return output_message; } diff --git a/rosbag2_cpp/src/rosbag2_cpp/rmw_implemented_serialization_format_converter.cpp b/rosbag2_cpp/src/rosbag2_cpp/rmw_implemented_serialization_format_converter.cpp index 3424a63d12..f3975a4b2f 100644 --- a/rosbag2_cpp/src/rosbag2_cpp/rmw_implemented_serialization_format_converter.cpp +++ b/rosbag2_cpp/src/rosbag2_cpp/rmw_implemented_serialization_format_converter.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "rmw_implemented_serialization_format_converter.hpp" +#include "rosbag2_cpp/rmw_implemented_serialization_format_converter.hpp" #include #include diff --git a/rosbag2_cpp/src/rosbag2_cpp/serialization_format_converter_factory_impl.hpp b/rosbag2_cpp/src/rosbag2_cpp/serialization_format_converter_factory_impl.hpp index 31901cec77..b338a158ab 100644 --- a/rosbag2_cpp/src/rosbag2_cpp/serialization_format_converter_factory_impl.hpp +++ b/rosbag2_cpp/src/rosbag2_cpp/serialization_format_converter_factory_impl.hpp @@ -28,7 +28,7 @@ #include "rosbag2_cpp/logging.hpp" #include "rosbag2_cpp/visibility_control.hpp" -#include "./rmw_implemented_serialization_format_converter.hpp" +#include "rosbag2_cpp/rmw_implemented_serialization_format_converter.hpp" namespace rosbag2_cpp { diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_serialization_converter.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_serialization_converter.cpp new file mode 100644 index 0000000000..5cb91e752d --- /dev/null +++ b/rosbag2_cpp/test/rosbag2_cpp/test_serialization_converter.cpp @@ -0,0 +1,215 @@ +// Copyright 2024 Apex.AI, Inc. +// +// 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. + +#include + +#include +#include +#include +#include +#include + +#include "mock_converter.hpp" +#include "mock_converter_factory.hpp" +#include "mock_metadata_io.hpp" +#include "mock_storage.hpp" +#include "mock_storage_factory.hpp" +#include "rmw/rmw.h" +#include "rclcpp/serialization.hpp" +#include "rclcpp/serialized_message.hpp" +#include "rosbag2_cpp/rmw_implemented_serialization_format_converter.hpp" +#include "rosbag2_cpp/writers/sequential_writer.hpp" +#include "rosbag2_cpp/writer.hpp" +#include "rosbag2_storage/ros_helper.hpp" +#include "std_msgs/msg/string.hpp" + +using namespace testing; // NOLINT + +namespace fs = std::filesystem; + +class SerializationConverterTest : public Test +{ +public: + SerializationConverterTest() + { + storage_factory_ = std::make_unique>(); + storage_ = std::make_shared>(); + converter_factory_ = std::make_shared>(); + metadata_io_ = std::make_unique>(); + tmp_dir_path_ = fs::temp_directory_path() / "SerializationConverterTest"; + storage_options_ = rosbag2_storage::StorageOptions{}; + // We are using in memory mock storage to avoid writing to file. However, writer->open(..) + // creating a new subfolder for the new recording. Therefore, need to provide a valid uri and + // clean up those newly created folder in the destructor. + storage_options_.uri = (tmp_dir_path_ / bag_base_dir_).string(); + fs::remove_all(tmp_dir_path_); + + ON_CALL(*storage_factory_, open_read_write(_)).WillByDefault( + DoAll( + Invoke( + [this](const rosbag2_storage::StorageOptions & storage_options) { + mock_storage_data_.clear(); + (void)storage_options; + }), + Return(storage_))); + EXPECT_CALL(*storage_factory_, open_read_write(_)).Times(AtLeast(1)); + + ON_CALL(*storage_, set_read_order).WillByDefault(Return(true)); + + ON_CALL( + *storage_, + write(An>())).WillByDefault( + [this](std::shared_ptr serialized_message) { + mock_storage_data_.push_back(serialized_message); + }); + + using VectorSharedBagMessages = + std::vector>; + + EXPECT_CALL(*storage_, write(An())).Times(0); + + EXPECT_CALL(*storage_, get_bagfile_size()).Times(0); + } + + ~SerializationConverterTest() override + { + fs::remove_all(tmp_dir_path_); + } + + std::shared_ptr make_test_msg() + { + std_msgs::msg::String std_string_msg; + std_string_msg.data = test_msg_content_; + auto rclcpp_serialized_msg = std::make_shared(); + rclcpp::Serialization serialization; + serialization.serialize_message(&std_string_msg, rclcpp_serialized_msg.get()); + // Convert rclcpp serialized message to the rosbag2_storage::SerializedBagMessage + auto message = std::make_shared(); + message->topic_name = test_topic_name_; + message->serialized_data = rosbag2_storage::make_serialized_message( + rclcpp_serialized_msg->get_rcl_serialized_message().buffer, rclcpp_serialized_msg->size()); + + return message; + } + + std::unique_ptr> storage_factory_; + std::shared_ptr> storage_; + std::shared_ptr> converter_factory_; + std::unique_ptr metadata_io_; + + fs::path tmp_dir_path_; + const std::string bag_base_dir_ = "test_bag"; + const std::string test_msg_content_ = "Test message string"; + const std::string test_topic_name_ = "test_topic"; + rosbag2_storage::StorageOptions storage_options_; + std::vector> mock_storage_data_; + std::unique_ptr writer_; +}; + +TEST_F(SerializationConverterTest, default_rmw_converter_can_deserialize) { + auto sequential_writer = std::make_unique( + std::move(storage_factory_), converter_factory_, std::move(metadata_io_)); + writer_ = std::make_unique(std::move(sequential_writer)); + + const std::string mock_serialization_format = "mock_serialization_format"; + const std::string rmw_serialization_format = rmw_get_serialization_format(); + + auto mock_converter = std::make_unique>(); + std::vector> + intercepted_converter_messages; + EXPECT_CALL( + *mock_converter, + serialize( + An>(), + An(), + An>())). + WillRepeatedly( + [&](std::shared_ptr ros_message, + const rosidl_message_type_support_t * type_support, + std::shared_ptr serialized_message) { + intercepted_converter_messages.push_back(ros_message); + (void)serialized_message; + (void)type_support; + }); + + auto rmw_converter = + std::make_unique(rmw_serialization_format); + + EXPECT_CALL(*converter_factory_, load_serializer(mock_serialization_format)) + .WillOnce(Return(ByMove(std::move(mock_converter)))); + EXPECT_CALL(*converter_factory_, load_deserializer(rmw_serialization_format)) + .WillOnce(Return(ByMove(std::move(rmw_converter)))); + + auto message = make_test_msg(); + writer_->open(storage_options_, {rmw_serialization_format, mock_serialization_format}); + + writer_->create_topic({test_topic_name_, "std_msgs/msg/String", "", {}, ""}); + writer_->write(message); + + ASSERT_EQ(intercepted_converter_messages.size(), 1); + // Using the type punning since we know the type of the message in advance + const auto & ros_message = + *static_cast(intercepted_converter_messages[0]->message); + EXPECT_THAT(ros_message.data, StrEq(test_msg_content_)); +} + +TEST_F(SerializationConverterTest, default_rmw_converter_can_serialize) { + auto sequential_writer = std::make_unique( + std::move(storage_factory_), converter_factory_, std::move(metadata_io_)); + writer_ = std::make_unique(std::move(sequential_writer)); + + const std::string mock_serialization_format = "mock_serialization_format"; + const std::string rmw_serialization_format = rmw_get_serialization_format(); + + auto mock_converter = std::make_unique>(); + EXPECT_CALL( + *mock_converter, + deserialize( + An>(), + An(), + An>())). + WillRepeatedly( + [&](std::shared_ptr serialized_message, + const rosidl_message_type_support_t * type_support, + std::shared_ptr ros_message) + { + // Use rclcpp deserialization for concrete std_msgs::msg::String message type + rclcpp::Serialization serialization; + rclcpp::SerializedMessage rclcpp_serialized_msg(*serialized_message->serialized_data); + serialization.deserialize_message(&rclcpp_serialized_msg, ros_message->message); + (void)type_support; + }); + + auto rmw_converter = + std::make_unique(rmw_serialization_format); + + EXPECT_CALL(*converter_factory_, load_serializer(rmw_serialization_format)) + .WillOnce(Return(ByMove(std::move(rmw_converter)))); + EXPECT_CALL(*converter_factory_, load_deserializer(mock_serialization_format)) + .WillOnce(Return(ByMove(std::move(mock_converter)))); + + auto message = make_test_msg(); + writer_->open(storage_options_, {mock_serialization_format, rmw_serialization_format}); + + writer_->create_topic({test_topic_name_, "std_msgs/msg/String", "", {}, ""}); + writer_->write(message); + + ASSERT_EQ(mock_storage_data_.size(), 1); + + rclcpp::Serialization serialization; + rclcpp::SerializedMessage rclcpp_serialized_msg(*mock_storage_data_[0]->serialized_data); + std_msgs::msg::String ros_message; + serialization.deserialize_message(&rclcpp_serialized_msg, &ros_message); + EXPECT_THAT(ros_message.data, StrEq(test_msg_content_)); +}