Skip to content

Commit

Permalink
Various fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
roncapat committed Oct 26, 2023
1 parent 5628556 commit f01582c
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -604,7 +604,8 @@ void SqliteStorage::fill_topics_and_types()
yaml_node,
metadata_.version);
std::vector<rclcpp::QoS> offered_qos_profiles;
std::copy(decoded.begin(), decoded.end(), offered_qos_profiles.begin());
offered_qos_profiles.reserve(decoded.size());
std::copy(decoded.begin(), decoded.end(), std::back_inserter(offered_qos_profiles));
all_topics_and_types_.push_back(
{
std::get<0>(result),
Expand All @@ -625,7 +626,7 @@ void SqliteStorage::fill_topics_and_types()
yaml_node,
metadata_.version);
std::vector<rclcpp::QoS> offered_qos_profiles;
std::copy(decoded.begin(), decoded.end(), offered_qos_profiles.begin());
std::copy(decoded.begin(), decoded.end(), std::back_inserter(offered_qos_profiles));
all_topics_and_types_.push_back(
{std::get<0>(result), std::get<1>(result), std::get<2>(result), offered_qos_profiles,
""});
Expand Down Expand Up @@ -707,7 +708,7 @@ void SqliteStorage::read_metadata()
yaml_node,
metadata_.version);
std::vector<rclcpp::QoS> offered_qos_profiles;
std::copy(decoded.begin(), decoded.end(), offered_qos_profiles.begin());
std::copy(decoded.begin(), decoded.end(), std::back_inserter(offered_qos_profiles));
metadata_.topics_with_message_count.push_back(
{
{std::get<0>(result), std::get<1>(result), std::get<2>(
Expand Down Expand Up @@ -737,7 +738,7 @@ void SqliteStorage::read_metadata()
yaml_node,
metadata_.version);
std::vector<rclcpp::QoS> offered_qos_profiles;
std::copy(decoded.begin(), decoded.end(), offered_qos_profiles.begin());
std::copy(decoded.begin(), decoded.end(), std::back_inserter(offered_qos_profiles));
metadata_.topics_with_message_count.push_back(
{
{std::get<0>(result), std::get<1>(result), std::get<2>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,7 @@ TEST_F(StorageTestFixture, get_all_topics_and_types_returns_the_correct_vector)
topics_and_types, ElementsAreArray(
{
rosbag2_storage::TopicMetadata{"topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"},
rosbag2_storage::TopicMetadata{"topic2", "type2", "rmw2", {rclcpp::QoS(1)}, "type_hash2"}
rosbag2_storage::TopicMetadata{"topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}
}));
}

Expand Down Expand Up @@ -269,7 +269,7 @@ TEST_F(StorageTestFixture, get_metadata_returns_correct_struct) {
rosbag2_storage::TopicInformation{rosbag2_storage::TopicMetadata{
"topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, 2u},
rosbag2_storage::TopicInformation{rosbag2_storage::TopicMetadata{
"topic2", "type2", "rmw2", {rclcpp::QoS(1)}, "type_hash2"}, 1u}
"topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}, 1u}
}));
EXPECT_THAT(metadata.message_count, Eq(3u));
EXPECT_THAT(
Expand Down

0 comments on commit f01582c

Please sign in to comment.