Skip to content

Commit

Permalink
Adjust tests for humble
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Orlov <[email protected]>
  • Loading branch information
MichaelOrlov committed Sep 27, 2024
1 parent 6f9ab54 commit aa1a0db
Showing 1 changed file with 2 additions and 4 deletions.
6 changes: 2 additions & 4 deletions rosbag2_cpp/test/rosbag2_cpp/test_serialization_converter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,8 +65,6 @@ class SerializationConverterTest : public Test
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<std::shared_ptr<const rosbag2_storage::SerializedBagMessage>>())).WillByDefault(
Expand Down Expand Up @@ -154,7 +152,7 @@ TEST_F(SerializationConverterTest, default_rmw_converter_can_deserialize) {
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_->create_topic({test_topic_name_, "std_msgs/msg/String", "", {}});
writer_->write(message);

ASSERT_EQ(intercepted_converter_messages.size(), 1);
Expand Down Expand Up @@ -202,7 +200,7 @@ TEST_F(SerializationConverterTest, default_rmw_converter_can_serialize) {
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_->create_topic({test_topic_name_, "std_msgs/msg/String", "", {}});
writer_->write(message);

ASSERT_EQ(mock_storage_data_.size(), 1);
Expand Down

0 comments on commit aa1a0db

Please sign in to comment.