Skip to content

Commit

Permalink
Address review nitpicks
Browse files Browse the repository at this point in the history
Signed-off-by: Emerson Knapp <[email protected]>
  • Loading branch information
emersonknapp committed Mar 26, 2020
1 parent 383089b commit fd8b7fe
Show file tree
Hide file tree
Showing 4 changed files with 4 additions and 5 deletions.
2 changes: 1 addition & 1 deletion rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ struct TopicMetadata
std::string name;
std::string type;
std::string serialization_format;
// std::vector<rclcpp::QoS> serialized to YAML string
// Serialized std::vector<rclcpp::QoS> as a YAML string
std::string offered_qos_profiles;

bool operator==(const rosbag2_storage::TopicMetadata & rhs) const
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -231,7 +231,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), ""};
}
}

Expand Down Expand Up @@ -273,7 +273,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<size_t>(std::get<3>(result))
});

Expand Down
2 changes: 1 addition & 1 deletion rosbag2_transport/src/rosbag2_transport/qos.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ class Rosbag2QoS : public rclcpp::QoS
{
public:
Rosbag2QoS()
: rclcpp::QoS(10) {}
: rclcpp::QoS(0) {} // 0 history depth is always overwritten on deserializing
explicit Rosbag2QoS(const rclcpp::QoS & value)
: rclcpp::QoS(value) {}
};
Expand Down
1 change: 0 additions & 1 deletion rosbag2_transport/src/rosbag2_transport/recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,6 @@

#include "generic_subscription.hpp"
#include "rosbag2_node.hpp"
#include "qos.hpp"

namespace rosbag2_transport
{
Expand Down

0 comments on commit fd8b7fe

Please sign in to comment.