Skip to content

Commit

Permalink
Revert "Add extra initializations in an attempt to fix a freeze on CI"
Browse files Browse the repository at this point in the history
This reverts commit 4e1c579.

Signed-off-by: Michael Orlov <[email protected]>
  • Loading branch information
MichaelOrlov committed Sep 21, 2024
1 parent 6a2c3cf commit 1d37e18
Showing 1 changed file with 55 additions and 67 deletions.
122 changes: 55 additions & 67 deletions rosbag2_cpp/test/rosbag2_cpp/test_serialization_converter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,15 +47,13 @@ class SerializationConverterTest : public Test
storage_ = std::make_shared<NiceMock<MockStorage>>();
converter_factory_ = std::make_shared<StrictMock<MockConverterFactory>>();
metadata_io_ = std::make_unique<NiceMock<MockMetadataIo>>();
tmp_dir_path_ = fs::temp_directory_path() / "SerializationConverterTest";
tmp_dir_ = 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_).generic_string();
storage_options_.storage_id = "mcap";
fs::remove_all(tmp_dir_path_);
fs::create_directories(tmp_dir_path_);
storage_options_.uri = (tmp_dir_ / bag_base_dir_).string();
fs::remove_all(tmp_dir_);

ON_CALL(*storage_factory_, open_read_write(_)).WillByDefault(
DoAll(
Expand Down Expand Up @@ -89,7 +87,7 @@ class SerializationConverterTest : public Test

~SerializationConverterTest() override
{
fs::remove_all(tmp_dir_path_);
fs::remove_all(tmp_dir_);
}

std::shared_ptr<rosbag2_storage::SerializedBagMessage> make_test_msg()
Expand All @@ -102,8 +100,6 @@ class SerializationConverterTest : public Test
// Convert rclcpp serialized message to the rosbag2_storage::SerializedBagMessage
auto message = std::make_shared<rosbag2_storage::SerializedBagMessage>();
message->topic_name = test_topic_name_;
message->recv_timestamp = 100;
message->send_timestamp = message->recv_timestamp;
message->serialized_data = rosbag2_storage::make_serialized_message(
rclcpp_serialized_msg->get_rcl_serialized_message().buffer, rclcpp_serialized_msg->size());

Expand All @@ -115,7 +111,7 @@ class SerializationConverterTest : public Test
std::shared_ptr<StrictMock<MockConverterFactory>> converter_factory_;
std::unique_ptr<MockMetadataIo> metadata_io_;

fs::path tmp_dir_path_;
fs::path tmp_dir_;
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";
Expand Down Expand Up @@ -161,15 +157,7 @@ TEST_F(SerializationConverterTest, default_rmw_converter_can_deserialize) {
auto message = make_test_msg();
writer_->open(storage_options_, {rmw_serialization_format, mock_serialization_format});

rosbag2_storage::TopicMetadata topic_metadata{
0u, test_topic_name_, "std_msgs/msg/String", "cdr", {rclcpp::QoS(1)}, "hash1"
};
const rosbag2_storage::MessageDefinition msg_definition =
{
"std_msgs/msg/String", "ros2msg",
"string data", ""
};
writer_->create_topic(topic_metadata, msg_definition);
writer_->create_topic({0u, test_topic_name_, "std_msgs/msg/String", "", {}, ""});
writer_->write(message);

ASSERT_EQ(intercepted_converter_messages.size(), 1);
Expand All @@ -179,52 +167,52 @@ TEST_F(SerializationConverterTest, default_rmw_converter_can_deserialize) {
EXPECT_THAT(ros_message.data, StrEq(test_msg_content_));
}

// TEST_F(SerializationConverterTest, default_rmw_converter_can_serialize) {
// auto sequential_writer = std::make_unique<rosbag2_cpp::writers::SequentialWriter>(
// std::move(storage_factory_), converter_factory_, std::move(metadata_io_));
// writer_ = std::make_unique<rosbag2_cpp::Writer>(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<StrictMock<MockConverter>>();
// EXPECT_CALL(
// *mock_converter,
// deserialize(
// An<std::shared_ptr<const rosbag2_storage::SerializedBagMessage>>(),
// An<const rosidl_message_type_support_t *>(),
// An<std::shared_ptr<rosbag2_cpp::rosbag2_introspection_message_t>>())).
// WillRepeatedly(
// [&](std::shared_ptr<const rosbag2_storage::SerializedBagMessage> serialized_message,
// const rosidl_message_type_support_t * type_support,
// std::shared_ptr<rosbag2_cpp::rosbag2_introspection_message_t> ros_message)
// {
// // Use rclcpp deserialization for concrete std_msgs::msg::String message type
// rclcpp::Serialization<std_msgs::msg::String> 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<rosbag2_cpp::RMWImplementedConverter>(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({0u, test_topic_name_, "std_msgs/msg/String", "", {}, ""});
// writer_->write(message);
//
// ASSERT_EQ(mock_storage_data_.size(), 1);
//
// rclcpp::Serialization<std_msgs::msg::String> 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_));
// }
TEST_F(SerializationConverterTest, default_rmw_converter_can_serialize) {
auto sequential_writer = std::make_unique<rosbag2_cpp::writers::SequentialWriter>(
std::move(storage_factory_), converter_factory_, std::move(metadata_io_));
writer_ = std::make_unique<rosbag2_cpp::Writer>(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<StrictMock<MockConverter>>();
EXPECT_CALL(
*mock_converter,
deserialize(
An<std::shared_ptr<const rosbag2_storage::SerializedBagMessage>>(),
An<const rosidl_message_type_support_t *>(),
An<std::shared_ptr<rosbag2_cpp::rosbag2_introspection_message_t>>())).
WillRepeatedly(
[&](std::shared_ptr<const rosbag2_storage::SerializedBagMessage> serialized_message,
const rosidl_message_type_support_t * type_support,
std::shared_ptr<rosbag2_cpp::rosbag2_introspection_message_t> ros_message)
{
// Use rclcpp deserialization for concrete std_msgs::msg::String message type
rclcpp::Serialization<std_msgs::msg::String> 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<rosbag2_cpp::RMWImplementedConverter>(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({0u, test_topic_name_, "std_msgs/msg/String", "", {}, ""});
writer_->write(message);

ASSERT_EQ(mock_storage_data_.size(), 1);

rclcpp::Serialization<std_msgs::msg::String> 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_));
}

0 comments on commit 1d37e18

Please sign in to comment.