Skip to content

Commit

Permalink
Display bag summary using ros2 bag info
Browse files Browse the repository at this point in the history
  • Loading branch information
greimela-si committed Oct 11, 2018
1 parent 98e4be7 commit 6a5479e
Show file tree
Hide file tree
Showing 42 changed files with 1,279 additions and 66 deletions.
10 changes: 8 additions & 2 deletions ros2bag/ros2bag/verb/info.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,18 +12,24 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import os
import sys

from ros2bag.verb import VerbExtension

from rosbag2_transport import rosbag2_transport_py


class InfoVerb(VerbExtension):
"""ros2 bag info."""

def add_arguments(self, parser, cli_name): # noqa: D102
arg = parser.add_argument(
parser.add_argument(
'bag_file', help='bag file to introspect')

def main(self, *, args): # noqa: D102
bag_file = args.bag_file
print('calling ros2 bag info on', bag_file)
if not os.path.exists(bag_file):
return "Error: bag file '{}' does not exist!".format(bag_file)

rosbag2_transport_py.info(uri=bag_file)
10 changes: 10 additions & 0 deletions rosbag2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ find_package(rosbag2_storage REQUIRED)
find_package(rosidl_generator_cpp REQUIRED)

add_library(${PROJECT_NAME} SHARED
src/rosbag2/info.cpp
src/rosbag2/sequential_reader.cpp
src/rosbag2/typesupport_helpers.cpp
src/rosbag2/writer.cpp)
Expand Down Expand Up @@ -71,6 +72,15 @@ if(BUILD_TESTING)
if(TARGET rosbag2_typesupport_helpers_test)
target_link_libraries(rosbag2_typesupport_helpers_test rosbag2)
endif()

ament_add_gmock(test_info
test/rosbag2/test_info.cpp
test/rosbag2/mock_metadata_io.hpp
WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
if(TARGET test_info)
target_link_libraries(test_info rosbag2)
ament_target_dependencies(test_info rosbag2_test_common)
endif()
endif()

ament_package()
Original file line number Diff line number Diff line change
Expand Up @@ -12,23 +12,25 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef ROSBAG2_STORAGE__BAG_INFO_HPP_
#define ROSBAG2_STORAGE__BAG_INFO_HPP_
#ifndef ROSBAG2__INFO_HPP_
#define ROSBAG2__INFO_HPP_

#include <string>

namespace rosbag2_storage
#include "rosbag2/types.hpp"
#include "visibility_control.hpp"

namespace rosbag2
{

/**
* Struct to hold the storage information.
*/
struct BagInfo
class ROSBAG2_PUBLIC Info
{
std::string uri;
// TODO(greimela-si/botteroa-si): Add remaining info fields.
public:
virtual ~Info() = default;

virtual rosbag2::BagMetadata read_metadata(const std::string & uri);
};

} // namespace rosbag2_storage
} // namespace rosbag2

#endif // ROSBAG2_STORAGE__BAG_INFO_HPP_
#endif // ROSBAG2__INFO_HPP_
3 changes: 3 additions & 0 deletions rosbag2/include/rosbag2/types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,15 @@
#ifndef ROSBAG2__TYPES_HPP_
#define ROSBAG2__TYPES_HPP_

#include "rosbag2_storage/bag_metadata.hpp"
#include "rosbag2_storage/serialized_bag_message.hpp"
#include "rosbag2_storage/topic_with_type.hpp"

namespace rosbag2
{
using BagMetadata = rosbag2_storage::BagMetadata;
using SerializedBagMessage = rosbag2_storage::SerializedBagMessage;
using TopicMetadata = rosbag2_storage::TopicMetadata;
using TopicWithType = rosbag2_storage::TopicWithType;
} // namespace rosbag2

Expand Down
1 change: 1 addition & 0 deletions rosbag2/include/rosbag2/writer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ class ROSBAG2_PUBLIC Writer
virtual void write(std::shared_ptr<SerializedBagMessage> message);

private:
std::string uri_;
rosbag2_storage::StorageFactory factory_;
std::shared_ptr<rosbag2_storage::storage_interfaces::ReadWriteInterface> storage_;
};
Expand Down
1 change: 1 addition & 0 deletions rosbag2/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>test_msgs</test_depend>
<test_depend>rosbag2_test_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
30 changes: 30 additions & 0 deletions rosbag2/src/rosbag2/info.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
// Copyright 2018, Bosch Software Innovations GmbH.
//
// 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 "rosbag2/info.hpp"

#include <string>

#include "rosbag2_storage/metadata_io.hpp"

namespace rosbag2
{

rosbag2::BagMetadata Info::read_metadata(const std::string & uri)
{
rosbag2_storage::MetadataIo metadata_io;
return metadata_io.read_metadata(uri);
}

} // namespace rosbag2
9 changes: 9 additions & 0 deletions rosbag2/src/rosbag2/writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,14 +16,22 @@

#include <memory>
#include <string>
#include <utility>

#include "rosbag2_storage/metadata_io.hpp"
#include "rosbag2/info.hpp"
#include "rosbag2/storage_options.hpp"

namespace rosbag2
{

Writer::~Writer()
{
if (!uri_.empty()) {
rosbag2_storage::MetadataIo metadata_io;
metadata_io.write_metadata(uri_, storage_->get_metadata());
}

storage_.reset(); // Necessary to ensure that the writer is destroyed before the factory
}

Expand All @@ -33,6 +41,7 @@ void Writer::open(const StorageOptions & options)
if (!storage_) {
throw std::runtime_error("No storage could be initialized. Abort");
}
uri_ = options.uri;
}

