diff --git a/rosbag2_storage_mcap/src/mcap_storage.cpp b/rosbag2_storage_mcap/src/mcap_storage.cpp index 3b38e8f7fd..7641df0fba 100644 --- a/rosbag2_storage_mcap/src/mcap_storage.cpp +++ b/rosbag2_storage_mcap/src/mcap_storage.cpp @@ -825,7 +825,7 @@ void MCAPStorage::create_topic(const rosbag2_storage::TopicMetadata & topic, to_encode.reserve(topic_info.topic_metadata.offered_qos_profiles.size()); std::transform(topic_info.topic_metadata.offered_qos_profiles.begin(), topic_info.topic_metadata.offered_qos_profiles.end(), - to_encode.begin(), + std::back_inserter(to_encode), [](auto & qos) { return static_cast(qos); }); diff --git a/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp b/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp index 6244ebe48b..219e024d14 100644 --- a/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp +++ b/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp @@ -465,7 +465,7 @@ void SqliteStorage::create_topic( std::transform( topic.offered_qos_profiles.begin(), topic.offered_qos_profiles.end(), - to_encode.begin(), + std::back_inserter(to_encode), [](auto & qos) {return static_cast(qos);}); auto yaml_node = YAML::convert>::encode(to_encode); auto insert_topic = diff --git a/rosbag2_transport/src/rosbag2_transport/player.cpp b/rosbag2_transport/src/rosbag2_transport/player.cpp index 0294c3d025..52d6657a1c 100644 --- a/rosbag2_transport/src/rosbag2_transport/player.cpp +++ b/rosbag2_transport/src/rosbag2_transport/player.cpp @@ -82,7 +82,7 @@ rclcpp::QoS publisher_qos_for_topic( std::vector casted; casted.reserve(topic.offered_qos_profiles.size()); std::transform( - topic.offered_qos_profiles.begin(), topic.offered_qos_profiles.end(), casted.begin(), + topic.offered_qos_profiles.begin(), topic.offered_qos_profiles.end(), std::back_inserter(casted), [](auto & qos) {return static_cast(qos);}); return rosbag2_storage::Rosbag2QoS::adapt_offer_to_recorded_offers(topic.name, casted); } diff --git a/rosbag2_transport/test/rosbag2_transport/test_record.cpp b/rosbag2_transport/test/rosbag2_transport/test_record.cpp index 391030ff64..f100aaacd8 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record.cpp @@ -181,7 +181,7 @@ TEST_F(RecordIntegrationTestFixture, qos_is_stored_in_metadata) std::vector to_encode; to_encode.reserve(offered_qos_profiles.size()); std::transform( - offered_qos_profiles.begin(), offered_qos_profiles.end(), to_encode.begin(), + offered_qos_profiles.begin(), offered_qos_profiles.end(), std::back_inserter(to_encode), [](auto & qos) {return static_cast(qos);}); std::string serialized_profiles = YAML::convert>::encode( to_encode).as();