Skip to content

Commit

Permalink
Cpplint
Browse files Browse the repository at this point in the history
Signed-off-by: roncapat <[email protected]>
  • Loading branch information
roncapat committed Oct 25, 2023
1 parent 71d2780 commit 5814327
Show file tree
Hide file tree
Showing 3 changed files with 13 additions and 8 deletions.
1 change: 1 addition & 0 deletions rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define ROSBAG2_STORAGE__TOPIC_METADATA_HPP_

#include <string>
#include <vector>
#include "rclcpp/qos.hpp"

namespace rosbag2_storage
Expand Down
1 change: 1 addition & 0 deletions rosbag2_storage/include/rosbag2_storage/yaml.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#ifndef ROSBAG2_STORAGE__YAML_HPP_
#define ROSBAG2_STORAGE__YAML_HPP_

#include <algorithm>
#include <string>
#include <unordered_map>
#include <vector>
Expand Down
19 changes: 11 additions & 8 deletions rosbag2_storage_mcap/src/mcap_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -439,9 +439,11 @@ void MCAPStorage::read_metadata()
const auto metadata_it = channel.metadata.find("offered_qos_profiles");
if (metadata_it != channel.metadata.end()) {
auto node = YAML::Load(metadata_it->second);
auto decoded = YAML::decode_for_version<std::vector<rosbag2_storage::Rosbag2QoS>>(YAML::Load(metadata_it->second), metadata_.version);
auto decoded = YAML::decode_for_version<std::vector<rosbag2_storage::Rosbag2QoS>>(
YAML::Load(metadata_it->second), metadata_.version);
topic_info.topic_metadata.offered_qos_profiles.reserve(decoded.size());
std::copy(decoded.begin(), decoded.end(), topic_info.topic_metadata.offered_qos_profiles.begin());
std::copy(decoded.begin(), decoded.end(),
topic_info.topic_metadata.offered_qos_profiles.begin());
}
const auto type_hash_it = channel.metadata.find("topic_type_hash");
if (type_hash_it != channel.metadata.end()) {
Expand Down Expand Up @@ -818,14 +820,15 @@ void MCAPStorage::create_topic(const rosbag2_storage::TopicMetadata & topic,
channel.topic = topic.name;
channel.messageEncoding = topic_info.topic_metadata.serialization_format;
channel.schemaId = schema_id;

std::vector<rosbag2_storage::Rosbag2QoS> to_encode;
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(),
[](auto & qos){return static_cast<rosbag2_storage::Rosbag2QoS>(qos);});
std::transform(topic_info.topic_metadata.offered_qos_profiles.begin(),
topic_info.topic_metadata.offered_qos_profiles.end(),
to_encode.begin(),
[](auto & qos) {
return static_cast<rosbag2_storage::Rosbag2QoS>(qos);
});
auto yaml_node = YAML::convert<std::vector<rosbag2_storage::Rosbag2QoS>>::encode(to_encode);
channel.metadata.emplace("offered_qos_profiles", yaml_node.as<std::string>());
channel.metadata.emplace("topic_type_hash", topic_info.topic_metadata.type_description_hash);
Expand Down

0 comments on commit 5814327

Please sign in to comment.