void Writer::create_topic(const TopicWithType & topic_with_type)
Expand Down
34 changes: 34 additions & 0 deletions rosbag2/test/rosbag2/mock_metadata_io.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
// Copyright 2018, Bosch Software Innovations GmbH.
//
// 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__MOCK_METADATA_IO_HPP_
#define ROSBAG2__MOCK_METADATA_IO_HPP_

#include <gmock/gmock.h>

#include <memory>
#include <string>
#include <vector>

#include "rosbag2_storage/bag_metadata.hpp"
#include "rosbag2_storage/metadata_io.hpp"

class MockMetadataIo : public rosbag2_storage::MetadataIo
{
public:
MOCK_METHOD2(write_metadata, void(const std::string &, rosbag2_storage::BagMetadata));
MOCK_METHOD1(read_metadata, rosbag2_storage::BagMetadata(const std::string &));
};

#endif // ROSBAG2__MOCK_METADATA_IO_HPP_
63 changes: 63 additions & 0 deletions rosbag2/test/rosbag2/mock_storage.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
// Copyright 2018, Bosch Software Innovations GmbH.
//
// 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__MOCK_STORAGE_HPP_
#define ROSBAG2__MOCK_STORAGE_HPP_

#include <memory>
#include <string>
#include <vector>

#include "rosbag2_storage/bag_metadata.hpp"
#include "rosbag2_storage/serialized_bag_message.hpp"
#include "rosbag2_storage/topic_with_type.hpp"
#include "rosbag2_storage/storage_interfaces/read_write_interface.hpp"

class MockStorage : public rosbag2_storage::storage_interfaces::ReadWriteInterface
{
public:
~MockStorage() override = default;

void open(const std::string & uri, rosbag2_storage::storage_interfaces::IOFlag flag) override
{
(void) uri;
(void) flag;
}

void create_topic(const rosbag2_storage::TopicWithType & topic) override
{
(void) topic;
}

bool has_next() override {return true;}

std::shared_ptr<rosbag2_storage::SerializedBagMessage> read_next() override {return nullptr;}

void write(std::shared_ptr<const rosbag2_storage::SerializedBagMessage> msg) override
{
(void) msg;
}

std::vector<rosbag2_storage::TopicWithType> get_all_topics_and_types() override
{
return std::vector<rosbag2_storage::TopicWithType>();
}

rosbag2_storage::BagMetadata get_metadata() override
{
return rosbag2_storage::BagMetadata();
}
};

#endif // ROSBAG2__MOCK_STORAGE_HPP_
91 changes: 91 additions & 0 deletions rosbag2/test/rosbag2/test_info.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,91 @@
// Copyright 2018, Bosch Software Innovations GmbH.
//
// 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 <gmock/gmock.h>

#include <fstream>
#include <memory>
#include <string>
#include <vector>

#include "mock_metadata_io.hpp"
#include "rosbag2/info.hpp"
#include "rosbag2_storage/bag_metadata.hpp"
#include "rosbag2_storage/filesystem_helper.hpp"
#include "rosbag2_test_common/temporary_directory_fixture.hpp"

using namespace ::testing; // NOLINT
using namespace rosbag2_test_common; // NOLINT

TEST_F(TemporaryDirectoryFixture, read_metadata_makes_appropriate_call_to_metadata_io_method) {
std::string bagfile(
"rosbag2_bagfile_information:\n"
" version: 1\n"
" storage_identifier: sqlite3\n"
" storage_format: cdr\n"
" relative_file_paths:\n"
" - some_relative_path\n"
" - some_other_relative_path\n"
" combined_bag_size: 10\n"
" duration:\n"
" nanoseconds: 100\n"
" starting_time:\n"
" nanoseconds_since_epoch: 1000000\n"
" message_count: 50\n"
" topics_with_message_count:\n"
" - topic_and_type:\n"
" name: topic1\n"
" type: type1\n"
" message_count: 100\n"
" - topic_and_type:\n"
" name: topic2\n"
" type: type2\n"
" message_count: 200");

std::ofstream fout(
rosbag2_storage::FilesystemHelper::concat({
temporary_dir_path_, rosbag2_storage::MetadataIo::metadata_filename
}));
fout << bagfile;
fout.close();

rosbag2::Info info;
auto read_metadata = info.read_metadata(temporary_dir_path_);

EXPECT_THAT(read_metadata.storage_identifier, Eq("sqlite3"));
EXPECT_THAT(read_metadata.storage_format, Eq("cdr"));
EXPECT_THAT(read_metadata.relative_file_paths,
Eq(std::vector<std::string>({"some_relative_path", "some_other_relative_path"})));
EXPECT_THAT(read_metadata.duration, Eq(std::chrono::nanoseconds(100)));
EXPECT_THAT(read_metadata.starting_time,
Eq(std::chrono::time_point<std::chrono::high_resolution_clock>(
std::chrono::nanoseconds(1000000))));
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::TopicMetadata expected_first_topic = {{"topic1", "type1"}, 100};
EXPECT_THAT(actual_first_topic.topic_with_type.name,
Eq(expected_first_topic.topic_with_type.name));
EXPECT_THAT(actual_first_topic.topic_with_type.type,
Eq(expected_first_topic.topic_with_type.type));
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::TopicMetadata expected_second_topic = {{"topic2", "type2"}, 200};
EXPECT_THAT(actual_second_topic.topic_with_type.name,
Eq(expected_second_topic.topic_with_type.name));
EXPECT_THAT(actual_second_topic.topic_with_type.type,
Eq(expected_second_topic.topic_with_type.type));
EXPECT_THAT(actual_second_topic.message_count, Eq(expected_second_topic.message_count));
}
Loading

0 comments on commit 6a5479e

Please sign in to comment.