diff --git a/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_reader.cpp b/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_reader.cpp index 2362bf8f7d..8f7b6fbf86 100644 --- a/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_reader.cpp +++ b/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_reader.cpp @@ -44,7 +44,7 @@ class SequentialCompressionReaderTest : public Test storage_serialization_format_{"rmw1_format"} { topic_with_type_ = rosbag2_storage::TopicMetadata{ - "topic", "test_msgs/BasicTypes", storage_serialization_format_, ""}; + "topic", "test_msgs/BasicTypes", storage_serialization_format_}; auto topics_and_types = std::vector{topic_with_type_}; auto message = std::make_shared(); message->topic_name = topic_with_type_.name; diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp index 21891bf1c9..36761db9f1 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp @@ -82,7 +82,7 @@ TEST_F(TemporaryDirectoryFixture, read_metadata_supports_version_2) { { const auto actual_first_topic = metadata.topics_with_message_count[0]; const auto expected_first_topic = - rosbag2_storage::TopicInformation{{"topic1", "type1", "rmw1", ""}, 100}; + rosbag2_storage::TopicInformation{{"topic1", "type1", "rmw1"}, 100}; EXPECT_EQ(actual_first_topic.topic_metadata, expected_first_topic.topic_metadata); EXPECT_EQ(actual_first_topic.message_count, expected_first_topic.message_count); @@ -91,7 +91,7 @@ TEST_F(TemporaryDirectoryFixture, read_metadata_supports_version_2) { { const auto actual_second_topic = metadata.topics_with_message_count[1]; const auto expected_second_topic = - rosbag2_storage::TopicInformation{{"topic2", "type2", "rmw2", ""}, 200}; + rosbag2_storage::TopicInformation{{"topic2", "type2", "rmw2"}, 200}; EXPECT_EQ(actual_second_topic.topic_metadata, expected_second_topic.topic_metadata); EXPECT_EQ(actual_second_topic.message_count, expected_second_topic.message_count); @@ -148,7 +148,7 @@ TEST_F(TemporaryDirectoryFixture, read_metadata_makes_appropriate_call_to_metada EXPECT_THAT(read_metadata.message_count, Eq(50u)); 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}; + rosbag2_storage::TopicInformation expected_first_topic = {{"topic1", "type1", "rmw1"}, 100}; EXPECT_THAT( actual_first_topic.topic_metadata.name, Eq(expected_first_topic.topic_metadata.name)); @@ -160,7 +160,7 @@ TEST_F(TemporaryDirectoryFixture, read_metadata_makes_appropriate_call_to_metada 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}; + rosbag2_storage::TopicInformation expected_second_topic = {{"topic2", "type2", "rmw2"}, 200}; EXPECT_THAT( actual_second_topic.topic_metadata.name, Eq(expected_second_topic.topic_metadata.name)); diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_multifile_reader.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_multifile_reader.cpp index d0e903db37..a78c875c3b 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_multifile_reader.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_multifile_reader.cpp @@ -43,7 +43,7 @@ class MultifileReaderTest : public Test relative_path_2_("some_relative_path_2") { auto topic_with_type = rosbag2_storage::TopicMetadata{ - "topic", "test_msgs/BasicTypes", storage_serialization_format_, ""}; + "topic", "test_msgs/BasicTypes", storage_serialization_format_}; auto topics_and_types = std::vector{topic_with_type}; auto message = std::make_shared(); diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp index af2d6d143c..2ecca15019 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp @@ -93,7 +93,7 @@ TEST_F( auto message = std::make_shared(); message->topic_name = "test_topic"; writer_->open(storage_options_, {input_format, storage_serialization_format}); - writer_->create_topic({"test_topic", "test_msgs/BasicTypes", "", ""}); + writer_->create_topic({"test_topic", "test_msgs/BasicTypes", ""}); writer_->write(message); } @@ -110,7 +110,7 @@ TEST_F(SequentialWriterTest, write_does_not_use_converters_if_input_and_output_f auto message = std::make_shared(); message->topic_name = "test_topic"; writer_->open(storage_options_, {storage_serialization_format, storage_serialization_format}); - writer_->create_topic({"test_topic", "test_msgs/BasicTypes", "", ""}); + writer_->create_topic({"test_topic", "test_msgs/BasicTypes", ""}); writer_->write(message); } @@ -179,7 +179,7 @@ TEST_F(SequentialWriterTest, bagfile_size_is_checked_on_every_write) { storage_options_.max_bagfile_size = max_bagfile_size; writer_->open(storage_options_, {rmw_format, rmw_format}); - writer_->create_topic({"test_topic", "test_msgs/BasicTypes", "", ""}); + writer_->create_topic({"test_topic", "test_msgs/BasicTypes", ""}); for (auto i = 0; i < counter; ++i) { writer_->write(message); @@ -227,7 +227,7 @@ TEST_F(SequentialWriterTest, writer_splits_when_storage_bagfile_size_gt_max_bagf storage_options_.max_bagfile_size = max_bagfile_size; writer_->open(storage_options_, {rmw_format, rmw_format}); - writer_->create_topic({"test_topic", "test_msgs/BasicTypes", "", ""}); + writer_->create_topic({"test_topic", "test_msgs/BasicTypes", ""}); for (auto i = 0; i < message_count; ++i) { writer_->write(message); diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_storage_without_metadata_file.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_storage_without_metadata_file.cpp index fd34ce4ce5..bae30812f2 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_storage_without_metadata_file.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_storage_without_metadata_file.cpp @@ -55,8 +55,7 @@ TEST_F(StorageWithoutMetadataFileTest, open_uses_storage_id_from_storage_options auto topic_with_type = rosbag2_storage::TopicMetadata{ "topic", "test_msgs/BasicTypes", - kRmwFormat, - "" + kRmwFormat }; auto topic_information = rosbag2_storage::TopicInformation{ diff --git a/rosbag2_storage/include/rosbag2_storage/bag_metadata.hpp b/rosbag2_storage/include/rosbag2_storage/bag_metadata.hpp index 9f2ffd13a5..706b30dd2c 100644 --- a/rosbag2_storage/include/rosbag2_storage/bag_metadata.hpp +++ b/rosbag2_storage/include/rosbag2_storage/bag_metadata.hpp @@ -33,7 +33,7 @@ struct TopicInformation struct BagMetadata { - int version = 4; // upgrade this number when changing the content of the struct + int version = 3; // upgrade this number when changing the content of the struct uint64_t bag_size = 0; // Will not be serialized std::string storage_identifier; std::vector relative_file_paths; diff --git a/rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp b/rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp index e43fa12fc1..155b562a1e 100644 --- a/rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp +++ b/rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp @@ -25,8 +25,6 @@ struct TopicMetadata std::string name; std::string type; std::string serialization_format; - // Serialized std::vector as a YAML string - std::string offered_qos_profiles; bool operator==(const rosbag2_storage::TopicMetadata & rhs) const { diff --git a/rosbag2_storage/src/rosbag2_storage/metadata_io.cpp b/rosbag2_storage/src/rosbag2_storage/metadata_io.cpp index 8806022de6..95df940aa4 100644 --- a/rosbag2_storage/src/rosbag2_storage/metadata_io.cpp +++ b/rosbag2_storage/src/rosbag2_storage/metadata_io.cpp @@ -48,7 +48,6 @@ struct convert node["name"] = topic.name; node["type"] = topic.type; node["serialization_format"] = topic.serialization_format; - node["offered_qos_profiles"] = topic.offered_qos_profiles; return node; } diff --git a/rosbag2_storage/test/rosbag2_storage/test_metadata_serialization.cpp b/rosbag2_storage/test/rosbag2_storage/test_metadata_serialization.cpp index f131055721..4c1f63f652 100644 --- a/rosbag2_storage/test/rosbag2_storage/test_metadata_serialization.cpp +++ b/rosbag2_storage/test/rosbag2_storage/test_metadata_serialization.cpp @@ -53,8 +53,8 @@ TEST_F(MetadataFixture, test_writing_and_reading_yaml) metadata.starting_time = std::chrono::time_point(std::chrono::nanoseconds(1000000)); metadata.message_count = 50; - metadata.topics_with_message_count.push_back({{"topic1", "type1", "rmw1", "qos1"}, 100}); - metadata.topics_with_message_count.push_back({{"topic2", "type2", "rmw2", "qos2"}, 200}); + metadata.topics_with_message_count.push_back({{"topic1", "type1", "rmw1"}, 100}); + metadata.topics_with_message_count.push_back({{"topic2", "type2", "rmw2"}, 200}); metadata_io_->write_metadata(temporary_dir_path_, metadata); auto read_metadata = metadata_io_->read_metadata(temporary_dir_path_); 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 bdc1e23e2e..0a33fe23b3 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 @@ -167,8 +167,7 @@ void SqliteStorage::initialize() "id INTEGER PRIMARY KEY," \ "name TEXT NOT NULL," \ "type TEXT NOT NULL," \ - "serialization_format TEXT NOT NULL," \ - "offered_qos_profiles TEXT NOT NULL);"; + "serialization_format TEXT NOT NULL);"; database_->prepare_statement(create_stmt)->execute_and_reset(); create_stmt = "CREATE TABLE messages(" \ "id INTEGER PRIMARY KEY," \ @@ -185,10 +184,8 @@ void SqliteStorage::create_topic(const rosbag2_storage::TopicMetadata & topic) if (topics_.find(topic.name) == std::end(topics_)) { auto insert_topic = database_->prepare_statement( - "INSERT INTO topics (name, type, serialization_format, offered_qos_profiles) " - "VALUES (?, ?, ?, ?)"); - insert_topic->bind( - topic.name, topic.type, topic.serialization_format, topic.offered_qos_profiles); + "INSERT INTO topics (name, type, serialization_format) VALUES (?, ?, ?)"); + insert_topic->bind(topic.name, topic.type, topic.serialization_format); insert_topic->execute_and_reset(); topics_.emplace(topic.name, static_cast(database_->get_last_insert_id())); } @@ -231,7 +228,7 @@ void SqliteStorage::fill_topics_and_types() for (auto result : query_results) { all_topics_and_types_.push_back( - {std::get<0>(result), std::get<1>(result), std::get<2>(result), ""}); + {std::get<0>(result), std::get<1>(result), std::get<2>(result)}); } } @@ -273,7 +270,7 @@ rosbag2_storage::BagMetadata SqliteStorage::get_metadata() for (auto result : query_results) { metadata.topics_with_message_count.push_back( { - {std::get<0>(result), std::get<1>(result), std::get<2>(result), ""}, + {std::get<0>(result), std::get<1>(result), std::get<2>(result)}, static_cast(std::get<3>(result)) }); 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 200f650d83..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 @@ -105,7 +105,7 @@ class StorageTestFixture : public TemporaryDirectoryFixture std::string topic_name = std::get<2>(msg); std::string type_name = std::get<3>(msg); std::string rmw_format = std::get<4>(msg); - writable_storage->create_topic({topic_name, type_name, rmw_format, ""}); + writable_storage->create_topic({topic_name, type_name, rmw_format}); auto bag_message = std::make_shared(); bag_message->serialized_data = make_serialized_message(std::get<0>(msg)); bag_message->time_stamp = std::get<1>(msg); 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 08b1dd5317..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 @@ -119,8 +119,8 @@ TEST_F(StorageTestFixture, get_all_topics_and_types_returns_the_correct_vector) const auto read_write_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string(); writable_storage->open(read_write_filename); - writable_storage->create_topic({"topic1", "type1", "rmw1", ""}); - writable_storage->create_topic({"topic2", "type2", "rmw2", ""}); + writable_storage->create_topic({"topic1", "type1", "rmw1"}); + writable_storage->create_topic({"topic2", "type2", "rmw2"}); const auto read_only_filename = writable_storage->get_relative_file_path(); @@ -134,8 +134,8 @@ TEST_F(StorageTestFixture, get_all_topics_and_types_returns_the_correct_vector) EXPECT_THAT( topics_and_types, ElementsAreArray( { - rosbag2_storage::TopicMetadata{"topic1", "type1", "rmw1", ""}, - rosbag2_storage::TopicMetadata{"topic2", "type2", "rmw2", ""} + rosbag2_storage::TopicMetadata{"topic1", "type1", "rmw1"}, + rosbag2_storage::TopicMetadata{"topic2", "type2", "rmw2"} })); } @@ -164,9 +164,9 @@ TEST_F(StorageTestFixture, get_metadata_returns_correct_struct) { metadata.topics_with_message_count, ElementsAreArray( { rosbag2_storage::TopicInformation{rosbag2_storage::TopicMetadata{ - "topic1", "type1", "rmw_format", ""}, 2u}, + "topic1", "type1", "rmw_format"}, 2u}, rosbag2_storage::TopicInformation{rosbag2_storage::TopicMetadata{ - "topic2", "type2", "rmw_format", ""}, 1u} + "topic2", "type2", "rmw_format"}, 1u} })); EXPECT_THAT(metadata.message_count, Eq(3u)); EXPECT_THAT( @@ -204,8 +204,8 @@ TEST_F(StorageTestFixture, remove_topics_and_types_returns_the_empty_vector) { const auto read_write_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string(); writable_storage->open(read_write_filename); - writable_storage->create_topic({"topic1", "type1", "rmw1", ""}); - writable_storage->remove_topic({"topic1", "type1", "rmw1", ""}); + writable_storage->create_topic({"topic1", "type1", "rmw1"}); + writable_storage->remove_topic({"topic1", "type1", "rmw1"}); const auto read_only_filename = writable_storage->get_relative_file_path(); diff --git a/rosbag2_transport/CMakeLists.txt b/rosbag2_transport/CMakeLists.txt index 31d9f2ad7e..d3e03076ba 100644 --- a/rosbag2_transport/CMakeLists.txt +++ b/rosbag2_transport/CMakeLists.txt @@ -35,7 +35,6 @@ add_library(${PROJECT_NAME} SHARED src/rosbag2_transport/formatter.cpp src/rosbag2_transport/generic_publisher.cpp src/rosbag2_transport/generic_subscription.cpp - src/rosbag2_transport/qos.cpp src/rosbag2_transport/recorder.cpp src/rosbag2_transport/rosbag2_node.cpp src/rosbag2_transport/rosbag2_transport.cpp) @@ -177,18 +176,6 @@ if(BUILD_TESTING) ament_target_dependencies(test_play test_msgs rosbag2_test_common) endif() - ament_add_gmock(test_qos - test/rosbag2_transport/test_qos.cpp - WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR} - ${SKIP_TEST}) - if(TARGET test_qos) - target_link_libraries(test_qos rosbag2_transport) - target_include_directories(test_qos - PUBLIC - $) - ament_target_dependencies(test_qos rosbag2_test_common) - endif() - endif() ament_package() diff --git a/rosbag2_transport/src/rosbag2_transport/qos.cpp b/rosbag2_transport/src/rosbag2_transport/qos.cpp deleted file mode 100644 index 00d2c5cbbf..0000000000 --- a/rosbag2_transport/src/rosbag2_transport/qos.cpp +++ /dev/null @@ -1,70 +0,0 @@ -// Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved. -// -// 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 "qos.hpp" - -namespace YAML -{ -Node convert::encode(const rmw_time_t & time) -{ - Node node; - node["sec"] = time.sec; - node["nsec"] = time.nsec; - return node; -} - -bool convert::decode(const Node & node, rmw_time_t & time) -{ - time.sec = node["sec"].as(); - time.nsec = node["nsec"].as(); - return true; -} - -Node convert::encode(const rosbag2_transport::Rosbag2QoS & qos) -{ - const auto & p = qos.get_rmw_qos_profile(); - Node node; - node["history"] = static_cast(p.history); - node["depth"] = p.depth; - node["reliability"] = static_cast(p.reliability); - node["durability"] = static_cast(p.durability); - node["deadline"] = p.deadline; - node["lifespan"] = p.lifespan; - node["liveliness"] = static_cast(p.liveliness); - node["liveliness_lease_duration"] = p.liveliness_lease_duration; - node["avoid_ros_namespace_conventions"] = p.avoid_ros_namespace_conventions; - return node; -} - -bool convert::decode( - const Node & node, rosbag2_transport::Rosbag2QoS & qos) -{ - auto history = static_cast(node["history"].as()); - auto reliability = static_cast(node["reliability"].as()); - auto durability = static_cast(node["durability"].as()); - auto liveliness = static_cast(node["liveliness"].as()); - - qos - .keep_last(node["depth"].as()) - .history(history) - .reliability(reliability) - .durability(durability) - .deadline(node["deadline"].as()) - .lifespan(node["lifespan"].as()) - .liveliness(liveliness) - .liveliness_lease_duration(node["liveliness_lease_duration"].as()) - .avoid_ros_namespace_conventions(node["avoid_ros_namespace_conventions"].as()); - return true; -} -} // namespace YAML diff --git a/rosbag2_transport/src/rosbag2_transport/qos.hpp b/rosbag2_transport/src/rosbag2_transport/qos.hpp deleted file mode 100644 index de8027f354..0000000000 --- a/rosbag2_transport/src/rosbag2_transport/qos.hpp +++ /dev/null @@ -1,66 +0,0 @@ -// Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved. -// -// 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. - -#ifndef ROSBAG2_TRANSPORT__QOS_HPP_ -#define ROSBAG2_TRANSPORT__QOS_HPP_ - -#include "rclcpp/qos.hpp" - -#ifdef _WIN32 -// This is necessary because of a bug in yaml-cpp's cmake -#define YAML_CPP_DLL -// This is necessary because yaml-cpp does not always use dllimport/dllexport consistently -# pragma warning(push) -# pragma warning(disable:4251) -# pragma warning(disable:4275) -#endif -#include "yaml-cpp/yaml.h" -#ifdef _WIN32 -# pragma warning(pop) -#endif - - -namespace rosbag2_transport -{ -/// Simple wrapper around rclcpp::QoS to provide a default constructor for YAML deserialization. -class Rosbag2QoS : public rclcpp::QoS -{ -public: - Rosbag2QoS() - : rclcpp::QoS(0) {} // 0 history depth is always overwritten on deserializing - explicit Rosbag2QoS(const rclcpp::QoS & value) - : rclcpp::QoS(value) {} -}; -} // namespace rosbag2_transport - - -namespace YAML -{ -template<> -struct convert -{ - static Node encode(const rmw_time_t & time); - static bool decode(const Node & node, rmw_time_t & time); -}; - -template<> -struct convert -{ - static Node encode(const rosbag2_transport::Rosbag2QoS & qos); - static bool decode(const Node & node, rosbag2_transport::Rosbag2QoS & qos); -}; -} // namespace YAML - - -#endif // ROSBAG2_TRANSPORT__QOS_HPP_ diff --git a/rosbag2_transport/src/rosbag2_transport/recorder.cpp b/rosbag2_transport/src/rosbag2_transport/recorder.cpp index 5eab2a2392..2551bed709 100644 --- a/rosbag2_transport/src/rosbag2_transport/recorder.cpp +++ b/rosbag2_transport/src/rosbag2_transport/recorder.cpp @@ -109,7 +109,7 @@ void Recorder::subscribe_topics( const std::unordered_map & topics_and_types) { for (const auto & topic_with_type : topics_and_types) { - subscribe_topic({topic_with_type.first, topic_with_type.second, serialization_format_, ""}); + subscribe_topic({topic_with_type.first, topic_with_type.second, serialization_format_}); } } diff --git a/rosbag2_transport/test/rosbag2_transport/test_formatter.cpp b/rosbag2_transport/test/rosbag2_transport/test_formatter.cpp index a43bf98bdb..84f3a578ce 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_formatter.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_formatter.cpp @@ -74,8 +74,8 @@ TEST_F(FormatterTestFixture, format_files_prints_newline_if_there_are_no_paths) TEST_F(FormatterTestFixture, format_topics_with_type_correctly_layouts_more_topics) { std::vector topics; - topics.push_back({{"topic1", "type1", "rmw1", ""}, 100}); - topics.push_back({{"topic2", "type2", "rmw2", ""}, 200}); + topics.push_back({{"topic1", "type1", "rmw1"}, 100}); + topics.push_back({{"topic2", "type2", "rmw2"}, 200}); std::stringstream formatted_output; formatter_->format_topics_with_type(topics, formatted_output, indentation_spaces_); diff --git a/rosbag2_transport/test/rosbag2_transport/test_info.cpp b/rosbag2_transport/test/rosbag2_transport/test_info.cpp index 94829111b3..fbb858d008 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_info.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_info.cpp @@ -36,8 +36,8 @@ TEST_F(Rosbag2TransportTestFixture, info_pretty_prints_information_from_bagfile) std::chrono::nanoseconds(1538051985348887471)); // corresponds to Sept 27 14:39:45.348 bagfile.duration = std::chrono::nanoseconds(50000000); bagfile.message_count = 50; - bagfile.topics_with_message_count.push_back({{"topic1", "type1", "rmw1", ""}, 100}); - bagfile.topics_with_message_count.push_back({{"topic2", "type2", "rmw2", ""}, 200}); + bagfile.topics_with_message_count.push_back({{"topic1", "type1", "rmw1"}, 100}); + bagfile.topics_with_message_count.push_back({{"topic2", "type2", "rmw2"}, 200}); EXPECT_CALL(*info_, read_metadata(_, _)).WillOnce(Return(bagfile)); // the expected output uses a regex to handle different time zones. diff --git a/rosbag2_transport/test/rosbag2_transport/test_play.cpp b/rosbag2_transport/test/rosbag2_transport/test_play.cpp index fedadd7a2d..1fdb2a3a68 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play.cpp @@ -66,8 +66,8 @@ TEST_F(RosBag2PlayTestFixture, recorded_messages_are_played_for_all_topics) complex_message1->bool_values = {{true, false, true}}; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", ""}, - {"topic2", "test_msgs/Arrays", "", ""}, + {"topic1", "test_msgs/BasicTypes", ""}, + {"topic2", "test_msgs/Arrays", ""}, }; std::vector> messages = diff --git a/rosbag2_transport/test/rosbag2_transport/test_play_timing.cpp b/rosbag2_transport/test/rosbag2_transport/test_play_timing.cpp index 695830eebf..7d7959df16 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play_timing.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play_timing.cpp @@ -43,7 +43,7 @@ TEST_F(Rosbag2TransportTestFixture, playing_respects_relative_timing_of_stored_m auto message_time_difference = std::chrono::seconds(1); auto topics_and_types = - std::vector{{"topic1", "test_msgs/Strings", "", ""}}; + std::vector{{"topic1", "test_msgs/Strings", ""}}; std::vector> messages = {serialize_test_message("topic1", 0, primitive_message1), serialize_test_message("topic1", 0, primitive_message2)}; @@ -79,7 +79,7 @@ TEST_F(Rosbag2TransportTestFixture, playing_respects_rate) auto message_time_difference = std::chrono::seconds(1); auto topics_and_types = - std::vector{{"topic1", "test_msgs/Strings", "", ""}}; + std::vector{{"topic1", "test_msgs/Strings", ""}}; std::vector> messages = {serialize_test_message("topic1", 0, primitive_message1), serialize_test_message("topic1", 0, primitive_message2)}; diff --git a/rosbag2_transport/test/rosbag2_transport/test_qos.cpp b/rosbag2_transport/test/rosbag2_transport/test_qos.cpp deleted file mode 100644 index 37f2e135eb..0000000000 --- a/rosbag2_transport/test/rosbag2_transport/test_qos.cpp +++ /dev/null @@ -1,98 +0,0 @@ -// Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved. -// -// 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 "rmw/types.h" - -#include "qos.hpp" - -TEST(TestQoS, serialization) -{ - rosbag2_transport::Rosbag2QoS expected_qos; - YAML::Node offered_qos_profiles; - offered_qos_profiles.push_back(expected_qos); - - std::string serialized = YAML::Dump(offered_qos_profiles); - YAML::Node loaded_node = YAML::Load(serialized); - auto deserialized_profiles = loaded_node.as>(); - ASSERT_EQ(deserialized_profiles.size(), 1u); - - rosbag2_transport::Rosbag2QoS actual_qos = deserialized_profiles[0]; - EXPECT_EQ(actual_qos, expected_qos); -} - -TEST(TestQoS, supports_version_4) -{ - // This test shows how this data looks at the time of introduction - // Bags created by this version of rosbag2 look like this and must be able to be read - std::string serialized_profiles = - "- history: 1\n" - " depth: 10\n" - " reliability: 1\n" - " durability: 2\n" - " deadline:\n" - " sec: 0\n" - " nsec: 0\n" - " lifespan:\n" - " sec: 0\n" - " nsec: 0\n" - " liveliness: 0\n" - " liveliness_lease_duration:\n" - " sec: 0\n" - " nsec: 0\n" - " avoid_ros_namespace_conventions: false\n"; - - YAML::Node loaded_node = YAML::Load(serialized_profiles); - auto deserialized_profiles = loaded_node.as>(); - ASSERT_EQ(deserialized_profiles.size(), 1u); - rosbag2_transport::Rosbag2QoS actual_qos = deserialized_profiles[0]; - - rmw_time_t zerotime{0, 0}; - // Explicitly set up the same QoS profile in case defaults change - rclcpp::QoS expected_qos(10); - expected_qos - .keep_last(10) - .reliable() - .durability_volatile() - .deadline(zerotime) - .lifespan(zerotime) - .liveliness(RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT) - .liveliness_lease_duration(zerotime) - .avoid_ros_namespace_conventions(false); - // Any values not present in the YAML should take the default value in both profiles - EXPECT_EQ(actual_qos, expected_qos); -} - -TEST(TestQoS, detect_new_qos_fields) -{ - // By trying to construct a profile explicitly by fields, the build fails if policies are added - // This build failure indicates that we need to update QoS serialization in rosbag2_transport - rmw_time_t notime{0, 0}; - rmw_qos_profile_t profile{ - RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT, - 10, - RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT, - RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT, - notime, - notime, - RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT, - notime, - false, - }; - EXPECT_EQ(profile.history, RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT); // fix "unused variable" -}