From 7a4b7f5870e4739a81f6a3fa52c706d4c9b361f4 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Fri, 31 Jan 2020 09:51:13 -0800 Subject: [PATCH] code style only: wrap after open parenthesis if not in one line Signed-off-by: Dirk Thomas --- .../rosbag2_compression/zstd_compressor.cpp | 10 +++--- .../rosbag2_compression/zstd_decompressor.cpp | 14 ++++---- .../cdr/cdr_converter.cpp | 3 +- rosbag2_cpp/src/rosbag2_cpp/info.cpp | 6 ++-- ...lization_format_converter_factory_impl.hpp | 10 +++--- .../rosbag2_cpp/converter_test_plugin.cpp | 4 +-- .../test/rosbag2_cpp/mock_converter.hpp | 6 ++-- .../rosbag2_cpp/mock_converter_factory.hpp | 6 ++-- .../test/rosbag2_cpp/mock_storage_factory.hpp | 6 ++-- .../rosbag2_cpp/serializer_test_plugin.cpp | 3 +- .../rosbag2_cpp/test_converter_factory.cpp | 3 +- rosbag2_cpp/test/rosbag2_cpp/test_info.cpp | 32 ++++++++++------- .../rosbag2_cpp/test_sequential_reader.cpp | 3 +- .../rosbag2_cpp/test_sequential_writer.cpp | 15 ++++---- .../rosbag2_cpp/test_typesupport_helpers.cpp | 6 ++-- .../src/rosbag2_storage/ros_helper.cpp | 22 ++++++------ .../test_metadata_serialization.cpp | 21 +++++++---- .../sqlite/sqlite_statement_wrapper.hpp | 3 +- .../sqlite/sqlite_storage.cpp | 10 +++--- .../sqlite/sqlite_wrapper.cpp | 10 +++--- .../sqlite/storage_test_fixture.hpp | 30 ++++++++-------- .../sqlite/test_sqlite_storage.cpp | 26 +++++++++----- .../rosbag2_test_common/memory_management.hpp | 24 +++++++------ .../rosbag2_test_common/publisher_manager.hpp | 3 +- .../test_rosbag2_info_end_to_end.cpp | 9 +++-- .../test_rosbag2_play_end_to_end.cpp | 23 ++++++++---- .../test_rosbag2_record_end_to_end.cpp | 3 +- .../generic_subscription.cpp | 19 +++++----- .../src/rosbag2_transport/player.cpp | 11 +++--- .../src/rosbag2_transport/rosbag2_node.cpp | 28 ++++++++------- .../rosbag2_transport/rosbag2_transport.cpp | 7 ++-- .../rosbag2_transport_python.cpp | 36 ++++++++++--------- .../record_integration_fixture.hpp | 3 +- .../test/rosbag2_transport/test_info.cpp | 9 +++-- .../test/rosbag2_transport/test_play.cpp | 23 ++++++++---- .../rosbag2_transport/test_rosbag2_node.cpp | 28 ++++++++------- 36 files changed, 290 insertions(+), 185 deletions(-) diff --git a/rosbag2_compression/src/rosbag2_compression/zstd_compressor.cpp b/rosbag2_compression/src/rosbag2_compression/zstd_compressor.cpp index a411483bfb..f3529b4d77 100644 --- a/rosbag2_compression/src/rosbag2_compression/zstd_compressor.cpp +++ b/rosbag2_compression/src/rosbag2_compression/zstd_compressor.cpp @@ -83,8 +83,9 @@ std::vector get_input_buffer(const std::string & uri) decompressed_buffer.data(), sizeof(uint8_t), decompressed_buffer.size(), file_pointer); if (read_count != decompressed_buffer_length) { - ROSBAG2_COMPRESSION_LOG_ERROR_STREAM("Bytes read (" << read_count << - ") != decompressed_buffer_length (" << decompressed_buffer.size() << ")!"); + ROSBAG2_COMPRESSION_LOG_ERROR_STREAM( + "Bytes read (" << read_count << + ") != decompressed_buffer_length (" << decompressed_buffer.size() << ")!"); // An error indicator is set by this, so the following check will throw } @@ -120,8 +121,9 @@ void write_output_buffer( file_pointer); if (write_count != output_buffer.size()) { - ROSBAG2_COMPRESSION_LOG_ERROR_STREAM("Bytes written (" << write_count << - ") != output_buffer size (" << output_buffer.size() << ")!"); + ROSBAG2_COMPRESSION_LOG_ERROR_STREAM( + "Bytes written (" << write_count << + ") != output_buffer size (" << output_buffer.size() << ")!"); // An error indicator is set by fwrite, so the following check will throw. } diff --git a/rosbag2_compression/src/rosbag2_compression/zstd_decompressor.cpp b/rosbag2_compression/src/rosbag2_compression/zstd_decompressor.cpp index 05df3c8d9b..8e2489722b 100644 --- a/rosbag2_compression/src/rosbag2_compression/zstd_decompressor.cpp +++ b/rosbag2_compression/src/rosbag2_compression/zstd_decompressor.cpp @@ -88,9 +88,10 @@ std::vector get_input_buffer(const std::string & uri) compressed_buffer_length, file_pointer); if (read_count != compressed_buffer_length) { - ROSBAG2_COMPRESSION_LOG_ERROR_STREAM("Bytes read !(" << - read_count << ") != compressed_buffer size (" << compressed_buffer.size() << - ")!"); + ROSBAG2_COMPRESSION_LOG_ERROR_STREAM( + "Bytes read !(" << + read_count << ") != compressed_buffer size (" << compressed_buffer.size() << + ")!"); // An error indicator is set by fread, so the following check will throw. } @@ -136,9 +137,10 @@ void write_output_buffer( output_buffer.size(), file_pointer); if (write_count != output_buffer.size()) { - ROSBAG2_COMPRESSION_LOG_ERROR_STREAM("Bytes written (" << - write_count << " != output_buffer size (" << output_buffer.size() << - ")!"); + ROSBAG2_COMPRESSION_LOG_ERROR_STREAM( + "Bytes written (" << + write_count << " != output_buffer size (" << output_buffer.size() << + ")!"); // An error indicator is set by fwrite, so the following check will throw. } diff --git a/rosbag2_converter_default_plugins/src/rosbag2_converter_default_plugins/cdr/cdr_converter.cpp b/rosbag2_converter_default_plugins/src/rosbag2_converter_default_plugins/cdr/cdr_converter.cpp index cd875ca2fd..144a6b06c6 100644 --- a/rosbag2_converter_default_plugins/src/rosbag2_converter_default_plugins/cdr/cdr_converter.cpp +++ b/rosbag2_converter_default_plugins/src/rosbag2_converter_default_plugins/cdr/cdr_converter.cpp @@ -131,5 +131,6 @@ void CdrConverter::serialize( } // namespace rosbag2_converter_default_plugins #include "pluginlib/class_list_macros.hpp" // NOLINT -PLUGINLIB_EXPORT_CLASS(rosbag2_converter_default_plugins::CdrConverter, +PLUGINLIB_EXPORT_CLASS( + rosbag2_converter_default_plugins::CdrConverter, rosbag2_cpp::converter_interfaces::SerializationFormatConverter) diff --git a/rosbag2_cpp/src/rosbag2_cpp/info.cpp b/rosbag2_cpp/src/rosbag2_cpp/info.cpp index f7009b6e77..cc26a3b2e6 100644 --- a/rosbag2_cpp/src/rosbag2_cpp/info.cpp +++ b/rosbag2_cpp/src/rosbag2_cpp/info.cpp @@ -36,13 +36,15 @@ rosbag2_storage::BagMetadata Info::read_metadata( std::shared_ptr storage; storage = factory.open_read_only(uri, storage_id); if (!storage) { - throw std::runtime_error("The metadata.yaml file does not exist and the bag could not be " + throw std::runtime_error( + "The metadata.yaml file does not exist and the bag could not be " "opened."); } auto bag_metadata = storage->get_metadata(); return bag_metadata; } - throw std::runtime_error("The metadata.yaml file does not exist. Please specify a the " + throw std::runtime_error( + "The metadata.yaml file does not exist. Please specify a the " "storage id of the bagfile to query it directly"); } 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 d15a4f1d03..ff299a538e 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 @@ -77,10 +77,12 @@ class SerializationFormatConverterFactoryImpl const std::vector & registered_converter_classes, const std::vector & registered_interface_classes) { - auto class_exists_in_converters = std::find(registered_converter_classes.begin(), - registered_converter_classes.end(), converter_id); - auto class_exists_in_deserializers = std::find(registered_interface_classes.begin(), - registered_interface_classes.end(), converter_id); + auto class_exists_in_converters = std::find( + registered_converter_classes.begin(), + registered_converter_classes.end(), converter_id); + auto class_exists_in_deserializers = std::find( + registered_interface_classes.begin(), + registered_interface_classes.end(), converter_id); return class_exists_in_converters == registered_converter_classes.end() && class_exists_in_deserializers == registered_interface_classes.end(); } diff --git a/rosbag2_cpp/test/rosbag2_cpp/converter_test_plugin.cpp b/rosbag2_cpp/test/rosbag2_cpp/converter_test_plugin.cpp index 6d61fc5d02..081ba06170 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/converter_test_plugin.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/converter_test_plugin.cpp @@ -38,5 +38,5 @@ void ConverterTestPlugin::serialize( } #include "pluginlib/class_list_macros.hpp" // NOLINT -PLUGINLIB_EXPORT_CLASS(ConverterTestPlugin, - rosbag2_cpp::converter_interfaces::SerializationFormatConverter) +PLUGINLIB_EXPORT_CLASS( + ConverterTestPlugin, rosbag2_cpp::converter_interfaces::SerializationFormatConverter) diff --git a/rosbag2_cpp/test/rosbag2_cpp/mock_converter.hpp b/rosbag2_cpp/test/rosbag2_cpp/mock_converter.hpp index e91dc75563..86b87e4c3c 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/mock_converter.hpp +++ b/rosbag2_cpp/test/rosbag2_cpp/mock_converter.hpp @@ -27,13 +27,15 @@ class MockConverter : public rosbag2_cpp::converter_interfaces::SerializationFormatConverter { public: - MOCK_METHOD3(deserialize, + MOCK_METHOD3( + deserialize, void( std::shared_ptr, const rosidl_message_type_support_t *, std::shared_ptr)); - MOCK_METHOD3(serialize, + MOCK_METHOD3( + serialize, void( std::shared_ptr, const rosidl_message_type_support_t *, diff --git a/rosbag2_cpp/test/rosbag2_cpp/mock_converter_factory.hpp b/rosbag2_cpp/test/rosbag2_cpp/mock_converter_factory.hpp index 189daf1499..9f76cebfac 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/mock_converter_factory.hpp +++ b/rosbag2_cpp/test/rosbag2_cpp/mock_converter_factory.hpp @@ -25,11 +25,13 @@ class MockConverterFactory : public rosbag2_cpp::SerializationFormatConverterFactoryInterface { public: - MOCK_METHOD1(load_serializer, + MOCK_METHOD1( + load_serializer, std::unique_ptr( const std::string &)); - MOCK_METHOD1(load_deserializer, + MOCK_METHOD1( + load_deserializer, std::unique_ptr( const std::string &)); }; diff --git a/rosbag2_cpp/test/rosbag2_cpp/mock_storage_factory.hpp b/rosbag2_cpp/test/rosbag2_cpp/mock_storage_factory.hpp index e0faeca986..b1a844a254 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/mock_storage_factory.hpp +++ b/rosbag2_cpp/test/rosbag2_cpp/mock_storage_factory.hpp @@ -27,10 +27,12 @@ class MockStorageFactory : public rosbag2_storage::StorageFactoryInterface { public: - MOCK_METHOD2(open_read_only, + MOCK_METHOD2( + open_read_only, std::shared_ptr( const std::string &, const std::string &)); - MOCK_METHOD2(open_read_write, + MOCK_METHOD2( + open_read_write, std::shared_ptr( const std::string &, const std::string &)); }; diff --git a/rosbag2_cpp/test/rosbag2_cpp/serializer_test_plugin.cpp b/rosbag2_cpp/test/rosbag2_cpp/serializer_test_plugin.cpp index 8688bad4ee..30eea1916d 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/serializer_test_plugin.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/serializer_test_plugin.cpp @@ -27,5 +27,6 @@ void SerializerTestPlugin::serialize( } #include "pluginlib/class_list_macros.hpp" // NOLINT -PLUGINLIB_EXPORT_CLASS(SerializerTestPlugin, +PLUGINLIB_EXPORT_CLASS( + SerializerTestPlugin, rosbag2_cpp::converter_interfaces::SerializationFormatSerializer) diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_converter_factory.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_converter_factory.cpp index c94745c4b5..5b99b9c8e5 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_converter_factory.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_converter_factory.cpp @@ -27,7 +27,8 @@ class ConverterFactoryTest : public Test rosbag2_cpp::SerializationFormatConverterFactory factory; }; -TEST_F(ConverterFactoryTest, +TEST_F( + ConverterFactoryTest, load_test_plugin_can_load_a_converter_plugin_as_both_deserializer_and_serializer) { auto deserializer = factory.load_deserializer("a"); diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp index 6bb7d627a8..36761db9f1 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp @@ -136,31 +136,39 @@ TEST_F(TemporaryDirectoryFixture, read_metadata_makes_appropriate_call_to_metada auto read_metadata = info.read_metadata(temporary_dir_path_, "sqlite3"); EXPECT_THAT(read_metadata.storage_identifier, Eq("sqlite3")); - EXPECT_THAT(read_metadata.relative_file_paths, + EXPECT_THAT( + read_metadata.relative_file_paths, Eq(std::vector({"some_relative_path", "some_other_relative_path"}))); EXPECT_THAT(read_metadata.duration, Eq(std::chrono::nanoseconds(100))); - EXPECT_THAT(read_metadata.starting_time, - Eq(std::chrono::time_point( - std::chrono::nanoseconds(1000000)))); + EXPECT_THAT( + read_metadata.starting_time, + Eq( + std::chrono::time_point( + std::chrono::nanoseconds(1000000)))); EXPECT_THAT(read_metadata.message_count, Eq(50u)); - EXPECT_THAT(read_metadata.topics_with_message_count, - SizeIs(2u)); + EXPECT_THAT(read_metadata.topics_with_message_count, SizeIs(2u)); auto actual_first_topic = read_metadata.topics_with_message_count[0]; rosbag2_storage::TopicInformation expected_first_topic = {{"topic1", "type1", "rmw1"}, 100}; - EXPECT_THAT(actual_first_topic.topic_metadata.name, + EXPECT_THAT( + actual_first_topic.topic_metadata.name, Eq(expected_first_topic.topic_metadata.name)); - EXPECT_THAT(actual_first_topic.topic_metadata.type, + EXPECT_THAT( + actual_first_topic.topic_metadata.type, Eq(expected_first_topic.topic_metadata.type)); - EXPECT_THAT(actual_first_topic.topic_metadata.serialization_format, + EXPECT_THAT( + actual_first_topic.topic_metadata.serialization_format, Eq(expected_first_topic.topic_metadata.serialization_format)); EXPECT_THAT(actual_first_topic.message_count, Eq(expected_first_topic.message_count)); auto actual_second_topic = read_metadata.topics_with_message_count[1]; rosbag2_storage::TopicInformation expected_second_topic = {{"topic2", "type2", "rmw2"}, 200}; - EXPECT_THAT(actual_second_topic.topic_metadata.name, + EXPECT_THAT( + actual_second_topic.topic_metadata.name, Eq(expected_second_topic.topic_metadata.name)); - EXPECT_THAT(actual_second_topic.topic_metadata.type, + EXPECT_THAT( + actual_second_topic.topic_metadata.type, Eq(expected_second_topic.topic_metadata.type)); - EXPECT_THAT(actual_second_topic.topic_metadata.serialization_format, + EXPECT_THAT( + actual_second_topic.topic_metadata.serialization_format, Eq(expected_second_topic.topic_metadata.serialization_format)); EXPECT_THAT(actual_second_topic.message_count, Eq(expected_second_topic.message_count)); diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp index e346abfcfb..44d7dd1c8a 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp @@ -105,7 +105,8 @@ TEST_F(SequentialReaderTest, open_throws_error_if_converter_plugin_does_not_exis EXPECT_ANY_THROW(reader_->open(rosbag2_cpp::StorageOptions(), {"", output_format})); } -TEST_F(SequentialReaderTest, +TEST_F( + SequentialReaderTest, read_next_does_not_use_converters_if_input_and_output_format_are_equal) { std::string storage_serialization_format = "rmw1_format"; diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp index 5b61f74467..2ecca15019 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp @@ -49,10 +49,11 @@ class SequentialWriterTest : public Test ON_CALL(*storage_factory_, open_read_write(_, _)).WillByDefault( DoAll( - Invoke([this](const std::string & uri, const std::string &) { - fake_storage_size_ = 0; - fake_storage_uri_ = uri; - }), + Invoke( + [this](const std::string & uri, const std::string &) { + fake_storage_size_ = 0; + fake_storage_uri_ = uri; + }), Return(storage_))); EXPECT_CALL( *storage_factory_, open_read_write(_, _)).Times(AtLeast(0)); @@ -69,7 +70,8 @@ class SequentialWriterTest : public Test std::string fake_storage_uri_; }; -TEST_F(SequentialWriterTest, +TEST_F( + SequentialWriterTest, write_uses_converters_to_convert_serialization_format_if_input_and_output_format_are_different) { auto sequential_writer = std::make_unique( std::move(storage_factory_), converter_factory_, std::move(metadata_io_)); @@ -234,7 +236,8 @@ TEST_F(SequentialWriterTest, writer_splits_when_storage_bagfile_size_gt_max_bagf writer_.reset(); // metadata should be written now that the Writer was released. - EXPECT_EQ(fake_metadata_.relative_file_paths.size(), + EXPECT_EQ( + fake_metadata_.relative_file_paths.size(), static_cast(expected_splits)) << "Storage should have split bagfile " << (expected_splits - 1); diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_typesupport_helpers.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_typesupport_helpers.cpp index 00ca7d79be..52788a76a1 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_typesupport_helpers.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_typesupport_helpers.cpp @@ -68,7 +68,8 @@ TEST(TypesupportHelpersTest, returns_c_type_info_for_valid_legacy_library) { auto string_typesupport = rosbag2_cpp::get_typesupport("test_msgs/BasicTypes", "rosidl_typesupport_cpp"); - EXPECT_THAT(std::string(string_typesupport->typesupport_identifier), + EXPECT_THAT( + std::string(string_typesupport->typesupport_identifier), ContainsRegex("rosidl_typesupport")); } @@ -76,6 +77,7 @@ TEST(TypesupportHelpersTest, returns_c_type_info_for_valid_library) { auto string_typesupport = rosbag2_cpp::get_typesupport("test_msgs/msg/BasicTypes", "rosidl_typesupport_cpp"); - EXPECT_THAT(std::string(string_typesupport->typesupport_identifier), + EXPECT_THAT( + std::string(string_typesupport->typesupport_identifier), ContainsRegex("rosidl_typesupport")); } diff --git a/rosbag2_storage/src/rosbag2_storage/ros_helper.cpp b/rosbag2_storage/src/rosbag2_storage/ros_helper.cpp index 935afe42cc..c2ae9eabc2 100644 --- a/rosbag2_storage/src/rosbag2_storage/ros_helper.cpp +++ b/rosbag2_storage/src/rosbag2_storage/ros_helper.cpp @@ -42,19 +42,21 @@ make_empty_serialized_message(size_t size) *msg = rcutils_get_zero_initialized_uint8_array(); auto ret = rcutils_uint8_array_init(msg, size, &allocator); if (ret != RCUTILS_RET_OK) { - throw std::runtime_error("Error allocating resources for serialized message: " + + throw std::runtime_error( + "Error allocating resources for serialized message: " + std::string(rcutils_get_error_string().str)); } - auto serialized_message = std::shared_ptr(msg, - [](rcutils_uint8_array_t * msg) { - int error = rcutils_uint8_array_fini(msg); - delete msg; - if (error != RCUTILS_RET_OK) { - ROSBAG2_STORAGE_LOG_ERROR_STREAM( - "Leaking memory. Error: " << rcutils_get_error_string().str); - } - }); + auto serialized_message = std::shared_ptr( + msg, + [](rcutils_uint8_array_t * msg) { + int error = rcutils_uint8_array_fini(msg); + delete msg; + if (error != RCUTILS_RET_OK) { + ROSBAG2_STORAGE_LOG_ERROR_STREAM( + "Leaking memory. Error: " << rcutils_get_error_string().str); + } + }); return serialized_message; } diff --git a/rosbag2_storage/test/rosbag2_storage/test_metadata_serialization.cpp b/rosbag2_storage/test/rosbag2_storage/test_metadata_serialization.cpp index 7eda04d5fa..4c1f63f652 100644 --- a/rosbag2_storage/test/rosbag2_storage/test_metadata_serialization.cpp +++ b/rosbag2_storage/test/rosbag2_storage/test_metadata_serialization.cpp @@ -65,24 +65,31 @@ TEST_F(MetadataFixture, test_writing_and_reading_yaml) EXPECT_THAT(read_metadata.duration, Eq(metadata.duration)); EXPECT_THAT(read_metadata.starting_time, Eq(metadata.starting_time)); EXPECT_THAT(read_metadata.message_count, Eq(metadata.message_count)); - EXPECT_THAT(read_metadata.topics_with_message_count, + EXPECT_THAT( + read_metadata.topics_with_message_count, SizeIs(metadata.topics_with_message_count.size())); auto actual_first_topic = read_metadata.topics_with_message_count[0]; auto expected_first_topic = metadata.topics_with_message_count[0]; - EXPECT_THAT(actual_first_topic.topic_metadata.name, + EXPECT_THAT( + actual_first_topic.topic_metadata.name, Eq(expected_first_topic.topic_metadata.name)); - EXPECT_THAT(actual_first_topic.topic_metadata.type, + EXPECT_THAT( + actual_first_topic.topic_metadata.type, Eq(expected_first_topic.topic_metadata.type)); - EXPECT_THAT(actual_first_topic.topic_metadata.serialization_format, + EXPECT_THAT( + actual_first_topic.topic_metadata.serialization_format, Eq(expected_first_topic.topic_metadata.serialization_format)); EXPECT_THAT(actual_first_topic.message_count, Eq(expected_first_topic.message_count)); auto actual_second_topic = read_metadata.topics_with_message_count[1]; auto expected_second_topic = metadata.topics_with_message_count[1]; - EXPECT_THAT(actual_second_topic.topic_metadata.name, + EXPECT_THAT( + actual_second_topic.topic_metadata.name, Eq(expected_second_topic.topic_metadata.name)); - EXPECT_THAT(actual_second_topic.topic_metadata.type, + EXPECT_THAT( + actual_second_topic.topic_metadata.type, Eq(expected_second_topic.topic_metadata.type)); - EXPECT_THAT(actual_second_topic.topic_metadata.serialization_format, + EXPECT_THAT( + actual_second_topic.topic_metadata.serialization_format, Eq(expected_second_topic.topic_metadata.serialization_format)); EXPECT_THAT(actual_second_topic.message_count, Eq(expected_second_topic.message_count)); } diff --git a/rosbag2_storage_default_plugins/include/rosbag2_storage_default_plugins/sqlite/sqlite_statement_wrapper.hpp b/rosbag2_storage_default_plugins/include/rosbag2_storage_default_plugins/sqlite/sqlite_statement_wrapper.hpp index 9496188b17..dd1f36a58c 100644 --- a/rosbag2_storage_default_plugins/include/rosbag2_storage_default_plugins/sqlite/sqlite_statement_wrapper.hpp +++ b/rosbag2_storage_default_plugins/include/rosbag2_storage_default_plugins/sqlite/sqlite_statement_wrapper.hpp @@ -224,7 +224,8 @@ inline void SqliteStatementWrapper::check_and_report_bind_error(int return_code, std::string value) { if (return_code != SQLITE_OK) { - throw SqliteException("SQLite error when binding parameter " + + throw SqliteException( + "SQLite error when binding parameter " + std::to_string(last_bound_parameter_index_) + " to value '" + value + "'. Return code: " + std::to_string(return_code)); } diff --git a/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp b/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp index 44a6d08d82..61e4c99eb5 100644 --- a/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp +++ b/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp @@ -103,8 +103,8 @@ void SqliteStorage::open( read_statement_ = nullptr; write_statement_ = nullptr; - ROSBAG2_STORAGE_DEFAULT_PLUGINS_LOG_INFO_STREAM("Opened database '" << - relative_path_ << "' for " << to_string(io_flag) << "."); + ROSBAG2_STORAGE_DEFAULT_PLUGINS_LOG_INFO_STREAM( + "Opened database '" << relative_path_ << "' for " << to_string(io_flag) << "."); } void SqliteStorage::write(std::shared_ptr message) @@ -114,7 +114,8 @@ void SqliteStorage::write(std::shared_ptrtopic_name); if (topic_entry == end(topics_)) { - throw SqliteException("Topic '" + message->topic_name + + throw SqliteException( + "Topic '" + message->topic_name + "' has not been created yet! Call 'create_topic' first."); } @@ -294,5 +295,6 @@ rosbag2_storage::BagMetadata SqliteStorage::get_metadata() } // namespace rosbag2_storage_plugins #include "pluginlib/class_list_macros.hpp" // NOLINT -PLUGINLIB_EXPORT_CLASS(rosbag2_storage_plugins::SqliteStorage, +PLUGINLIB_EXPORT_CLASS( + rosbag2_storage_plugins::SqliteStorage, rosbag2_storage::storage_interfaces::ReadWriteInterface) diff --git a/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_wrapper.cpp b/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_wrapper.cpp index c327026d1c..2e988d5c24 100644 --- a/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_wrapper.cpp +++ b/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_wrapper.cpp @@ -35,8 +35,9 @@ SqliteWrapper::SqliteWrapper( : db_ptr(nullptr) { if (io_flag == rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY) { - int rc = sqlite3_open_v2(uri.c_str(), &db_ptr, - SQLITE_OPEN_READONLY | SQLITE_OPEN_NOMUTEX, nullptr); + int rc = sqlite3_open_v2( + uri.c_str(), &db_ptr, + SQLITE_OPEN_READONLY | SQLITE_OPEN_NOMUTEX, nullptr); if (rc != SQLITE_OK) { std::stringstream errmsg; errmsg << "Could not read-only open database. SQLite error (" << @@ -46,8 +47,9 @@ SqliteWrapper::SqliteWrapper( // throws an exception if the database is not valid. prepare_statement("PRAGMA schema_version;")->execute_and_reset(); } else { - int rc = sqlite3_open_v2(uri.c_str(), &db_ptr, - SQLITE_OPEN_READWRITE | SQLITE_OPEN_CREATE | SQLITE_OPEN_NOMUTEX, nullptr); + int rc = sqlite3_open_v2( + uri.c_str(), &db_ptr, + SQLITE_OPEN_READWRITE | SQLITE_OPEN_CREATE | SQLITE_OPEN_NOMUTEX, nullptr); if (rc != SQLITE_OK) { std::stringstream errmsg; errmsg << "Could not read-write open database. SQLite error (" << diff --git a/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/storage_test_fixture.hpp b/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/storage_test_fixture.hpp index 833effc0d3..3c2d263cf3 100644 --- a/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/storage_test_fixture.hpp +++ b/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/storage_test_fixture.hpp @@ -60,15 +60,16 @@ class StorageTestFixture : public TemporaryDirectoryFixture throw std::runtime_error("Error allocating resources " + std::to_string(ret)); } - auto serialized_data = std::shared_ptr(msg, - [](rcutils_uint8_array_t * msg) { - int error = rcutils_uint8_array_fini(msg); - delete msg; - if (error != RCUTILS_RET_OK) { - RCUTILS_LOG_ERROR_NAMED( - "rosbag2_storage_default_plugins", "Leaking memory %i", error); - } - }); + auto serialized_data = std::shared_ptr( + msg, + [](rcutils_uint8_array_t * msg) { + int error = rcutils_uint8_array_fini(msg); + delete msg; + if (error != RCUTILS_RET_OK) { + RCUTILS_LOG_ERROR_NAMED( + "rosbag2_storage_default_plugins", "Leaking memory %i", error); + } + }); serialized_data->buffer_length = message_size; int written_size = write_data_to_serialized_string_message( @@ -145,11 +146,12 @@ class StorageTestFixture : public TemporaryDirectoryFixture { // This function also writes the final null charachter, which is absent in the CDR format. // Here this behaviour is ok, because we only test test writing and reading from/to sqlite. - return rcutils_snprintf(reinterpret_cast(buffer), - buffer_capacity, - "%c%c%c%c%c%c%c%c%s", - 0x00, 0x01, 0x00, 0x00, 0x0f, 0x00, 0x00, 0x00, - message.c_str()); + return rcutils_snprintf( + reinterpret_cast(buffer), + buffer_capacity, + "%c%c%c%c%c%c%c%c%s", + 0x00, 0x01, 0x00, 0x00, 0x0f, 0x00, 0x00, 0x00, + message.c_str()); } rcutils_allocator_t allocator_; diff --git a/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/test_sqlite_storage.cpp b/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/test_sqlite_storage.cpp index e86a4c5334..e989f5d862 100644 --- a/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/test_sqlite_storage.cpp +++ b/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/test_sqlite_storage.cpp @@ -131,7 +131,9 @@ TEST_F(StorageTestFixture, get_all_topics_and_types_returns_the_correct_vector) read_only_filename, rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY); auto topics_and_types = readable_storage->get_all_topics_and_types(); - EXPECT_THAT(topics_and_types, ElementsAreArray({ + EXPECT_THAT( + topics_and_types, ElementsAreArray( + { rosbag2_storage::TopicMetadata{"topic1", "type1", "rmw1"}, rosbag2_storage::TopicMetadata{"topic2", "type2", "rmw2"} })); @@ -158,14 +160,17 @@ TEST_F(StorageTestFixture, get_metadata_returns_correct_struct) { EXPECT_THAT(metadata.storage_identifier, Eq("sqlite3")); EXPECT_THAT(metadata.relative_file_paths, ElementsAreArray({db_filename})); - EXPECT_THAT(metadata.topics_with_message_count, ElementsAreArray({ + EXPECT_THAT( + metadata.topics_with_message_count, ElementsAreArray( + { rosbag2_storage::TopicInformation{rosbag2_storage::TopicMetadata{ "topic1", "type1", "rmw_format"}, 2u}, rosbag2_storage::TopicInformation{rosbag2_storage::TopicMetadata{ "topic2", "type2", "rmw_format"}, 1u} })); EXPECT_THAT(metadata.message_count, Eq(3u)); - EXPECT_THAT(metadata.starting_time, Eq( + EXPECT_THAT( + metadata.starting_time, Eq( std::chrono::time_point(std::chrono::seconds(1)) )); EXPECT_THAT(metadata.duration, Eq(std::chrono::seconds(2))); @@ -184,7 +189,8 @@ TEST_F(StorageTestFixture, get_metadata_returns_correct_struct_if_no_messages) { EXPECT_THAT(metadata.relative_file_paths, ElementsAreArray({db_filename})); EXPECT_THAT(metadata.topics_with_message_count, IsEmpty()); EXPECT_THAT(metadata.message_count, Eq(0u)); - EXPECT_THAT(metadata.starting_time, Eq( + EXPECT_THAT( + metadata.starting_time, Eq( std::chrono::time_point(std::chrono::seconds(0)) )); EXPECT_THAT(metadata.duration, Eq(std::chrono::seconds(0))); @@ -208,7 +214,8 @@ TEST_F(StorageTestFixture, remove_topics_and_types_returns_the_empty_vector) { // Remove topics auto readable_storage = std::make_unique(); - readable_storage->open(read_only_filename, + readable_storage->open( + read_only_filename, rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY); auto topics_and_types = readable_storage->get_all_topics_and_types(); @@ -228,20 +235,23 @@ TEST_F(StorageTestFixture, get_relative_file_path_returns_db_name_with_ext) { const auto read_write_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string(); const auto storage_filename = read_write_filename + ".db3"; const auto read_write_storage = std::make_unique(); - read_write_storage->open(read_write_filename, + read_write_storage->open( + read_write_filename, rosbag2_storage::storage_interfaces::IOFlag::READ_WRITE); EXPECT_EQ(read_write_storage->get_relative_file_path(), storage_filename); // READ_ONLY expects uri to be the relative file path to the sqlite3 db. const auto & read_only_filename = storage_filename; const auto read_only_storage = std::make_unique(); - read_only_storage->open(read_only_filename, + read_only_storage->open( + read_only_filename, rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY); EXPECT_EQ(read_only_storage->get_relative_file_path(), storage_filename); const auto & append_filename = storage_filename; const auto append_storage = std::make_unique(); - append_storage->open(append_filename, + append_storage->open( + append_filename, rosbag2_storage::storage_interfaces::IOFlag::APPEND); EXPECT_EQ(append_storage->get_relative_file_path(), storage_filename); } diff --git a/rosbag2_test_common/include/rosbag2_test_common/memory_management.hpp b/rosbag2_test_common/include/rosbag2_test_common/memory_management.hpp index 2f42789c85..6ae39ead23 100644 --- a/rosbag2_test_common/include/rosbag2_test_common/memory_management.hpp +++ b/rosbag2_test_common/include/rosbag2_test_common/memory_management.hpp @@ -58,7 +58,8 @@ class MemoryManagement get_message_typesupport(message), message.get()); if (error != RCL_RET_OK) { - RCUTILS_LOG_ERROR_NAMED("rosbag2_test_common", "Leaking memory. Error: %s", + RCUTILS_LOG_ERROR_NAMED( + "rosbag2_test_common", "Leaking memory. Error: %s", rcutils_get_error_string().str); } return message; @@ -84,19 +85,22 @@ class MemoryManagement *msg = rmw_get_zero_initialized_serialized_message(); auto ret = rmw_serialized_message_init(msg, capacity, &rcutils_allocator_); if (ret != RCUTILS_RET_OK) { - throw std::runtime_error("Error allocating resources for serialized message: " + + throw std::runtime_error( + "Error allocating resources for serialized message: " + std::string(rcutils_get_error_string().str)); } - auto serialized_message = std::shared_ptr(msg, - [](rmw_serialized_message_t * msg) { - int error = rmw_serialized_message_fini(msg); - delete msg; - if (error != RCUTILS_RET_OK) { - RCUTILS_LOG_ERROR_NAMED("rosbag2_test_common", "Leaking memory. Error: %s", + auto serialized_message = std::shared_ptr( + msg, + [](rmw_serialized_message_t * msg) { + int error = rmw_serialized_message_fini(msg); + delete msg; + if (error != RCUTILS_RET_OK) { + RCUTILS_LOG_ERROR_NAMED( + "rosbag2_test_common", "Leaking memory. Error: %s", rcutils_get_error_string().str); - } - }); + } + }); return serialized_message; } diff --git a/rosbag2_test_common/include/rosbag2_test_common/publisher_manager.hpp b/rosbag2_test_common/include/rosbag2_test_common/publisher_manager.hpp index 4e47479890..a5704d9b48 100644 --- a/rosbag2_test_common/include/rosbag2_test_common/publisher_manager.hpp +++ b/rosbag2_test_common/include/rosbag2_test_common/publisher_manager.hpp @@ -84,7 +84,8 @@ class PublisherManager auto publisher = publisher_node->create_publisher(topic_name, 10); publisher_nodes_.push_back(publisher_node); - publishers_.push_back([publisher, topic_name, message, expected_messages]( + publishers_.push_back( + [publisher, topic_name, message, expected_messages]( CountFunction count_stored_messages) { if (expected_messages != 0) { while (rclcpp::ok() && count_stored_messages(topic_name) < expected_messages) { diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp index fe4aecbf43..b2ea61464b 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp @@ -40,7 +40,8 @@ TEST_F(InfoEndToEndTestFixture, info_end_to_end_test) { EXPECT_THAT(exit_code, Eq(EXIT_SUCCESS)); // The bag size depends on the os and is not asserted, the time is asserted time zone independent - EXPECT_THAT(output, ContainsRegex( + EXPECT_THAT( + output, ContainsRegex( "\nFiles: cdr_test\\.db3" "\nBag size: .*B" "\nStorage id: sqlite3" @@ -49,9 +50,11 @@ TEST_F(InfoEndToEndTestFixture, info_end_to_end_test) { "\nEnd Sep 18 2018 .*:.*:44.397 \\(1537282604\\.397\\)" "\nMessages: 7" "\nTopic information: ")); - EXPECT_THAT(output, HasSubstr( + EXPECT_THAT( + output, HasSubstr( "Topic: /test_topic | Type: test_msgs/BasicTypes | Count: 3 | Serialization Format: cdr\n")); - EXPECT_THAT(output, HasSubstr( + EXPECT_THAT( + output, HasSubstr( "Topic: /array_topic | Type: test_msgs/Arrays | Count: 4 | " "Serialization Format: cdr")); } diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_play_end_to_end.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_play_end_to_end.cpp index e051d0f79f..d436755533 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_play_end_to_end.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_play_end_to_end.cpp @@ -76,16 +76,25 @@ TEST_F(PlayEndToEndTestFixture, play_end_to_end_test) { EXPECT_THAT(exit_code, Eq(EXIT_SUCCESS)); EXPECT_THAT(primitive_messages, SizeIs(Ge(3u))); - EXPECT_THAT(primitive_messages, + EXPECT_THAT( + primitive_messages, Each(Pointee(Field(&test_msgs::msg::BasicTypes::string_value, "test")))); EXPECT_THAT(array_messages, SizeIs(Ge(2u))); - EXPECT_THAT(array_messages, - Each(Pointee(Field(&test_msgs::msg::Arrays::bool_values, - ElementsAre(true, false, true))))); - EXPECT_THAT(array_messages, - Each(Pointee(Field(&test_msgs::msg::Arrays::string_values, - ElementsAre("Complex Hello1", "Complex Hello2", "Complex Hello3"))))); + EXPECT_THAT( + array_messages, + Each( + Pointee( + Field( + &test_msgs::msg::Arrays::bool_values, + ElementsAre(true, false, true))))); + EXPECT_THAT( + array_messages, + Each( + Pointee( + Field( + &test_msgs::msg::Arrays::string_values, + ElementsAre("Complex Hello1", "Complex Hello2", "Complex Hello3"))))); } TEST_F(PlayEndToEndTestFixture, play_fails_gracefully_if_bag_does_not_exist) { diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp index f923d5dddc..679b84a6df 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp @@ -71,7 +71,8 @@ TEST_F(RecordFixture, record_end_to_end_test) { rosbag2_storage_plugins::SqliteWrapper db(database_path_, rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY); - pub_man_.run_publishers([this, &db](const std::string & topic_name) { + pub_man_.run_publishers( + [this, &db](const std::string & topic_name) { return count_stored_messages(db, topic_name); }); diff --git a/rosbag2_transport/src/rosbag2_transport/generic_subscription.cpp b/rosbag2_transport/src/rosbag2_transport/generic_subscription.cpp index 7f92299d8b..5abad2aacf 100644 --- a/rosbag2_transport/src/rosbag2_transport/generic_subscription.cpp +++ b/rosbag2_transport/src/rosbag2_transport/generic_subscription.cpp @@ -87,15 +87,16 @@ GenericSubscription::borrow_serialized_message(size_t capacity) rclcpp::exceptions::throw_from_rcl_error(init_return); } - auto serialized_msg = std::shared_ptr(message, - [](rmw_serialized_message_t * msg) { - auto fini_return = rmw_serialized_message_fini(msg); - delete msg; - if (fini_return != RCL_RET_OK) { - ROSBAG2_TRANSPORT_LOG_ERROR_STREAM( - "Failed to destroy serialized message: " << rcl_get_error_string().str); - } - }); + auto serialized_msg = std::shared_ptr( + message, + [](rmw_serialized_message_t * msg) { + auto fini_return = rmw_serialized_message_fini(msg); + delete msg; + if (fini_return != RCL_RET_OK) { + ROSBAG2_TRANSPORT_LOG_ERROR_STREAM( + "Failed to destroy serialized message: " << rcl_get_error_string().str); + } + }); return serialized_msg; } diff --git a/rosbag2_transport/src/rosbag2_transport/player.cpp b/rosbag2_transport/src/rosbag2_transport/player.cpp index f69b4e3f13..fd1319b988 100644 --- a/rosbag2_transport/src/rosbag2_transport/player.cpp +++ b/rosbag2_transport/src/rosbag2_transport/player.cpp @@ -60,8 +60,9 @@ void Player::play(const PlayOptions & options) { prepare_publishers(); - storage_loading_future_ = std::async(std::launch::async, - [this, options]() {load_storage_content(options);}); + storage_loading_future_ = std::async( + std::launch::async, + [this, options]() {load_storage_content(options);}); wait_for_filled_queue(options); @@ -124,7 +125,8 @@ void Player::play_messages_from_queue() do { play_messages_until_queue_empty(); if (!is_storage_completely_loaded() && rclcpp::ok()) { - ROSBAG2_TRANSPORT_LOG_WARN("Message queue starved. Messages will be delayed. Consider " + ROSBAG2_TRANSPORT_LOG_WARN( + "Message queue starved. Messages will be delayed. Consider " "increasing the --read-ahead-queue-size option."); } } while (!is_storage_completely_loaded() && rclcpp::ok()); @@ -145,7 +147,8 @@ void Player::prepare_publishers() { auto topics = reader_->get_all_topics_and_types(); for (const auto & topic : topics) { - publishers_.insert(std::make_pair( + publishers_.insert( + std::make_pair( topic.name, rosbag2_transport_->create_generic_publisher(topic.name, topic.type))); } } diff --git a/rosbag2_transport/src/rosbag2_transport/rosbag2_node.cpp b/rosbag2_transport/src/rosbag2_transport/rosbag2_node.cpp index 4a3be835de..fffa65b324 100644 --- a/rosbag2_transport/src/rosbag2_transport/rosbag2_node.cpp +++ b/rosbag2_transport/src/rosbag2_transport/rosbag2_node.cpp @@ -77,14 +77,15 @@ std::shared_ptr get_initialized_string_map() ROSBAG2_TRANSPORT_LOG_ERROR("Failed to initialize string map within rcutils."); return std::shared_ptr(); } - return std::shared_ptr(substitutions_map, - [](rcutils_string_map_t * map) { - rcl_ret_t cleanup = rcutils_string_map_fini(map); - delete map; - if (cleanup != RCL_RET_OK) { - ROSBAG2_TRANSPORT_LOG_ERROR("Failed to deallocate string map when expanding topic."); - } - }); + return std::shared_ptr( + substitutions_map, + [](rcutils_string_map_t * map) { + rcl_ret_t cleanup = rcutils_string_map_fini(map); + delete map; + if (cleanup != RCL_RET_OK) { + ROSBAG2_TRANSPORT_LOG_ERROR("Failed to deallocate string map when expanding topic."); + } + }); } std::string Rosbag2Node::expand_topic_name(const std::string & topic_name) @@ -135,8 +136,10 @@ std::unordered_map Rosbag2Node::get_topics_with_types( std::map> filtered_topics_and_types; for (const auto & topic_and_type : topics_and_types) { - if (std::find(sanitized_topic_names.begin(), sanitized_topic_names.end(), - topic_and_type.first) != sanitized_topic_names.end()) + if ( + std::find( + sanitized_topic_names.begin(), sanitized_topic_names.end(), + topic_and_type.first) != sanitized_topic_names.end()) { filtered_topics_and_types.insert(topic_and_type); } @@ -157,8 +160,9 @@ std::unordered_map Rosbag2Node::filter_topics_with_mor std::unordered_map filtered_topics_and_types; for (const auto & topic_and_type : topics_and_types) { if (topic_and_type.second.size() > 1) { - ROSBAG2_TRANSPORT_LOG_ERROR_STREAM("Topic '" << topic_and_type.first << - "' has several types associated. Only topics with one type are supported"); + ROSBAG2_TRANSPORT_LOG_ERROR_STREAM( + "Topic '" << topic_and_type.first << + "' has several types associated. Only topics with one type are supported"); } else { filtered_topics_and_types.insert({topic_and_type.first, topic_and_type.second[0]}); } diff --git a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport.cpp b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport.cpp index 43c4b21012..063e22d020 100644 --- a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport.cpp +++ b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport.cpp @@ -111,9 +111,10 @@ void Rosbag2Transport::print_bag_info(const std::string & uri, const std::string metadata = info_->read_metadata(uri, storage_id); } catch (std::runtime_error & e) { (void) e; - ROSBAG2_TRANSPORT_LOG_ERROR_STREAM("Could not read metadata for " << uri << ". Please specify " - "the path to the folder containing an existing 'metadata.yaml' file or provide correct " - "storage id if metadata file doesn't exist (see help)."); + ROSBAG2_TRANSPORT_LOG_ERROR_STREAM( + "Could not read metadata for " << uri << ". Please specify " + "the path to the folder containing an existing 'metadata.yaml' file or provide correct " + "storage id if metadata file doesn't exist (see help)."); return; } diff --git a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp index ae601f7458..f5974b6040 100644 --- a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp +++ b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp @@ -49,16 +49,18 @@ rosbag2_transport_record(PyObject * Py_UNUSED(self), PyObject * args, PyObject * uint64_t polling_interval_ms = 100; unsigned long long max_bagfile_size = 0; // NOLINT PyObject * topics = nullptr; - if (!PyArg_ParseTupleAndKeywords(args, kwargs, "ssss|bbKKO", const_cast(kwlist), - &uri, - &storage_id, - &serilization_format, - &node_prefix, - &all, - &no_discovery, - &polling_interval_ms, - &max_bagfile_size, - &topics)) + if ( + !PyArg_ParseTupleAndKeywords( + args, kwargs, "ssss|bbKKO", const_cast(kwlist), + &uri, + &storage_id, + &serilization_format, + &node_prefix, + &all, + &no_discovery, + &polling_interval_ms, + &max_bagfile_size, + &topics)) { return nullptr; } @@ -113,11 +115,12 @@ rosbag2_transport_play(PyObject * Py_UNUSED(self), PyObject * args, PyObject * k char * storage_id; char * node_prefix; size_t read_ahead_queue_size; - if (!PyArg_ParseTupleAndKeywords(args, kwargs, "sss|k", const_cast(kwlist), - &uri, - &storage_id, - &node_prefix, - &read_ahead_queue_size)) + if (!PyArg_ParseTupleAndKeywords( + args, kwargs, "sss|k", const_cast(kwlist), + &uri, + &storage_id, + &node_prefix, + &read_ahead_queue_size)) { return nullptr; } @@ -182,7 +185,8 @@ static PyMethodDef rosbag2_transport_methods[] = { # pragma GCC diagnostic pop #endif -PyDoc_STRVAR(rosbag2_transport__doc__, +PyDoc_STRVAR( + rosbag2_transport__doc__, "Python module for rosbag2 transport"); /// Define the Python module diff --git a/rosbag2_transport/test/rosbag2_transport/record_integration_fixture.hpp b/rosbag2_transport/test/rosbag2_transport/record_integration_fixture.hpp index 473dfcec30..119c4333ce 100644 --- a/rosbag2_transport/test/rosbag2_transport/record_integration_fixture.hpp +++ b/rosbag2_transport/test/rosbag2_transport/record_integration_fixture.hpp @@ -64,7 +64,8 @@ class RecordIntegrationTestFixture : public Rosbag2TransportTestFixture void run_publishers() { - pub_man_.run_publishers([this](const std::string & topic_name) { + pub_man_.run_publishers( + [this](const std::string & topic_name) { MockSequentialWriter & writer = static_cast(writer_->get_implementation_handle()); return writer.messages_per_topic()[topic_name]; diff --git a/rosbag2_transport/test/rosbag2_transport/test_info.cpp b/rosbag2_transport/test/rosbag2_transport/test_info.cpp index 48c5f18686..fbb858d008 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_info.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_info.cpp @@ -45,7 +45,8 @@ TEST_F(Rosbag2TransportTestFixture, info_pretty_prints_information_from_bagfile) transport.print_bag_info("test", "sqlite3"); std::string output = internal::GetCapturedStdout(); - EXPECT_THAT(output, ContainsRegex( + EXPECT_THAT( + output, ContainsRegex( "\nFiles: some_relative_path\n" " some_other_relative_path\n" "Bag size: 0 B\n" @@ -55,8 +56,10 @@ TEST_F(Rosbag2TransportTestFixture, info_pretty_prints_information_from_bagfile) "End Sep 27 2018 .*:.*:45.398 \\(1538051985\\.398\\)\n" "Messages: 50\n" "Topic information: ")); - EXPECT_THAT(output, HasSubstr( + EXPECT_THAT( + output, HasSubstr( "Topic: topic1 | Type: type1 | Count: 100 | Serialization Format: rmw1")); - EXPECT_THAT(output, HasSubstr( + EXPECT_THAT( + output, HasSubstr( "Topic: topic2 | Type: type2 | Count: 200 | Serialization Format: rmw2\n\n")); } diff --git a/rosbag2_transport/test/rosbag2_transport/test_play.cpp b/rosbag2_transport/test/rosbag2_transport/test_play.cpp index c118268c71..1fdb2a3a68 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play.cpp @@ -97,16 +97,25 @@ TEST_F(RosBag2PlayTestFixture, recorded_messages_are_played_for_all_topics) auto replayed_test_primitives = sub_->get_received_messages( "/topic1"); EXPECT_THAT(replayed_test_primitives, SizeIs(Ge(2u))); - EXPECT_THAT(replayed_test_primitives, + EXPECT_THAT( + replayed_test_primitives, Each(Pointee(Field(&test_msgs::msg::BasicTypes::int32_value, 42)))); auto replayed_test_arrays = sub_->get_received_messages( "/topic2"); EXPECT_THAT(replayed_test_arrays, SizeIs(Ge(2u))); - EXPECT_THAT(replayed_test_arrays, - Each(Pointee(Field(&test_msgs::msg::Arrays::bool_values, - ElementsAre(true, false, true))))); - EXPECT_THAT(replayed_test_arrays, - Each(Pointee(Field(&test_msgs::msg::Arrays::float32_values, - ElementsAre(40.0f, 2.0f, 0.0f))))); + EXPECT_THAT( + replayed_test_arrays, + Each( + Pointee( + Field( + &test_msgs::msg::Arrays::bool_values, + ElementsAre(true, false, true))))); + EXPECT_THAT( + replayed_test_arrays, + Each( + Pointee( + Field( + &test_msgs::msg::Arrays::float32_values, + ElementsAre(40.0f, 2.0f, 0.0f))))); } diff --git a/rosbag2_transport/test/rosbag2_transport/test_rosbag2_node.cpp b/rosbag2_transport/test/rosbag2_transport/test_rosbag2_node.cpp index 87104275a0..1539d5c337 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_rosbag2_node.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_rosbag2_node.cpp @@ -63,13 +63,14 @@ class RosBag2NodeFixture : public Test { std::vector messages; size_t counter = 0; - auto subscription = node_->create_generic_subscription(topic_name, type, - [this, &counter, &messages](std::shared_ptr message) { - auto string_message = - memory_management_.deserialize_message(message); - messages.push_back(string_message->string_value); - counter++; - }); + auto subscription = node_->create_generic_subscription( + topic_name, type, + [this, &counter, &messages](std::shared_ptr message) { + auto string_message = + memory_management_.deserialize_message(message); + messages.push_back(string_message->string_value); + counter++; + }); while (counter < expected_messages_number) { rclcpp::spin_some(node_); @@ -106,9 +107,10 @@ TEST_F(RosBag2NodeFixture, publisher_and_subscriber_work) auto publisher = node_->create_generic_publisher(topic_name, type); - auto subscriber_future_ = std::async(std::launch::async, [this, topic_name, type] { - return subscribe_raw_messages(1, topic_name, type); - }); + auto subscriber_future_ = std::async( + std::launch::async, [this, topic_name, type] { + return subscribe_raw_messages(1, topic_name, type); + }); // Give time to the subscriber to start. std::this_thread::sleep_for(std::chrono::milliseconds(100)); @@ -132,7 +134,8 @@ TEST_F(RosBag2NodeFixture, get_topics_with_types_returns_empty_if_topic_does_not ASSERT_THAT(topics_and_types, IsEmpty()); } -TEST_F(RosBag2NodeFixture, +TEST_F( + RosBag2NodeFixture, get_topics_with_types_returns_with_topic_string_if_topic_is_specified_without_slash) { create_publisher("string_topic"); @@ -144,7 +147,8 @@ TEST_F(RosBag2NodeFixture, EXPECT_THAT(topics_and_types.begin()->second, StrEq("test_msgs/msg/Strings")); } -TEST_F(RosBag2NodeFixture, +TEST_F( + RosBag2NodeFixture, get_topics_with_types_returns_with_topic_string_if_topic_is_specified_with_slash) { create_publisher("string_topic");