From 5e6c4910d25ef2ac252143067b2772cbb924a69c Mon Sep 17 00:00:00 2001 From: Martin Idel Date: Sat, 15 Dec 2018 03:09:19 +0100 Subject: [PATCH] Play old bagfiles (#69) * GH-138 Move calculation of bag size - previously in rosbag2::Info - now in storage plugin * GH-130 Add rosbag2_bag_v2_plugins package -This package will contain storage and converter plugins * GH-131 don't build plugins on Windows * GH-129 Add function to be generated - massive if/else between all message types - will be generated similar to ros1_bridge plugin * GH-138 Write storage plugin for rosbag v2 bags * GH-138 Make sure that no attempt to create a converter is made when trying to read a rsbag v2 bag file * GH-138 Add play end-to-end test for rosbag v2 plugin * GH-138 Use cmake files to find ros1 packages - Use files from ros1_bridge via PkgConfig * GH-138 Add generator code * GH-141 Add initial version of vendor package * GH-141 Improve vendor package to build on Mac * GH-138 Cleanup CMakeLists * GH-141 Use unmanaged Instance of class-loader - managed instance somehow isn't available for gcc 6.3 * GH-141 Reduce patch and copy new toplevle CMakeLists by hand * GH-141 Fix Shared Instance usage * GH-141 Improve maintainability of vendor package - Document what patches do and why changes are necessary - Load ros1 packages through cmake macro - Do not export ros1 packages via ament - use commit hash of current master which is more stable than using melodic-devel * GH-138 Link against rclcpp - necessary for ros1_bridge * GH-138 Avoid crash when trying to play v2 bags which contain unknown message types * GH-138 Add CLI -s option to ros2 bag info and use it in rosbag2::info - this allows ros2 bag info to work also when the yaml metadata file does not exsist - this is always the case for rosbag1 bagfiles - it could also happen for sqlite or other storage based bagfiles * GH-138 Add end-to-end info test for rosbag v2 files * GH-138 Add unit tests to rosbag_storage * GH-138 Add method to extract filename from path to FilesystemHelpers * GH-138 Add proper logging for topics which cannot be converted * GH-138 Improve finding dependencies of ros1 * GH-141 Explicitly import transitive dependencies of vendor package * GH-138 Skip tests via ament if ros1 is not available * GH-133 First split of plugins * GH-133 Write serialized rosbag message * GH-133 Improve converter plugin - move generation templates outside of plugin folders as both plugins need it - use ros::serialization routines to deserialize the ros message * GH-133 Add plugin to be found by pluginlib * GH-133 Remove empty check in converter - With the rosbag_v2_converter_plugin, we don't need to treat rosbag_v2 storage any different * GH-133 Assert serialization format in unit tests for storage * GH-133 Delete superfluous include folder - Only needed if we want to link against the library * GH-133 get_all_topics_and_types returns only valid ros2 types - This is necessary as the information is used by rosbag2_transport - ros2 bag info still shows all topics and types - rosbag::View::getConnections() can return multiple connections corresponding to the same topic * GH-133 Improve end to end test - use a bagfile with messages not known to ros2 * GH-133 Reformulate info message in case of missing ros1-ros2 mapping for a topic * GH-14 Find messages first * Explicitly print message when on Windows Co-Authored-By: Martin-Idel-SI * GH-14 Refactor rosbag_storage vendor package - Improve toplevel CMakeLists - Put all patches into a resource subfolder * GH-14 Reflect renames of converter interfaces * GH-156 Workaround for path problems * GH-156 Add documentation for plugin * GH-156 Fix the pluginlib version to greater 2 * GH-156 Prohibit CMake from declaring paths as system paths This switches the order of ros2 and ros1 directories resulting in build failures * GH-156 Prohibit system include paths for rosbag plugins This can lead to switching ros1 and ros2 include paths resulting in missing symbols as the wrong pluginlib gets included * GH-14 Split patches * make README more verbose * add plugin specific readme * more readme for bag_v2 plugin --- README.md | 125 +++- ros1_rosbag_storage_vendor/CMakeLists.txt | 69 +++ .../cmake/CMakeLists.txt.in | 5 + ros1_rosbag_storage_vendor/package.xml | 18 + .../resources/bagcpp.diff | 22 + .../resources/bagcpp_name.diff | 29 + .../resources/bagh.diff | 22 + .../resources/cmakeliststxt.diff | 201 ++++++ .../resources/packagexml.diff | 58 ++ .../resources/plugin_descriptionxml.diff | 10 + .../resources/rosbag1_encryption_patch.diff | 573 ++++++++++++++++++ ros2bag/ros2bag/verb/info.py | 6 +- rosbag2/include/rosbag2/info.hpp | 2 +- rosbag2/src/rosbag2/info.cpp | 1 - rosbag2/src/rosbag2/typesupport_helpers.cpp | 8 +- rosbag2/test/rosbag2/test_info.cpp | 2 +- .../test/rosbag2/test_typesupport_helpers.cpp | 4 +- rosbag2_bag_v2_plugins/CMakeLists.txt | 169 ++++++ rosbag2_bag_v2_plugins/README.md | 70 +++ .../converter_plugin_description.xml | 13 + rosbag2_bag_v2_plugins/package.xml | 27 + rosbag2_bag_v2_plugins/resources/test_bag.bag | Bin 0 -> 9023 bytes .../test_bag_multiple_connections.bag | Bin 0 -> 9940 bytes .../src/generate_coverter_cpp.py | 54 ++ .../convert_rosbag_message.cpp.em | 78 +++ .../convert_rosbag_message.hpp | 36 ++ .../converter/rosbag_v2_deserializer.cpp | 56 ++ .../converter/rosbag_v2_deserializer.hpp | 40 ++ .../src/rosbag2_bag_v2_plugins/logging.hpp | 61 ++ .../storage/rosbag_output_stream.cpp | 47 ++ .../storage/rosbag_output_stream.hpp | 42 ++ .../storage/rosbag_v2_storage.cpp | 169 ++++++ .../storage/rosbag_v2_storage.hpp | 62 ++ .../storage_plugin_description.xml | 13 + .../rosbag_v2_storage_test_fixture.hpp | 46 ++ .../test_rosbag_output_stream.cpp | 70 +++ .../test_rosbag_v2_storage.cpp | 144 +++++ .../rosbag2_storage/filesystem_helper.hpp | 17 + .../rosbag2_storage/topic_metadata.hpp | 5 + .../test_filesystem_helper.cpp | 19 + .../sqlite/sqlite_storage.cpp | 1 + .../sqlite/test_sqlite_storage.cpp | 5 - rosbag2_tests/CMakeLists.txt | 44 ++ .../cmake/skip_ros1_tests_if_necessary.cmake | 37 ++ rosbag2_tests/package.xml | 2 + rosbag2_tests/resources/test_bag.bag | Bin 0 -> 8522 bytes ...test_rosbag2_info_rosbag_v2_end_to_end.cpp | 72 +++ ...test_rosbag2_play_rosbag_v2_end_to_end.cpp | 92 +++ .../rosbag2_transport/rosbag2_transport.hpp | 2 +- .../rosbag2_transport/rosbag2_transport.cpp | 8 +- .../rosbag2_transport_python.cpp | 10 +- .../test/rosbag2_transport/test_info.cpp | 2 +- 52 files changed, 2640 insertions(+), 28 deletions(-) create mode 100644 ros1_rosbag_storage_vendor/CMakeLists.txt create mode 100644 ros1_rosbag_storage_vendor/cmake/CMakeLists.txt.in create mode 100644 ros1_rosbag_storage_vendor/package.xml create mode 100644 ros1_rosbag_storage_vendor/resources/bagcpp.diff create mode 100644 ros1_rosbag_storage_vendor/resources/bagcpp_name.diff create mode 100644 ros1_rosbag_storage_vendor/resources/bagh.diff create mode 100644 ros1_rosbag_storage_vendor/resources/cmakeliststxt.diff create mode 100644 ros1_rosbag_storage_vendor/resources/packagexml.diff create mode 100644 ros1_rosbag_storage_vendor/resources/plugin_descriptionxml.diff create mode 100644 ros1_rosbag_storage_vendor/resources/rosbag1_encryption_patch.diff create mode 100644 rosbag2_bag_v2_plugins/CMakeLists.txt create mode 100644 rosbag2_bag_v2_plugins/README.md create mode 100644 rosbag2_bag_v2_plugins/converter_plugin_description.xml create mode 100644 rosbag2_bag_v2_plugins/package.xml create mode 100644 rosbag2_bag_v2_plugins/resources/test_bag.bag create mode 100644 rosbag2_bag_v2_plugins/resources/test_bag_multiple_connections.bag create mode 100644 rosbag2_bag_v2_plugins/src/generate_coverter_cpp.py create mode 100644 rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/convert_rosbag_message.cpp.em create mode 100644 rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/convert_rosbag_message.hpp create mode 100644 rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/converter/rosbag_v2_deserializer.cpp create mode 100644 rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/converter/rosbag_v2_deserializer.hpp create mode 100644 rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/logging.hpp create mode 100644 rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_output_stream.cpp create mode 100644 rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_output_stream.hpp create mode 100644 rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_v2_storage.cpp create mode 100644 rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_v2_storage.hpp create mode 100644 rosbag2_bag_v2_plugins/storage_plugin_description.xml create mode 100644 rosbag2_bag_v2_plugins/test/rosbag2_bag_v2_plugins/rosbag_v2_storage_test_fixture.hpp create mode 100644 rosbag2_bag_v2_plugins/test/rosbag2_bag_v2_plugins/test_rosbag_output_stream.cpp create mode 100644 rosbag2_bag_v2_plugins/test/rosbag2_bag_v2_plugins/test_rosbag_v2_storage.cpp create mode 100644 rosbag2_tests/cmake/skip_ros1_tests_if_necessary.cmake create mode 100644 rosbag2_tests/resources/test_bag.bag create mode 100644 rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_rosbag_v2_end_to_end.cpp create mode 100644 rosbag2_tests/test/rosbag2_tests/test_rosbag2_play_rosbag_v2_end_to_end.cpp diff --git a/README.md b/README.md index 30a47611e1..6505ccea7a 100644 --- a/README.md +++ b/README.md @@ -1,12 +1,24 @@ # rosbag2 -THIS IS WORK IN PROGRESS AND NOT READY TO BE USED YET +THIS IS WORK IN PROGRESS AND SHOULD BE USED WITH CARE -Repository for implementing ROSBag2 as described in its corresponding [design article](https://github.com/ros2/design/blob/f69fbbd11848e3dd6866b71a158a1902e31e92f1/articles/rosbags.md) +Repository for implementing rosbag2 as described in its corresponding [design article](https://github.com/ros2/design/blob/f69fbbd11848e3dd6866b71a158a1902e31e92f1/articles/rosbags.md) -## Build instructions +## Installation instructions -Create a new workspace: +## Debian packages + +rosbag2 packages are available via debian packages and thus can be installed via + +``` +$ sudo apt-get install ros2bag rosbag2* +``` + +For other platforms than Linux, rosbag2 has to be built from source as it's currently not part of the latest (ros2.repos file)[https://github.com/ros2/ros2/blob/master/ros2.repos]. + +## Build from source + +It is recommended to create a new overlay workspace on top of your current ROS 2 installation. ``` $ mkdir -p ~/rosbag_ws/src @@ -22,18 +34,117 @@ $ git clone https://github.com/ros2/rosbag2.git Then build all the packages with this command: ``` -$ colcon build --merge-install +$ colcon build [--merge-install] ``` -The `--merge-install` flag is optional but ensures a cleaner environment which is helpful for development. +The `--merge-install` flag is optional and installs all packages into one folder rather than isolated folders for each package. #### Executing tests The tests can be run using the following commands: ``` -$ colcon test --merge-install +$ colcon test [--merge-install] $ colcon test-result --verbose ``` The first command executes the test and the second command displays the errors (if any). + +## Using rosbag2 + +rosbag2 is part of the ROS 2 command line interfaces. +This repo introduces a new verb called `bag` and thus serves as the entry point of using rosbag2. +As of the time of writing, there are three commands available for `ros2 bag`: + +* record +* play +* info + +### Recording data + +In order to record all topics currently available in the system: + +``` +$ ros2 bag record -a +``` + +The command above will record all available topics and discovers new topics as they appear while recording. +This auto-discovery of new topics can be disabled by given the command line argument `--no-discovery`. + +To record a set of predefined topics, one can specify them on the command line explicitly. + +``` +$ ros2 bag record +``` + +The specified topics don't necessarily have to be present at start time. +The discovery function will automatically recognize if one of the specified topics appeared. +In the same fashion, this auto discovery can be disabled with `--no-discovery`. + +If not further specified, `ros2 bag record` will create a new folder named to the current time stamp and stores all data within this folder. +A user defined name can be given with `-o, --output`. + +### Replaying data + +After recording data, the next logical step is to replay this data: + +``` +$ ros2 bag play +``` + +The bag file is by default set to the folder name where the data was previously recorded in. + +### Analyzing data + +The recorded data can be analyzed by displaying some meta information about it: + +``` +$ ros2 bag info +``` + +You should see something along these lines: + +``` +Files: demo_strings.db3 +Bag size: 44.5 KiB +Storage id: sqlite3 +Duration: 8.501s +Start: Nov 28 2018 18:02:18.600 (1543456938.600) +End Nov 28 2018 18:02:27.102 (1543456947.102) +Messages: 27 +Topic information: Topic: /chatter | Type: std_msgs/String | Count: 9 | Serialization Format: cdr + Topic: /my_chatter | Type: std_msgs/String | Count: 18 | Serialization Format: cdr +``` + +## Storage format plugin architecture + +Looking at the output of the `ros2 bag info` command, we can see a field called `storage id:`. +rosbag2 specifically was designed to support multiple storage formats. +This allows a flexible adaptation of various storage formats depending on individual use cases. +As of now, this repository comes with two storage plugins. +The first plugin, sqlite3 is chosen by default. +If not specified otherwise, rosbag2 will store and replay all recorded data in an SQLite3 database. +Secondly, rosbag2 provides support for legacy ROS 1 bag data. __TODO(karsten1987) Add link when rosindex ran__. + +In order to use a specified (non-default) storage format plugin, rosbag2 has a command line argument for it: + +``` +$ ros2 bag | | -s | | +``` + +Have a look at each of the individual plugins for further information. + +## Serialization format plugin architecture + +Looking further at the output of `ros2 bag info`, we can see another field attached to each topic called `Serialization Format`. +By design, ROS 2 is middleware agnostic and thus can leverage multiple communication frameworks. +The default middleware for ROS 2 is DDS which has `cdr` as its default binary serialization format. +However, other middleware implementation might have different formats. +If not specified, `ros2 bag record -a` will record all data in the middleware specific format. +This however also means that such a bag file can't easily be replayed with another middleware format. + +rosbag2 implements a serialization format plugin architecture which allows the user the specify a certain serialization format. +When specified, rosbag2 looks for a suitable converter to transform the native middleware protocol to the target format. +This also allows to record data in a native format to optimize for speed, but to convert or transform the recorded data into a middleware agnostic serialization format. + +By default, rosbag2 can convert from and to CDR as it's the default serialization format for ROS 2. diff --git a/ros1_rosbag_storage_vendor/CMakeLists.txt b/ros1_rosbag_storage_vendor/CMakeLists.txt new file mode 100644 index 0000000000..9978060592 --- /dev/null +++ b/ros1_rosbag_storage_vendor/CMakeLists.txt @@ -0,0 +1,69 @@ +cmake_minimum_required(VERSION 3.5) +project(ros1_rosbag_storage_vendor) + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) + +# We don't need to build on Windows for now +if(WIN32) + message("Replay ROS1 rosbags is currently not supported on Windows systems") + return() +endif() + +set(git_apply git apply) + +include(ExternalProject) +# We have to include a number of patches to the rosbag +# 1. rosbag1_encryption_patch includes https://github.com/ros/ros_comm/pull/1499, without it, pluginlib won't link +# 2. The next two patches patch the pluginlib usage: +# Missing boost/bind include +# Using pluginlib with boost results in compile errors on some systems, so we need to switch to pluginlib without boost +# 3. The next patches patch the catkin package to ament and renames it +# Patching to ament is necessary as otherwise colcon needs to build a catkin package together with an ament package, which is impossible +# Renaming the package is necessary on some systems to not confuse the linker +# +# Note that we need to build with CMAKE_NO_SYSTEM_FROM_IMPORTED. This prohibits cmake from +# declaring any paths as "internal" (flagged with -isystem instead of -I) which can result in this +# vendor package building against the wrong pluginlib, because the paths get switched. +# Symptoms of wrong paths: The build of the rosbag for ROS 1 plugins fails with missing symbols +# like ros::package::getPlugins(...) when linking the vendor package +ExternalProject_Add(ros1_rosbag_storage + DOWNLOAD_DIR ${CMAKE_CURRENT_BINARY_DIR}/download + URL https://github.com/ros/ros_comm/archive/669fbd32d2f92cc295f4b024fcb2f982fddec0f0.zip + URL_MD5 4c8b4c33165b223870f5d77bb697bef6 + TIMEOUT 60 + SOURCE_DIR ${CMAKE_CURRENT_BINARY_DIR}/sources + CMAKE_ARGS -DCMAKE_INSTALL_PREFIX=${CMAKE_CURRENT_BINARY_DIR}/rosbag_install -DCMAKE_NO_SYSTEM_FROM_IMPORTED=1 + PATCH_COMMAND + ${git_apply} ${CMAKE_CURRENT_SOURCE_DIR}/resources/rosbag1_encryption_patch.diff && + ${git_apply} ${CMAKE_CURRENT_SOURCE_DIR}/resources/bagh.diff && + ${git_apply} ${CMAKE_CURRENT_SOURCE_DIR}/resources/bagcpp.diff && + ${git_apply} ${CMAKE_CURRENT_SOURCE_DIR}/resources/bagcpp_name.diff && + ${git_apply} ${CMAKE_CURRENT_SOURCE_DIR}/resources/plugin_descriptionxml.diff && + ${git_apply} ${CMAKE_CURRENT_SOURCE_DIR}/resources/packagexml.diff && + ${git_apply} ${CMAKE_CURRENT_SOURCE_DIR}/resources/cmakeliststxt.diff && + ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/cmake/CMakeLists.txt.in ${CMAKE_CURRENT_BINARY_DIR}/sources/CMakeLists.txt +) + +install( + DIRECTORY + ${CMAKE_CURRENT_BINARY_DIR}/rosbag_install/ + DESTINATION + ${CMAKE_INSTALL_PREFIX}/ +) + +ament_package() diff --git a/ros1_rosbag_storage_vendor/cmake/CMakeLists.txt.in b/ros1_rosbag_storage_vendor/cmake/CMakeLists.txt.in new file mode 100644 index 0000000000..9b124b9fad --- /dev/null +++ b/ros1_rosbag_storage_vendor/cmake/CMakeLists.txt.in @@ -0,0 +1,5 @@ +# We download ros_comm, which does not contain a toplevel CMakeLists so colcon can't find the entry +# point and claims there is nothing to build. +# This is also an opportunity, because we want to only build rosbag_storage anyways +cmake_minimum_required(VERSION 3.5) +add_subdirectory(tools/rosbag_storage) diff --git a/ros1_rosbag_storage_vendor/package.xml b/ros1_rosbag_storage_vendor/package.xml new file mode 100644 index 0000000000..fc76b2072f --- /dev/null +++ b/ros1_rosbag_storage_vendor/package.xml @@ -0,0 +1,18 @@ + + + + ros1_rosbag_storage_vendor + 0.0.0 + Vendor package for rosbag_storage of ROS1 + Karsten Knese + Apache License 2.0 + + ament_cmake + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/ros1_rosbag_storage_vendor/resources/bagcpp.diff b/ros1_rosbag_storage_vendor/resources/bagcpp.diff new file mode 100644 index 0000000000..8037213912 --- /dev/null +++ b/ros1_rosbag_storage_vendor/resources/bagcpp.diff @@ -0,0 +1,22 @@ +diff --git a/tools/rosbag_storage/src/bag.cpp b/tools/rosbag_storage/src/bag.cpp +index 7e2e67171..073072934 100644 +--- a/tools/rosbag_storage/src/bag.cpp ++++ b/tools/rosbag_storage/src/bag.cpp +@@ -40,6 +40,7 @@ + #include + + #include ++#include + + #include "console_bridge/console.h" + +@@ -222,7 +223,8 @@ void Bag::setEncryptorPlugin(std::string const& plugin_name, std::string const& + if (!chunks_.empty()) { + throw BagException("Cannot set encryption plugin after chunks are written"); + } +- encryptor_ = encryptor_loader_.createInstance(plugin_name); ++ auto unmanaged_instance = encryptor_loader_.createUnmanagedInstance(plugin_name); ++ encryptor_ = std::shared_ptr(unmanaged_instance); + encryptor_->initialize(*this, plugin_param); + } + diff --git a/ros1_rosbag_storage_vendor/resources/bagcpp_name.diff b/ros1_rosbag_storage_vendor/resources/bagcpp_name.diff new file mode 100644 index 0000000000..f592ff25ab --- /dev/null +++ b/ros1_rosbag_storage_vendor/resources/bagcpp_name.diff @@ -0,0 +1,29 @@ +diff --git a/tools/rosbag_storage/src/bag.cpp b/tools/rosbag_storage/src/bag.cpp +index 073072934..13a7fc8fc 100644 +--- a/tools/rosbag_storage/src/bag.cpp ++++ b/tools/rosbag_storage/src/bag.cpp +@@ -58,12 +58,13 @@ using ros::Time; + + namespace rosbag { + +-Bag::Bag() : encryptor_loader_("rosbag_storage", "rosbag::EncryptorBase") ++Bag::Bag() : encryptor_loader_("ros1_rosbag_storage", "rosbag::EncryptorBase") + { + init(); + } + +-Bag::Bag(string const& filename, uint32_t mode) : encryptor_loader_("rosbag_storage", "rosbag::EncryptorBase") ++Bag::Bag(string const& filename, uint32_t mode) ++: encryptor_loader_("ros1_rosbag_storage", "rosbag::EncryptorBase") + { + init(); + open(filename, mode); +@@ -71,7 +72,7 @@ Bag::Bag(string const& filename, uint32_t mode) : encryptor_loader_("rosbag_stor + + #ifndef BOOST_NO_CXX11_RVALUE_REFERENCES + +-Bag::Bag(Bag&& other) : encryptor_loader_("rosbag_storage", "rosbag::EncryptorBase") { ++Bag::Bag(Bag&& other) : encryptor_loader_("ros1_rosbag_storage", "rosbag::EncryptorBase") { + init(); + swap(other); + } diff --git a/ros1_rosbag_storage_vendor/resources/bagh.diff b/ros1_rosbag_storage_vendor/resources/bagh.diff new file mode 100644 index 0000000000..0eee68ca4b --- /dev/null +++ b/ros1_rosbag_storage_vendor/resources/bagh.diff @@ -0,0 +1,22 @@ +diff --git a/tools/rosbag_storage/include/rosbag/bag.h b/tools/rosbag_storage/include/rosbag/bag.h +index c65533011..e75ef9c78 100644 +--- a/tools/rosbag_storage/include/rosbag/bag.h ++++ b/tools/rosbag_storage/include/rosbag/bag.h +@@ -35,6 +35,8 @@ + #ifndef ROSBAG_BAG_H + #define ROSBAG_BAG_H + ++#include ++ + #include "rosbag/macros.h" + + #include "rosbag/buffer.h" +@@ -354,7 +356,7 @@ private: + // Encryptor plugin loader + pluginlib::ClassLoader encryptor_loader_; + // Active encryptor +- boost::shared_ptr encryptor_; ++ std::shared_ptr encryptor_; + }; + + } // namespace rosbag diff --git a/ros1_rosbag_storage_vendor/resources/cmakeliststxt.diff b/ros1_rosbag_storage_vendor/resources/cmakeliststxt.diff new file mode 100644 index 0000000000..0039c9a362 --- /dev/null +++ b/ros1_rosbag_storage_vendor/resources/cmakeliststxt.diff @@ -0,0 +1,201 @@ +diff --git a/tools/rosbag_storage/CMakeLists.txt b/tools/rosbag_storage/CMakeLists.txt +index dc49e2250..a440b7eda 100644 +--- a/tools/rosbag_storage/CMakeLists.txt ++++ b/tools/rosbag_storage/CMakeLists.txt +@@ -1,28 +1,55 @@ +-cmake_minimum_required(VERSION 2.8.3) ++cmake_minimum_required(VERSION 3.5) + +-project(rosbag_storage) ++project(ros1_rosbag_storage) ++ ++# Default to C99 ++if(NOT CMAKE_C_STANDARD) ++ set(CMAKE_C_STANDARD 99) ++endif() ++ ++# Default to C++14 ++if(NOT CMAKE_CXX_STANDARD) ++ set(CMAKE_CXX_STANDARD 14) ++endif() + + if(NOT WIN32) +- set_directory_properties(PROPERTIES COMPILE_OPTIONS "-Wall;-Wextra") ++ add_compile_options(-Wall -Wextra) + endif() + ++find_package(ament_cmake REQUIRED) ++find_package(pluginlib 2.0 REQUIRED) + find_package(console_bridge REQUIRED) +-find_package(catkin REQUIRED COMPONENTS cpp_common pluginlib roscpp_serialization roscpp_traits rostime roslz4) + find_package(Boost REQUIRED COMPONENTS date_time filesystem program_options regex) + find_package(BZip2 REQUIRED) + +-catkin_package( +- CFG_EXTRAS rosbag_storage-extras.cmake +- INCLUDE_DIRS include +- LIBRARIES rosbag_storage +- CATKIN_DEPENDS pluginlib roslz4 +- DEPENDS console_bridge Boost +-) ++find_package(ros1_bridge REQUIRED) ++include(${ros1_bridge_DIR}/find_ros1_interface_packages.cmake) ++include(${ros1_bridge_DIR}/find_ros1_package.cmake) ++ ++find_package(PkgConfig) ++if(NOT PKG_CONFIG_FOUND) ++ message(WARNING "Failed to find PkgConfig, skipping...") ++ # call ament_package() to avoid ament_tools treating this as a plain CMake pkg ++ ament_package() ++ return() ++endif() ++ ++find_ros1_package(cpp_common) ++if(NOT ros1_cpp_common_FOUND) ++ message(WARNING "Failed to find ROS 1 roscpp, skipping...") ++ # call ament_package() to avoid ament_tools treating this as a plain CMake pkg ++ ament_package() ++ return() ++endif() ++ ++find_ros1_package(roscpp_serialization) ++find_ros1_package(roscpp_traits) ++find_ros1_package(rostime) ++find_ros1_package(roslz4) + + # Support large bags (>2GB) on 32-bit systems + add_definitions(-D_FILE_OFFSET_BITS=64) + +-include_directories(include ${catkin_INCLUDE_DIRS} ${console_bridge_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} ${BZIP2_INCLUDE_DIR}) + add_definitions(${BZIP2_DEFINITIONS}) + + set(AES_ENCRYPT_SOURCE "") +@@ -32,7 +59,7 @@ if(NOT WIN32) + set(AES_ENCRYPT_LIBRARIES "crypto" "gpgme") + endif() + +-add_library(rosbag_storage ++add_library(ros1_rosbag_storage SHARED + src/bag.cpp + src/bag_player.cpp + src/buffer.cpp +@@ -45,44 +72,97 @@ add_library(rosbag_storage + src/view.cpp + src/uncompressed_stream.cpp + ) +-target_link_libraries(rosbag_storage ${catkin_LIBRARIES} ${Boost_LIBRARIES} ${BZIP2_LIBRARIES} ${console_bridge_LIBRARIES} ${AES_ENCRYPT_LIBRARIES}) + +-install(TARGETS rosbag_storage +- ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +- LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +- RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ++target_include_directories(ros1_rosbag_storage PUBLIC ++ $ ++ $ ++ ${console_bridge_INCLUDE_DIRS} ++ ${Boost_INCLUDE_DIRS} ++ ${BZIP2_INCLUDE_DIR}) ++ ++# prevent pluginlib from using boost because using boost seems to not work correctly ++target_compile_definitions(ros1_rosbag_storage PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS") ++ ++target_link_libraries(ros1_rosbag_storage ++ ${Boost_LIBRARIES} ${BZIP2_LIBRARIES} ${console_bridge_LIBRARIES} ${AES_ENCRYPT_LIBRARIES}) ++ ++pluginlib_export_plugin_description_file(ros1_rosbag_storage encryptor_plugins.xml) ++ ++ament_target_dependencies(ros1_rosbag_storage ++ pluginlib ++ ros1_cpp_common ++ ros1_roslz4 ++ ros1_roscpp_traits ++ ros1_roscpp_serialization ++ ros1_rostime ++) ++ ++install(TARGETS ros1_rosbag_storage ++ ARCHIVE DESTINATION lib ++ LIBRARY DESTINATION lib ++ RUNTIME DESTINATION bin + ) + +-add_library(rosbag_default_encryption_plugins ++add_library(rosbag_default_encryption_plugins SHARED + ${AES_ENCRYPT_SOURCE} + src/no_encryptor.cpp + ) + +-target_link_libraries(rosbag_default_encryption_plugins ${catkin_LIBRARIES} ${Boost_LIBRARIES} ${AES_ENCRYPT_LIBRARIES}) ++target_include_directories(rosbag_default_encryption_plugins PUBLIC ++ $ ++ $ ++ ${console_bridge_INCLUDE_DIRS} ++ ${Boost_INCLUDE_DIRS} ++ ${BZIP2_INCLUDE_DIR}) ++ ++target_link_libraries(rosbag_default_encryption_plugins ++ ros1_rosbag_storage ++ ${Boost_LIBRARIES} ++ ${BZIP2_LIBRARIES} ++ ${console_bridge_LIBRARIES} ++ ${AES_ENCRYPT_LIBRARIES}) ++ ++ament_target_dependencies(rosbag_default_encryption_plugins ++ pluginlib ++ ros1_cpp_common ++ ros1_roslz4 ++ ros1_roscpp_traits ++ ros1_roscpp_serialization ++ ros1_rostime ++) + + install(TARGETS rosbag_default_encryption_plugins +- ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +- LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +- RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ++ ARCHIVE DESTINATION lib ++ LIBRARY DESTINATION lib ++ RUNTIME DESTINATION bin + ) + + install(DIRECTORY include/ +- DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION} +- FILES_MATCHING PATTERN "*.h" ++ DESTINATION include + ) + + if(NOT WIN32) + install(FILES encryptor_plugins.xml +- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ++ DESTINATION share/ + ) + +- if(CATKIN_ENABLE_TESTING) +- find_package(rostest) +- +- catkin_add_gtest(test_aes_encryptor test/test_aes_encryptor.cpp src/gpgme_utils.cpp +- WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/test) +- if(TARGET test_aes_encryptor) +- target_link_libraries(test_aes_encryptor rosbag_storage ${BZIP2_LIBRARIES} ${AES_ENCRYPT_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +- endif() +- endif() ++# if(BUILD_TESTING) ++# find_package(ament_cmake_gmock) ++# ++# catkin_add_gtest(test_aes_encryptor test/test_aes_encryptor.cpp ++# WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/test) ++# if(TARGET test_aes_encryptor) ++# target_link_libraries(test_aes_encryptor rosbag_storage ${catkin_LIBRARIES} ${Boost_LIBRARIES}) ++# endif() ++# endif() + endif() ++ ++ament_export_include_directories(include) ++ament_export_libraries(ros1_rosbag_storage) ++ament_export_dependencies( ++ console_bridge ++ pluginlib ++ BZip2 ++) ++ ++ament_package() diff --git a/ros1_rosbag_storage_vendor/resources/packagexml.diff b/ros1_rosbag_storage_vendor/resources/packagexml.diff new file mode 100644 index 0000000000..78b5708f03 --- /dev/null +++ b/ros1_rosbag_storage_vendor/resources/packagexml.diff @@ -0,0 +1,58 @@ +diff --git a/tools/rosbag_storage/package.xml b/tools/rosbag_storage/package.xml +index 502f5308b..3f28d00f1 100644 +--- a/tools/rosbag_storage/package.xml ++++ b/tools/rosbag_storage/package.xml +@@ -1,5 +1,5 @@ +- +- rosbag_storage ++ ++ ros1_rosbag_storage + 1.14.3 + + This is a set of tools for recording from and playing back ROS +@@ -8,35 +8,25 @@ + Dirk Thomas + BSD + +- catkin ++ ament_cmake + ++ ros1_bridge + boost + bzip2 +- cpp_common ++ cpp_common + libconsole-bridge-dev + libgpgme-dev + libssl-dev + pluginlib +- roscpp_serialization +- roscpp_traits +- rostest +- rostime +- roslz4 + +- boost +- bzip2 +- cpp_common +- libconsole-bridge-dev +- libgpgme-dev +- libssl-dev +- pluginlib +- roscpp_serialization +- roscpp_traits +- rostime +- roslz4 ++ boost ++ bzip2 ++ libconsole-bridge-dev ++ libgpgme-dev ++ libssl-dev ++ pluginlib + + +- +- ++ ament_cmake + + diff --git a/ros1_rosbag_storage_vendor/resources/plugin_descriptionxml.diff b/ros1_rosbag_storage_vendor/resources/plugin_descriptionxml.diff new file mode 100644 index 0000000000..6e80a9913c --- /dev/null +++ b/ros1_rosbag_storage_vendor/resources/plugin_descriptionxml.diff @@ -0,0 +1,10 @@ +diff --git a/tools/rosbag_storage/encryptor_plugins.xml b/tools/rosbag_storage/encryptor_plugins.xml +index 3128ec9a5..fb66f450c 100644 +--- a/tools/rosbag_storage/encryptor_plugins.xml ++++ b/tools/rosbag_storage/encryptor_plugins.xml +@@ -1,4 +1,4 @@ +- ++ + + This is a plugin for no encryption. + diff --git a/ros1_rosbag_storage_vendor/resources/rosbag1_encryption_patch.diff b/ros1_rosbag_storage_vendor/resources/rosbag1_encryption_patch.diff new file mode 100644 index 0000000000..f944524e03 --- /dev/null +++ b/ros1_rosbag_storage_vendor/resources/rosbag1_encryption_patch.diff @@ -0,0 +1,573 @@ +diff --git a/tools/rosbag_storage/CMakeLists.txt b/tools/rosbag_storage/CMakeLists.txt +index ad2769817..dc49e2250 100644 +--- a/tools/rosbag_storage/CMakeLists.txt ++++ b/tools/rosbag_storage/CMakeLists.txt +@@ -28,19 +28,17 @@ add_definitions(${BZIP2_DEFINITIONS}) + set(AES_ENCRYPT_SOURCE "") + set(AES_ENCRYPT_LIBRARIES "") + if(NOT WIN32) +- set(AES_ENCRYPT_SOURCE "src/aes_encryptor.cpp") ++ set(AES_ENCRYPT_SOURCE "src/aes_encryptor.cpp" "src/gpgme_utils.cpp") + set(AES_ENCRYPT_LIBRARIES "crypto" "gpgme") + endif() + + add_library(rosbag_storage +- ${AES_ENCRYPT_SOURCE} + src/bag.cpp + src/bag_player.cpp + src/buffer.cpp + src/bz2_stream.cpp + src/lz4_stream.cpp + src/chunked_file.cpp +- src/encryptor.cpp + src/message_instance.cpp + src/query.cpp + src/stream.cpp +@@ -55,6 +53,19 @@ install(TARGETS rosbag_storage + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + ++add_library(rosbag_default_encryption_plugins ++ ${AES_ENCRYPT_SOURCE} ++ src/no_encryptor.cpp ++) ++ ++target_link_libraries(rosbag_default_encryption_plugins ${catkin_LIBRARIES} ${Boost_LIBRARIES} ${AES_ENCRYPT_LIBRARIES}) ++ ++install(TARGETS rosbag_default_encryption_plugins ++ ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} ++ LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} ++ RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ++) ++ + install(DIRECTORY include/ + DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" +@@ -68,10 +79,10 @@ if(NOT WIN32) + if(CATKIN_ENABLE_TESTING) + find_package(rostest) + +- catkin_add_gtest(test_aes_encryptor test/test_aes_encryptor.cpp ++ catkin_add_gtest(test_aes_encryptor test/test_aes_encryptor.cpp src/gpgme_utils.cpp + WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/test) + if(TARGET test_aes_encryptor) +- target_link_libraries(test_aes_encryptor rosbag_storage ${catkin_LIBRARIES} ${Boost_LIBRARIES}) ++ target_link_libraries(test_aes_encryptor rosbag_storage ${BZIP2_LIBRARIES} ${AES_ENCRYPT_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) + endif() + endif() + endif() +diff --git a/tools/rosbag_storage/encryptor_plugins.xml b/tools/rosbag_storage/encryptor_plugins.xml +index 91c0d31dc..3128ec9a5 100644 +--- a/tools/rosbag_storage/encryptor_plugins.xml ++++ b/tools/rosbag_storage/encryptor_plugins.xml +@@ -1,4 +1,4 @@ +- ++ + + This is a plugin for no encryption. + +diff --git a/tools/rosbag_storage/include/rosbag/aes_encryptor.h b/tools/rosbag_storage/include/rosbag/aes_encryptor.h +new file mode 100644 +index 000000000..b9a0ef6b0 +--- /dev/null ++++ b/tools/rosbag_storage/include/rosbag/aes_encryptor.h +@@ -0,0 +1,80 @@ ++/********************************************************************* ++* Software License Agreement (BSD License) ++* ++* Copyright (c) 2017, Open Source Robotics Foundation ++* All rights reserved. ++* ++* Redistribution and use in source and binary forms, with or without ++* modification, are permitted provided that the following conditions ++* are met: ++* ++* * Redistributions of source code must retain the above copyright ++* notice, this list of conditions and the following disclaimer. ++* * Redistributions in binary form must reproduce the above ++* copyright notice, this list of conditions and the following ++* disclaimer in the documentation and/or other materials provided ++* with the distribution. ++* * Neither the name of Willow Garage, Inc. nor the names of its ++* contributors may be used to endorse or promote products derived ++* from this software without specific prior written permission. ++* ++* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS ++* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT ++* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS ++* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE ++* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, ++* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, ++* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; ++* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER ++* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT ++* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ++* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ++* POSSIBILITY OF SUCH DAMAGE. ++*********************************************************************/ ++ ++#ifndef ROSBAG_AES_ENCRYPTION_H ++#define ROSBAG_AES_ENCRYPTION_H ++ ++#include "rosbag/encryptor.h" ++ ++#ifndef _WIN32 ++ #include ++ ++namespace rosbag { ++ ++class AesCbcEncryptor : public EncryptorBase ++{ ++public: ++ static const std::string GPG_USER_FIELD_NAME; ++ static const std::string ENCRYPTED_KEY_FIELD_NAME; ++ ++public: ++ AesCbcEncryptor() { } ++ ~AesCbcEncryptor() { } ++ ++ void initialize(Bag const& bag, std::string const& gpg_key_user); ++ uint32_t encryptChunk(const uint32_t chunk_size, const uint64_t chunk_data_pos, ChunkedFile& file); ++ void decryptChunk(ChunkHeader const& chunk_header, Buffer& decrypted_chunk, ChunkedFile& file) const; ++ void addFieldsToFileHeader(ros::M_string& header_fields) const; ++ void readFieldsFromFileHeader(ros::M_string const& header_fields); ++ void writeEncryptedHeader(boost::function, ros::M_string const& header_fields, ChunkedFile&); ++ bool readEncryptedHeader(boost::function, ros::Header& header, Buffer& header_buffer, ChunkedFile&); ++ ++private: ++ void buildSymmetricKey(); ++ ++private: ++ // User name of GPG key used for symmetric key encryption ++ std::string gpg_key_user_; ++ // Symmetric key for encryption/decryption ++ std::basic_string symmetric_key_; ++ // Encrypted symmetric key ++ std::string encrypted_symmetric_key_; ++ // AES keys for encryption/decryption ++ AES_KEY aes_encrypt_key_; ++ AES_KEY aes_decrypt_key_; ++}; ++} ++#endif ++ ++#endif +diff --git a/tools/rosbag_storage/include/rosbag/encryptor.h b/tools/rosbag_storage/include/rosbag/encryptor.h +index 2c3f8adab..b4dc31412 100644 +--- a/tools/rosbag_storage/include/rosbag/encryptor.h ++++ b/tools/rosbag_storage/include/rosbag/encryptor.h +@@ -46,10 +46,6 @@ + + #include + +-#ifndef _WIN32 +- #include +- #include +-#endif + + namespace rosbag { + +@@ -133,72 +129,6 @@ public: + virtual bool readEncryptedHeader(boost::function read_header, ros::Header& header, Buffer& header_buffer, ChunkedFile& file) = 0; + }; + +-class NoEncryptor : public EncryptorBase +-{ +-public: +- NoEncryptor() { } +- ~NoEncryptor() { } +- +- void initialize(Bag const&, std::string const&) { } +- uint32_t encryptChunk(const uint32_t, const uint64_t, ChunkedFile&); +- void decryptChunk(ChunkHeader const&, Buffer&, ChunkedFile&) const; +- void addFieldsToFileHeader(ros::M_string&) const { } +- void readFieldsFromFileHeader(ros::M_string const&) { } +- void writeEncryptedHeader(boost::function, ros::M_string const&, ChunkedFile&); +- bool readEncryptedHeader(boost::function, ros::Header&, Buffer&, ChunkedFile&); +-}; +- +-#ifndef _WIN32 +-//! Initialize GPGME library +-/*! +- * This method initializes GPGME library, and set locale. +- */ +-void initGpgme(); +- +-//! Get GPG key +-/*! +- * \param ctx GPGME context +- * \param user User name of the GPG key +- * \param key GPG key found +- * +- * This method outputs a GPG key in the system keyring corresponding to the given user name. +- * This method throws BagException if the key is not found or error occurred. +- */ +-void getGpgKey(gpgme_ctx_t& ctx, std::string const& user, gpgme_key_t& key); +- +-class AesCbcEncryptor : public EncryptorBase +-{ +-public: +- static const std::string GPG_USER_FIELD_NAME; +- static const std::string ENCRYPTED_KEY_FIELD_NAME; +- +-public: +- AesCbcEncryptor() { } +- ~AesCbcEncryptor() { } +- +- void initialize(Bag const& bag, std::string const& gpg_key_user); +- uint32_t encryptChunk(const uint32_t chunk_size, const uint64_t chunk_data_pos, ChunkedFile& file); +- void decryptChunk(ChunkHeader const& chunk_header, Buffer& decrypted_chunk, ChunkedFile& file) const; +- void addFieldsToFileHeader(ros::M_string& header_fields) const; +- void readFieldsFromFileHeader(ros::M_string const& header_fields); +- void writeEncryptedHeader(boost::function, ros::M_string const& header_fields, ChunkedFile&); +- bool readEncryptedHeader(boost::function, ros::Header& header, Buffer& header_buffer, ChunkedFile&); +- +-private: +- void buildSymmetricKey(); +- +-private: +- // User name of GPG key used for symmetric key encryption +- std::string gpg_key_user_; +- // Symmetric key for encryption/decryption +- std::basic_string symmetric_key_; +- // Encrypted symmetric key +- std::string encrypted_symmetric_key_; +- // AES keys for encryption/decryption +- AES_KEY aes_encrypt_key_; +- AES_KEY aes_decrypt_key_; +-}; +-#endif + } + + #endif +diff --git a/tools/rosbag_storage/include/rosbag/gpgme_utils.h b/tools/rosbag_storage/include/rosbag/gpgme_utils.h +new file mode 100644 +index 000000000..1e44a0fd1 +--- /dev/null ++++ b/tools/rosbag_storage/include/rosbag/gpgme_utils.h +@@ -0,0 +1,65 @@ ++/********************************************************************* ++* Software License Agreement (BSD License) ++* ++* Copyright (c) 2017, Open Source Robotics Foundation ++* All rights reserved. ++* ++* Redistribution and use in source and binary forms, with or without ++* modification, are permitted provided that the following conditions ++* are met: ++* ++* * Redistributions of source code must retain the above copyright ++* notice, this list of conditions and the following disclaimer. ++* * Redistributions in binary form must reproduce the above ++* copyright notice, this list of conditions and the following ++* disclaimer in the documentation and/or other materials provided ++* with the distribution. ++* * Neither the name of Willow Garage, Inc. nor the names of its ++* contributors may be used to endorse or promote products derived ++* from this software without specific prior written permission. ++* ++* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS ++* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT ++* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS ++* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE ++* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, ++* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, ++* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; ++* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER ++* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT ++* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ++* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ++* POSSIBILITY OF SUCH DAMAGE. ++*********************************************************************/ ++ ++#ifndef ROSBAG_GPGME_UTILS_H ++#define ROSBAG_GPGME_UTILS_H ++ ++#include "rosbag/encryptor.h" ++ ++#ifndef _WIN32 ++ #include ++ ++namespace rosbag { ++ ++//! Initialize GPGME library ++/*! ++ * This method initializes GPGME library, and set locale. ++ */ ++void initGpgme(); ++ ++//! Get GPG key ++/*! ++ * \param ctx GPGME context ++ * \param user User name of the GPG key ++ * \param key GPG key found ++ * ++ * This method outputs a GPG key in the system keyring corresponding to the given user name. ++ * This method throws BagException if the key is not found or error occurred. ++ */ ++void getGpgKey(gpgme_ctx_t& ctx, std::string const& user, gpgme_key_t& key); ++ ++} ++#endif ++ ++#endif +diff --git a/tools/rosbag_storage/include/rosbag/no_encryptor.h b/tools/rosbag_storage/include/rosbag/no_encryptor.h +new file mode 100644 +index 000000000..32e97df57 +--- /dev/null ++++ b/tools/rosbag_storage/include/rosbag/no_encryptor.h +@@ -0,0 +1,59 @@ ++/********************************************************************* ++* Software License Agreement (BSD License) ++* ++* Copyright (c) 2017, Open Source Robotics Foundation ++* All rights reserved. ++* ++* Redistribution and use in source and binary forms, with or without ++* modification, are permitted provided that the following conditions ++* are met: ++* ++* * Redistributions of source code must retain the above copyright ++* notice, this list of conditions and the following disclaimer. ++* * Redistributions in binary form must reproduce the above ++* copyright notice, this list of conditions and the following ++* disclaimer in the documentation and/or other materials provided ++* with the distribution. ++* * Neither the name of Willow Garage, Inc. nor the names of its ++* contributors may be used to endorse or promote products derived ++* from this software without specific prior written permission. ++* ++* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS ++* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT ++* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS ++* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE ++* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, ++* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, ++* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; ++* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER ++* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT ++* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ++* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ++* POSSIBILITY OF SUCH DAMAGE. ++*********************************************************************/ ++ ++#ifndef ROSBAG_NO_ENCRYPTION_H ++#define ROSBAG_NO_ENCRYPTION_H ++ ++#include "rosbag/encryptor.h" ++ ++ ++namespace rosbag { ++ ++class NoEncryptor : public EncryptorBase ++{ ++public: ++ NoEncryptor() { } ++ ~NoEncryptor() { } ++ ++ void initialize(Bag const&, std::string const&) { } ++ uint32_t encryptChunk(const uint32_t, const uint64_t, ChunkedFile&); ++ void decryptChunk(ChunkHeader const&, Buffer&, ChunkedFile&) const; ++ void addFieldsToFileHeader(ros::M_string&) const { } ++ void readFieldsFromFileHeader(ros::M_string const&) { } ++ void writeEncryptedHeader(boost::function, ros::M_string const&, ChunkedFile&); ++ bool readEncryptedHeader(boost::function, ros::Header&, Buffer&, ChunkedFile&); ++}; ++} ++ ++#endif +diff --git a/tools/rosbag_storage/src/aes_encryptor.cpp b/tools/rosbag_storage/src/aes_encryptor.cpp +index e0fcb807e..73f88de5a 100644 +--- a/tools/rosbag_storage/src/aes_encryptor.cpp ++++ b/tools/rosbag_storage/src/aes_encryptor.cpp +@@ -33,7 +33,8 @@ + *********************************************************************/ + + #include "rosbag/bag.h" +-#include "rosbag/encryptor.h" ++#include "rosbag/aes_encryptor.h" ++#include "rosbag/gpgme_utils.h" + + #include + +@@ -47,53 +48,6 @@ namespace rosbag + const std::string AesCbcEncryptor::GPG_USER_FIELD_NAME = "gpg_user"; + const std::string AesCbcEncryptor::ENCRYPTED_KEY_FIELD_NAME = "encrypted_key"; + +-void initGpgme() { +- // Check version method must be called before en/decryption +- gpgme_check_version(0); +- // Set locale +- setlocale(LC_ALL, ""); +- gpgme_set_locale(NULL, LC_CTYPE, setlocale(LC_CTYPE, NULL)); +-#ifdef LC_MESSAGES +- gpgme_set_locale(NULL, LC_MESSAGES, setlocale(LC_MESSAGES, NULL)); +-#endif +-} +- +-void getGpgKey(gpgme_ctx_t& ctx, std::string const& user, gpgme_key_t& key) { +- gpgme_error_t err; +- // Asterisk means an arbitrary user. +- if (user == std::string("*")) { +- err = gpgme_op_keylist_start(ctx, 0, 0); +- } else { +- err = gpgme_op_keylist_start(ctx, user.c_str(), 0); +- } +- if (err) { +- throw BagException((boost::format("gpgme_op_keylist_start returned %1%") % gpgme_strerror(err)).str()); +- } +- while (true) { +- err = gpgme_op_keylist_next(ctx, &key); +- if (!err) { +- if (user == std::string("*") || strcmp(key->uids->name, user.c_str()) == 0) { +- break; +- } +- gpgme_key_release(key); +- } else if (gpg_err_code(err) == GPG_ERR_EOF) { +- if (user == std::string("*")) { +- // A method throws an exception (instead of returning a specific value) if the key is not found +- // This allows rosbag client applications to work without modifying their source code +- throw BagException("GPG key not found"); +- } else { +- throw BagException((boost::format("GPG key not found for a user %1%") % user.c_str()).str()); +- } +- } else { +- throw BagException((boost::format("gpgme_op_keylist_next returned %1%") % err).str()); +- } +- } +- err = gpgme_op_keylist_end(ctx); +- if (err) { +- throw BagException((boost::format("gpgme_op_keylist_end returned %1%") % gpgme_strerror(err)).str()); +- } +-} +- + //! Encrypt string using GPGME + /*! + * \return Encrypted string +diff --git a/tools/rosbag_storage/src/gpgme_utils.cpp b/tools/rosbag_storage/src/gpgme_utils.cpp +new file mode 100644 +index 000000000..69ce9bd4e +--- /dev/null ++++ b/tools/rosbag_storage/src/gpgme_utils.cpp +@@ -0,0 +1,90 @@ ++/********************************************************************* ++* Software License Agreement (BSD License) ++* ++* Copyright (c) 2017, Open Source Robotics Foundation ++* All rights reserved. ++* ++* Redistribution and use in source and binary forms, with or without ++* modification, are permitted provided that the following conditions ++* are met: ++* ++* * Redistributions of source code must retain the above copyright ++* notice, this list of conditions and the following disclaimer. ++* * Redistributions in binary form must reproduce the above ++* copyright notice, this list of conditions and the following ++* disclaimer in the documentation and/or other materials provided ++* with the distribution. ++* * Neither the name of Willow Garage, Inc. nor the names of its ++* contributors may be used to endorse or promote products derived ++* from this software without specific prior written permission. ++* ++* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS ++* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT ++* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS ++* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE ++* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, ++* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, ++* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; ++* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER ++* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT ++* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ++* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ++* POSSIBILITY OF SUCH DAMAGE. ++*********************************************************************/ ++ ++#include "rosbag/gpgme_utils.h" ++ ++#include ++ ++namespace rosbag ++{ ++ ++void initGpgme() { ++ // Check version method must be called before en/decryption ++ gpgme_check_version(0); ++ // Set locale ++ setlocale(LC_ALL, ""); ++ gpgme_set_locale(NULL, LC_CTYPE, setlocale(LC_CTYPE, NULL)); ++#ifdef LC_MESSAGES ++ gpgme_set_locale(NULL, LC_MESSAGES, setlocale(LC_MESSAGES, NULL)); ++#endif ++} ++ ++void getGpgKey(gpgme_ctx_t& ctx, std::string const& user, gpgme_key_t& key) { ++ gpgme_error_t err; ++ // Asterisk means an arbitrary user. ++ if (user == std::string("*")) { ++ err = gpgme_op_keylist_start(ctx, 0, 0); ++ } else { ++ err = gpgme_op_keylist_start(ctx, user.c_str(), 0); ++ } ++ if (err) { ++ throw BagException((boost::format("gpgme_op_keylist_start returned %1%") % gpgme_strerror(err)).str()); ++ } ++ while (true) { ++ err = gpgme_op_keylist_next(ctx, &key); ++ if (!err) { ++ if (user == std::string("*") || strcmp(key->uids->name, user.c_str()) == 0) { ++ break; ++ } ++ gpgme_key_release(key); ++ } else if (gpg_err_code(err) == GPG_ERR_EOF) { ++ if (user == std::string("*")) { ++ // A method throws an exception (instead of returning a specific value) if the key is not found ++ // This allows rosbag client applications to work without modifying their source code ++ throw BagException("GPG key not found"); ++ } else { ++ throw BagException((boost::format("GPG key not found for a user %1%") % user.c_str()).str()); ++ } ++ } else { ++ throw BagException((boost::format("gpgme_op_keylist_next returned %1%") % err).str()); ++ } ++ } ++ err = gpgme_op_keylist_end(ctx); ++ if (err) { ++ throw BagException((boost::format("gpgme_op_keylist_end returned %1%") % gpgme_strerror(err)).str()); ++ } ++} ++ ++ ++} // namespace rosbag +diff --git a/tools/rosbag_storage/src/encryptor.cpp b/tools/rosbag_storage/src/no_encryptor.cpp +similarity index 97% +rename from tools/rosbag_storage/src/encryptor.cpp +rename to tools/rosbag_storage/src/no_encryptor.cpp +index 17c62815d..9e6174020 100644 +--- a/tools/rosbag_storage/src/encryptor.cpp ++++ b/tools/rosbag_storage/src/no_encryptor.cpp +@@ -32,7 +32,8 @@ + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +-#include "rosbag/encryptor.h" ++#include "rosbag/bag.h" ++#include "rosbag/no_encryptor.h" + + #include + +diff --git a/tools/rosbag_storage/test/test_aes_encryptor.cpp b/tools/rosbag_storage/test/test_aes_encryptor.cpp +index 7de167cf0..0a9c8abdb 100644 +--- a/tools/rosbag_storage/test/test_aes_encryptor.cpp ++++ b/tools/rosbag_storage/test/test_aes_encryptor.cpp +@@ -41,7 +41,8 @@ + #include "std_msgs/String.h" + + #include "rosbag/bag.h" +-#include "rosbag/encryptor.h" ++#include "rosbag/aes_encryptor.h" ++#include "rosbag/gpgme_utils.h" + #include "rosbag/view.h" + + const char *GPG_KEY_USER = "Foo00"; diff --git a/ros2bag/ros2bag/verb/info.py b/ros2bag/ros2bag/verb/info.py index a38b94ec1e..19a27df4bc 100644 --- a/ros2bag/ros2bag/verb/info.py +++ b/ros2bag/ros2bag/verb/info.py @@ -25,10 +25,14 @@ class InfoVerb(VerbExtension): def add_arguments(self, parser, cli_name): # noqa: D102 parser.add_argument( 'bag_file', help='bag file to introspect') + parser.add_argument( + '-s', '--storage', default='sqlite3', + help='storage identifier to be used to open storage, if no yaml file exists.' + ' Defaults to "sqlite3"') def main(self, *, args): # noqa: D102 bag_file = args.bag_file if not os.path.exists(bag_file): return "[ERROR] [ros2bag]: bag file '{}' does not exist!".format(bag_file) - rosbag2_transport_py.info(uri=bag_file) + rosbag2_transport_py.info(uri=bag_file, storage_id=args.storage) diff --git a/rosbag2/include/rosbag2/info.hpp b/rosbag2/include/rosbag2/info.hpp index fa7a473ced..1e7709b633 100644 --- a/rosbag2/include/rosbag2/info.hpp +++ b/rosbag2/include/rosbag2/info.hpp @@ -29,7 +29,7 @@ class ROSBAG2_PUBLIC Info virtual ~Info() = default; virtual rosbag2::BagMetadata read_metadata( - const std::string & uri, const std::string & storage_id = ""); + const std::string & uri, const std::string & storage_id); }; } // namespace rosbag2 diff --git a/rosbag2/src/rosbag2/info.cpp b/rosbag2/src/rosbag2/info.cpp index e33e881446..1b73a628d0 100644 --- a/rosbag2/src/rosbag2/info.cpp +++ b/rosbag2/src/rosbag2/info.cpp @@ -39,7 +39,6 @@ rosbag2::BagMetadata Info::read_metadata(const std::string & uri, const std::str "opened."); } auto bag_metadata = storage->get_metadata(); - bag_metadata.bag_size = rosbag2_storage::FilesystemHelper::calculate_directory_size(uri); return bag_metadata; } throw std::runtime_error("The metadata.yaml file does not exist. Please specify a the " diff --git a/rosbag2/src/rosbag2/typesupport_helpers.cpp b/rosbag2/src/rosbag2/typesupport_helpers.cpp index 163c66e891..2abf2fdcd6 100644 --- a/rosbag2/src/rosbag2/typesupport_helpers.cpp +++ b/rosbag2/src/rosbag2/typesupport_helpers.cpp @@ -48,7 +48,13 @@ std::string get_typesupport_library_path( dynamic_library_folder = "/lib/"; #endif - auto package_prefix = ament_index_cpp::get_package_prefix(package_name); + std::string package_prefix; + try { + package_prefix = ament_index_cpp::get_package_prefix(package_name); + } catch (ament_index_cpp::PackageNotFoundError & e) { + throw std::runtime_error(e.what()); + } + auto library_path = package_prefix + dynamic_library_folder + filename_prefix + package_name + "__" + typesupport_identifier + filename_extension; return library_path; diff --git a/rosbag2/test/rosbag2/test_info.cpp b/rosbag2/test/rosbag2/test_info.cpp index b3cd4942e5..61ba87dadb 100644 --- a/rosbag2/test/rosbag2/test_info.cpp +++ b/rosbag2/test/rosbag2/test_info.cpp @@ -63,7 +63,7 @@ TEST_F(TemporaryDirectoryFixture, read_metadata_makes_appropriate_call_to_metada fout.close(); rosbag2::Info info; - auto read_metadata = info.read_metadata(temporary_dir_path_); + auto read_metadata = info.read_metadata(temporary_dir_path_, "sqlite3"); EXPECT_THAT(read_metadata.storage_identifier, Eq("sqlite3")); EXPECT_THAT(read_metadata.relative_file_paths, diff --git a/rosbag2/test/rosbag2/test_typesupport_helpers.cpp b/rosbag2/test/rosbag2/test_typesupport_helpers.cpp index 00d8c13b79..7c110204cf 100644 --- a/rosbag2/test/rosbag2/test_typesupport_helpers.cpp +++ b/rosbag2/test/rosbag2/test_typesupport_helpers.cpp @@ -49,8 +49,8 @@ TEST(TypesupportHelpersTest, separates_into_package_and_name_for_correct_package } TEST(TypesupportHelpersTest, throws_exception_if_library_cannot_be_found) { - EXPECT_THROW(rosbag2::get_typesupport("invalid/message", "rosidl_typesupport_cpp"), - ament_index_cpp::PackageNotFoundError); + EXPECT_THROW( + rosbag2::get_typesupport("invalid/message", "rosidl_typesupport_cpp"), std::runtime_error); } TEST(TypesupportHelpersTest, returns_c_type_info_for_valid_library) { diff --git a/rosbag2_bag_v2_plugins/CMakeLists.txt b/rosbag2_bag_v2_plugins/CMakeLists.txt new file mode 100644 index 0000000000..879f7eee38 --- /dev/null +++ b/rosbag2_bag_v2_plugins/CMakeLists.txt @@ -0,0 +1,169 @@ +cmake_minimum_required(VERSION 3.5) +project(rosbag2_bag_v2_plugins) + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) + +find_package(PkgConfig) +if(NOT PKG_CONFIG_FOUND) + message(WARNING "Failed to find PkgConfig, skipping...") + # call ament_package() to avoid ament_tools treating this as a plain CMake pkg + ament_package() + return() +endif() + +# include bridge first to not create package if ros1 packages cannot be found +find_package(ros1_bridge REQUIRED) +include(${ros1_bridge_DIR}/find_ros1_interface_packages.cmake) +include(${ros1_bridge_DIR}/find_ros1_package.cmake) + +find_ros1_package(roscpp) +if(NOT ros1_roscpp_FOUND) + message(WARNING "Failed to find ROS 1 roscpp, skipping...") + # call ament_package() to avoid ament_tools treating this as a plain CMake pkg + ament_package() + return() +endif() + +find_package(pluginlib REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rcutils REQUIRED) +find_package(rosbag2 REQUIRED) +find_package(rosbag2_storage REQUIRED) +find_package(ros1_rosbag_storage REQUIRED) # provided by ros1_rosbag_storage_vendor + +# Find transitive ros1 dependencies for ros1_rosbag_storage +find_ros1_package(cpp_common) +find_ros1_package(roscpp_serialization) +find_ros1_package(roscpp_traits) +find_ros1_package(rostime) +find_ros1_package(roslz4) + +set(generated_path "${CMAKE_BINARY_DIR}/generated") +set(generated_files "${generated_path}/convert_rosbag_message.cpp") + +add_custom_command( + OUTPUT ${generated_files} + COMMAND python3 ${CMAKE_CURRENT_SOURCE_DIR}/src/generate_coverter_cpp.py + --output-path "${generated_path}" --template-dir ${CMAKE_CURRENT_SOURCE_DIR}/src/rosbag2_bag_v2_plugins + WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} +) + +find_ros1_interface_packages(ros1_message_packages) + +set(prefixed_ros1_message_packages "") +foreach(ros1_message_package ${ros1_message_packages}) + if(NOT "${ros1_message_package}" STREQUAL "nodelet") + find_ros1_package(${ros1_message_package} REQUIRED) + list(APPEND prefixed_ros1_message_packages "ros1_${ros1_message_package}") + endif() +endforeach() + +# generate conversion methods +ament_index_get_resources(ros2_message_packages "rosidl_interfaces") +foreach(message_package ${ros2_message_packages}) + find_package(${message_package} REQUIRED) + message(STATUS "Found ${message_package}: ${${message_package}_VERSION} (${${message_package}_DIR})") +endforeach() + +add_library( + ${PROJECT_NAME} SHARED + src/rosbag2_bag_v2_plugins/converter/rosbag_v2_deserializer.cpp + src/rosbag2_bag_v2_plugins/storage/rosbag_output_stream.cpp + src/rosbag2_bag_v2_plugins/storage/rosbag_v2_storage.cpp + ${generated_files}) + +ament_target_dependencies(${PROJECT_NAME} + ros1_rosbag_storage + rclcpp + rosbag2_storage + rosbag2 + ros1_bridge + pluginlib + ros1_cpp_common + ros1_roscpp + ros1_roscpp_serialization + ros1_roscpp_traits + ros1_rostime + ros1_roslz4 + ${ros2_message_packages} + ${prefixed_ros1_message_packages}) + +target_include_directories(${PROJECT_NAME} + PUBLIC + $ +) + +# This is necessary on some systems where CMake declares ros2 paths as "system paths" thereby +# messing up the include order. This results in this package being built with the wrong pluginlib +# i.e. the pluginlib from ROS 1. Symptoms of this problem are missing symbols for class loader +# classes (i.e. class_loader::impl::...) when linking the tests in this package +set_target_properties(${PROJECT_NAME} PROPERTIES NO_SYSTEM_FROM_IMPORTED 1) + +# Causes the visibility macros to use dllexport rather than dllimport, +# which is appropriate when building the dll but not consuming it. +target_compile_definitions(${PROJECT_NAME} PRIVATE + ROSBAG2_BAG_V2_PLUGINS_BUILDING_DLL) + +pluginlib_export_plugin_description_file(rosbag2_storage storage_plugin_description.xml) +pluginlib_export_plugin_description_file(rosbag2 converter_plugin_description.xml) + +install( + TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin) + +ament_export_libraries(${PROJECT_NAME}) +ament_export_dependencies(rosbag2_storage) +ament_export_dependencies(rosbag2 ros1_rosbag_storage rosbag2_storage) + + +if(BUILD_TESTING) + find_package(ament_cmake_gmock REQUIRED) + find_package(ament_lint_auto REQUIRED) + find_package(rosbag2_test_common REQUIRED) + + ament_lint_auto_find_test_dependencies() + + add_definitions(-D_SRC_RESOURCES_DIR_PATH="${CMAKE_CURRENT_SOURCE_DIR}/resources") + + ament_add_gmock(test_rosbag_v2_storage + test/rosbag2_bag_v2_plugins/test_rosbag_v2_storage.cpp + WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}) + if(TARGET test_rosbag_v2_storage) + target_include_directories(test_rosbag_v2_storage + PUBLIC + $) + target_link_libraries(test_rosbag_v2_storage ${PROJECT_NAME}) + ament_target_dependencies(test_rosbag_v2_storage + rosbag2_test_common) + endif() + + ament_add_gmock(test_rosbag_output_stream + test/rosbag2_bag_v2_plugins/test_rosbag_output_stream.cpp + WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}) + if(TARGET test_rosbag_output_stream) + target_include_directories(test_rosbag_output_stream + PUBLIC + $) + target_link_libraries(test_rosbag_output_stream ${PROJECT_NAME}) + ament_target_dependencies(test_rosbag_output_stream + rosbag2_test_common) + endif() +endif() + +ament_package() diff --git a/rosbag2_bag_v2_plugins/README.md b/rosbag2_bag_v2_plugins/README.md new file mode 100644 index 0000000000..a194ebdf17 --- /dev/null +++ b/rosbag2_bag_v2_plugins/README.md @@ -0,0 +1,70 @@ +# The plugin for rosbags from ROS 1 + +It is possible to read old bag files with `ros2`. +This requires translating ROS 1 messages into ROS 2 messages similar to the `ros1_bridge`. +If your rosbags contain custom message formats which can be translated into ROS 2 messages, the plugins need to be built from source. + +## Building the ROS 1 plugin + +You need to have the `ros1_bridge` built (see ). +Secondly, this plugin is part of the `rosbag2` plugin architecture. +It is thus required that `rosbag2` is correctly installed, see . + +We assume that the ROS 2 as well as the rosbag2 environment is correctly built and sourced. +Then, in a fresh terminal: + +* Source your ROS 1 installation +* Source your ROS 2 installation (including the `ros1_bridge`) +* Build the workspace using `colcon build --merge-install` + +This will automatically match all ROS 1 messages to their ROS 2 counterpart using the same logic as the `ros1_bridge`. + +**N.B:** The ROS 1 installation must be sourced first to avoid problems with the `class_loader`. +It happens to occur that cyclic dependencies are detected when compiling this plugin. +The reason for this is that some packages which contain message definitions in ROS 1 also depend on class loader. +It is therefore very important to source the ROS 2 installation after ROS 1 in order to guarantee that the ROS 2 class loader is correctly found and linked. +There is an open issue for this stating that the ROS 1 and ROS 2 class loader API should be provide some basic interoperability. +See https://github.com/ros/class_loader/issues/109 + +## Using the plugins + +In order to use the plugins, again, the ROS 1 installation must be sourced **before** sourcing the ROS 2 installation. + +You can then just use the plugin through the regular interface. +For instance, on the command line write: + +``` +ros2 bag info -s rosbag_v2 +``` +Here, `-s rosbag_v2` tells rosbag2 to use the plugin to read rosbags (version 2) to query the bagfile. +For old rosbags, the storage format must be added to the info call as rosbag does not have the necessary information to read the plugin otherwise. + +The command above should print something like the following: + +``` +Files: test_bag.bag +Bag size: 8.8 KiB +Storage id: rosbag_v2 +Duration: 0.268s +Start: Nov 29 2018 16:43:33.298 (1543509813.298) +End Nov 29 2018 16:43:33.567 (1543509813.567) +Messages: 5 +Topic information: Topic: /rosout | Type: rosgraph_msgs/Log | Count: 3 | Serialization Format: rosbag_v2 + Topic: /test_topic | Type: std_msgs/String | Count: 1 | Serialization Format: rosbag_v2 + Topic: /test_topic2 | Type: std_msgs/String | Count: 1 | Serialization Format: rosbag_v2 +``` + +For playing, one can similarly write: + +``` +ros2 bag play -s rosbag_v2 +``` + +If there is ROS 1 data where no topic matching exists to ROS 2 these topics are ignored when replying. +When calling `ros2 bag info`, one can see a list of mismatching topics: + +``` +[INFO] [rosbag2_bag_v2_plugins]: ROS 1 to ROS 2 type mapping is not available for topic '/rosout' which is of type 'rosgraph_msgs/Log'. Skipping messages of this topic when replaying +``` + +Currently, split bagfiles are unsupported. diff --git a/rosbag2_bag_v2_plugins/converter_plugin_description.xml b/rosbag2_bag_v2_plugins/converter_plugin_description.xml new file mode 100644 index 0000000000..47b3785a06 --- /dev/null +++ b/rosbag2_bag_v2_plugins/converter_plugin_description.xml @@ -0,0 +1,13 @@ + + + + This is a deserializer plugin which allows to convert ROS 1 messages via the + ros1_bridge to ROS 2 messages, if both message definitions are present. + This plugin needs to be build from source if custom messages are to be supported. + + + \ No newline at end of file diff --git a/rosbag2_bag_v2_plugins/package.xml b/rosbag2_bag_v2_plugins/package.xml new file mode 100644 index 0000000000..5ee5852e9d --- /dev/null +++ b/rosbag2_bag_v2_plugins/package.xml @@ -0,0 +1,27 @@ + + + rosbag2_bag_v2_plugins + 0.0.0 + Package containing storage and converter plugins for rosbag 1 + Karsten Knese + Apache License 2.0 + + ament_cmake + + pluginlib + rcutils + rclcpp + ros1_rosbag_storage_vendor + rosbag2_storage + rosbag2 + + rosbag2_test_common + ament_lint_auto + ament_lint_common + ament_cmake_gmock + std_msgs + + + ament_cmake + + diff --git a/rosbag2_bag_v2_plugins/resources/test_bag.bag b/rosbag2_bag_v2_plugins/resources/test_bag.bag new file mode 100644 index 0000000000000000000000000000000000000000..67e05851fdf8ca48ceccfd33bbaecf53716b2650 GIT binary patch literal 9023 zcmeHNOOG2x5H@+j0D|SMAVEit$OG-J$6oK+RtB+AvPq0BK!resK!resK!resK!resK!resK!resK!w2n8G+MyjL+T!MB~^f zYlBF8I?}3myg&R1#%*v*c^^5o8r`p;gF5LYfrqku5peWz)RQOPvy!?oH8 zqU2$yOd!#(L}X;&ZLhT2jc&(nHP_nR&T4C=1ID$GCt?(6-*Zo*HI{9gjy*1hL)mHw zxjI;ts?`{}%|^G?5$>93cU!~3rx0`uxw)_UQVjzgB&0&U?$qmSOI^pp$%KWdgbX6v zgzLm&%o$7)#m-+i_tr(vWp$|rsh^YOBbTpkT=SZY)qSOv;o z*|7_oo7XnI4y!9;A~QR(vA(^2#dB9#eaI6YE(=H&0Gom)mv|#kq0HpFq_|Xujj|$_ zDbvESiJ>($A1hYRi)hG_kzzWMsvI6$AEN~_tn3{IAx+8(no*7mVm361g?8tA0eWMQC*b5`t5n9Kd{`z&)33*xMjX<#8gPo_$+I30w69VzQL-amXfZ){!c zF`LLfAhOFj%np17o*}uBz$D=k7Ggu#Zxr|=WfpV)f%A-GC0RC_Ok!o1FmZbnScYHW zDB*;q7DPz|e;bce4I9JLk^orG&d1C^GtOde;09^P4d}5u0!`#Y1B(!M{H*#gRaz)^ z`Ft<)VI|TefJ0BfK^Vm?`NQS&%qeVv2~K_cMzjdiC?8HVT|9>w!m69uZik%Q_OQko zAOhu# zhMS2)vvO6P`UYVPBFxGxijrF!i2w$W>_(7`Abz8VZIzn?Ew{(~FdAUfW(Jz>7UI+o zq;pRUe2#)5JjFvu^bLEu#8X;#D;-z_nE~MgZ!Ds6mnJ6Tcp3db1c8qR7RM@#WFQt%A8>!sU2<2JTFcgm zVi9GQL>#YSvK?`wWIs;KSrGSn1T1a z`Clu42I5T<2l~`dq!>p@xgv4c5%+6!lB>)l50TBN`fj7uXqQRE+G=C1+1)dJ=ysbz zb-26QSrbZhL}ws7ot6@7Ex}h@>As95c1a(KGnT@Fv#WT|kj%8Nrw7Sab}Y|%_l%PB zyZXx?zCTVMS{@}XWTAY$SJ9jzL_5Ajh`zwwgHZDu^zI2!v%3Qk5+%3sZ$h-YeEY&^ zM$LJQg6%uUDKUMFbl<_Kxs3J{B-Cr9SpNNrf<*z@p@&gN@|S(nI)Qo_OfMlRr8)(e z*N^0N+Hhx&A}oS#%9@O~!+OS)bF4`^Vn-Hz33KOIkZ${DK?fqtLn8xKgzAYn^NGV*_` z(BDv=rQ875&iP8GKbcl(*{8?6?D>ff)xz#ap2i@aHVqQua+n^kW;2BsKtdPsq9dPf II>o8{6OE^~fdBvi literal 0 HcmV?d00001 diff --git a/rosbag2_bag_v2_plugins/resources/test_bag_multiple_connections.bag b/rosbag2_bag_v2_plugins/resources/test_bag_multiple_connections.bag new file mode 100644 index 0000000000000000000000000000000000000000..237664366c87da6385b6455ecb69d9ee78163a88 GIT binary patch literal 9940 zcmeHNOOM<{5FYY`SrE@8C@7-QAo7rQcRZelXM_Spd7n%3howe??$^*jjr5Yh#Itx2aPldXlQ8mZb2ScCm?mfO^59jX zy4-Jn4%}zN?Z888bI~jInD0|R|qTeQFlQ^6%2-CnOAc?pr z?mZy&f<*5y-wTLy_Sl;+m;1wyS!N^(#91NJKtX<aK;(e*5T=j0eOtzrB0nqjTTsOFx6hQQTCYrhn2_ z**NkN{@rIkrFnN!OJS3-2p?GEd{-XQz+@V&q8*4}mg}a(OJpI7;HzK|C52)5!P@mX98dwzG|1#-ov%3n72SP`VDLx4G0^ z`UTV!hDh(=&S}J+f7bgfXbORt_f8fxChYZ3zDoo1w9=Aj9bN^h1hGNz+|yzQ>-h z`O_aQg5Yc170;r^0-HTe_kNzGwKZ*l%dpe!^!LT(k$P51$z53P0hZst{G?48{gb#$ zp4C}Jec@UtH%PDi!(Yk#jy;Z6WX;*fz!y<2qR>@j^Hipt`OOoEA?RDMBRAh=S91Ca zJCcZ4kng{Oc`7VOhJ&*pzqpF&D=f%T4#uJ|9|7_T3qti^EDET2Kj$YaVwgZ(zu7!^zbIE6~irM zW)FU_JH+XyfOpbw!SbJs(Qm;{QJ#rwH)EpTi&4rg12Lv|EoPA>%{}=9ordtrC&m%3 b{EnlXbzT4oUE~{-O441F$%=~flAeD7kvgT7 literal 0 HcmV?d00001 diff --git a/rosbag2_bag_v2_plugins/src/generate_coverter_cpp.py b/rosbag2_bag_v2_plugins/src/generate_coverter_cpp.py new file mode 100644 index 0000000000..8cb9b36f5b --- /dev/null +++ b/rosbag2_bag_v2_plugins/src/generate_coverter_cpp.py @@ -0,0 +1,54 @@ +# 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. + +import argparse +import os +import sys + +from ros1_bridge import generate_messages +from rosidl_cmake import expand_template + + +def generate_cpp(output_path, template_dir): + data = generate_messages() + + template_file = os.path.join(template_dir, 'convert_rosbag_message.cpp.em') + output_file = os.path.join(output_path, 'convert_rosbag_message.cpp') + data_for_template = {'mappings': data['mappings']} + expand_template(template_file, data_for_template, output_file) + + +def main(argv=sys.argv[1:]): + parser = argparse.ArgumentParser( + description='Generate a C++ template converter specialization for rosbag_storage to ROS 2', + formatter_class=argparse.ArgumentDefaultsHelpFormatter) + parser.add_argument( + '--output-path', + required=True, + help='The path to the generated C++ files') + parser.add_argument( + '--template-dir', + required=True, + help='The location of the template file') + args = parser.parse_args(argv) + + try: + return generate_cpp(args.output_path, args.template_dir) + except RuntimeError as e: + print(str(e), file=sys.stderr) + return 1 + + +if __name__ == '__main__': + sys.exit(main()) diff --git a/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/convert_rosbag_message.cpp.em b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/convert_rosbag_message.cpp.em new file mode 100644 index 0000000000..8411f7216d --- /dev/null +++ b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/convert_rosbag_message.cpp.em @@ -0,0 +1,78 @@ +// 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. +@{ +from ros1_bridge import camel_case_to_lower_case_underscore +}@ + +#include "convert_rosbag_message.hpp" + +#include +#include +#include + +#include "ros1_bridge/bridge.hpp" +#include "ros1_bridge/factory_interface.hpp" + +#include "rclcpp/rclcpp.hpp" +#include "rcutils/allocator.h" +#include "rosbag2_storage/ros_helper.hpp" +#include "rosbag2/typesupport_helpers.hpp" +#include "rosbag2/types/introspection_message.hpp" + +@[for m in mappings]@ +#include "@(m.ros1_msg.package_name)/@(m.ros1_msg.message_name).h" +#include "@(m.ros2_msg.package_name)/msg/@(camel_case_to_lower_case_underscore(m.ros2_msg.message_name)).hpp" +@[end for]@ + +namespace rosbag2_bag_v2_plugins +{ + +bool get_1to2_mapping(const std::string & ros1_message_type, std::string & ros2_message_type) +{ + return ros1_bridge::get_1to2_mapping(ros1_message_type, ros2_message_type); +} + +void +convert_1_to_2( + const std::string & ros1_type_name, + ros::serialization::IStream & ros1_message_stream, + std::shared_ptr ros2_message) +{ + @[if not mappings]@ + (void) ros1_type_name; + (void) ros1_message_stream; + (void) ros2_message; + @[end if]@ + + std::string ros2_type_name; + ros1_bridge::get_1to2_mapping(ros1_type_name, ros2_type_name); + + @[for m in mappings]@ + if (ros1_type_name == "@(m.ros1_msg.package_name)/@(m.ros1_msg.message_name)" + && ros2_type_name == "@(m.ros2_msg.package_name)/@(m.ros2_msg.message_name)") + { + @(m.ros1_msg.package_name)::@(m.ros1_msg.message_name) typed_ros1_message; + + ros::serialization + ::Serializer<@(m.ros1_msg.package_name)::@(m.ros1_msg.message_name)> + ::read(ros1_message_stream, typed_ros1_message); + + auto factory = ros1_bridge::get_factory( + "@(m.ros1_msg.package_name)/@(m.ros1_msg.message_name)", + "@(m.ros2_msg.package_name)/@(m.ros2_msg.message_name)"); + factory->convert_1_to_2(&typed_ros1_message, ros2_message->message); + } + @[end for]@ +} +} // end namespace rosbag2_bag_v2_plugin \ No newline at end of file diff --git a/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/convert_rosbag_message.hpp b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/convert_rosbag_message.hpp new file mode 100644 index 0000000000..ce23d04a33 --- /dev/null +++ b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/convert_rosbag_message.hpp @@ -0,0 +1,36 @@ +// 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_BAG_V2_PLUGINS__CONVERT_ROSBAG_MESSAGE_HPP_ +#define ROSBAG2_BAG_V2_PLUGINS__CONVERT_ROSBAG_MESSAGE_HPP_ + +#include +#include + +#include "rosbag/message_instance.h" +#include "rosbag2/types.hpp" +#include "rosbag2/types/introspection_message.hpp" + +namespace rosbag2_bag_v2_plugins +{ +bool get_1to2_mapping(const std::string & ros1_message_type, std::string & ros2_message_type); + +void +convert_1_to_2( + const std::string & ros1_type_name, + ros::serialization::IStream & ros1_message_stream, + std::shared_ptr ros2_message); +} // namespace rosbag2_bag_v2_plugins + +#endif // ROSBAG2_BAG_V2_PLUGINS__CONVERT_ROSBAG_MESSAGE_HPP_ diff --git a/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/converter/rosbag_v2_deserializer.cpp b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/converter/rosbag_v2_deserializer.cpp new file mode 100644 index 0000000000..8cebd5def3 --- /dev/null +++ b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/converter/rosbag_v2_deserializer.cpp @@ -0,0 +1,56 @@ +// 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 "rosbag_v2_deserializer.hpp" + +#include +#include + +#include "rosbag/message_instance.h" + +#include "rosbag2/converter_interfaces/serialization_format_deserializer.hpp" +#include "rosbag2/types/introspection_message.hpp" +#include "../convert_rosbag_message.hpp" + +namespace rosbag2_bag_v2_plugins +{ +void RosbagV2Deserializer::deserialize( + std::shared_ptr serialized_message, + const rosidl_message_type_support_t * type_support, + std::shared_ptr ros_message) +{ + (void) type_support; + + // See rosbag_output_stream.cpp for reasoning: The serialialized data starts with a + // null-terminated string containing the data_type of the message and then the message itself + // in serialized form + auto ros1_data_type = std::string( + reinterpret_cast(serialized_message->serialized_data->buffer)); + + size_t data_type_zero_terminated_length = ros1_data_type.length() + 1; + ros::serialization::IStream stream( + serialized_message->serialized_data->buffer + data_type_zero_terminated_length, + serialized_message->serialized_data->buffer_length - data_type_zero_terminated_length); + + convert_1_to_2(ros1_data_type, stream, ros_message); + + ros_message->time_stamp = serialized_message->time_stamp; + rosbag2::introspection_message_set_topic_name( + ros_message.get(), serialized_message->topic_name.c_str()); +} +} // namespace rosbag2_bag_v2_plugins + +#include "pluginlib/class_list_macros.hpp" // NOLINT +PLUGINLIB_EXPORT_CLASS(rosbag2_bag_v2_plugins::RosbagV2Deserializer, + rosbag2::converter_interfaces::SerializationFormatDeserializer) diff --git a/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/converter/rosbag_v2_deserializer.hpp b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/converter/rosbag_v2_deserializer.hpp new file mode 100644 index 0000000000..8f5b41737b --- /dev/null +++ b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/converter/rosbag_v2_deserializer.hpp @@ -0,0 +1,40 @@ +// 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_BAG_V2_PLUGINS__CONVERTER__ROSBAG_V2_DESERIALIZER_HPP_ +#define ROSBAG2_BAG_V2_PLUGINS__CONVERTER__ROSBAG_V2_DESERIALIZER_HPP_ + +#include + +#include "rosbag2/converter_interfaces/serialization_format_deserializer.hpp" +#include "rosbag2/types.hpp" +#include "rosbag2/types/introspection_message.hpp" + +namespace rosbag2_bag_v2_plugins +{ +class RosbagV2Deserializer : public rosbag2::converter_interfaces::SerializationFormatDeserializer +{ +public: + RosbagV2Deserializer() = default; + virtual ~RosbagV2Deserializer() = default; + + void deserialize( + std::shared_ptr serialized_message, + const rosidl_message_type_support_t * type_support, + std::shared_ptr ros_message) override; +}; + +} // namespace rosbag2_bag_v2_plugins + +#endif // ROSBAG2_BAG_V2_PLUGINS__CONVERTER__ROSBAG_V2_DESERIALIZER_HPP_ diff --git a/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/logging.hpp b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/logging.hpp new file mode 100644 index 0000000000..98e20c912a --- /dev/null +++ b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/logging.hpp @@ -0,0 +1,61 @@ +// 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_BAG_V2_PLUGINS__LOGGING_HPP_ +#define ROSBAG2_BAG_V2_PLUGINS__LOGGING_HPP_ + +#include +#include + +#include "rcutils/logging_macros.h" + +#define ROSBAG2_BAG_V2_PLUGINS_PACKAGE_NAME "rosbag2_bag_v2_plugins" + +#define ROSBAG2_BAG_V2_PLUGINS_LOG_INFO(...) \ + RCUTILS_LOG_INFO_NAMED(ROSBAG2_BAG_V2_PLUGINS_PACKAGE_NAME, __VA_ARGS__) + +#define ROSBAG2_BAG_V2_PLUGINS_LOG_INFO_STREAM(args) do { \ + std::stringstream __ss; \ + __ss << args; \ + RCUTILS_LOG_INFO_NAMED(ROSBAG2_BAG_V2_PLUGINS_PACKAGE_NAME, __ss.str().c_str()); \ +} while (0) + +#define ROSBAG2_BAG_V2_PLUGINS_LOG_ERROR(...) \ + RCUTILS_LOG_ERROR_NAMED(ROSBAG2_BAG_V2_PLUGINS_PACKAGE_NAME, __VA_ARGS__) + +#define ROSBAG2_BAG_V2_PLUGINS_LOG_ERROR_STREAM(args) do { \ + std::stringstream __ss; \ + __ss << args; \ + RCUTILS_LOG_ERROR_NAMED(ROSBAG2_BAG_V2_PLUGINS_PACKAGE_NAME, __ss.str().c_str()); \ +} while (0) + +#define ROSBAG2_BAG_V2_PLUGINS_LOG_WARN(...) \ + RCUTILS_LOG_WARN_NAMED(ROSBAG2_BAG_V2_PLUGINS_PACKAGE_NAME, __VA_ARGS__) + +#define ROSBAG2_BAG_V2_PLUGINS_LOG_WARN_STREAM(args) do { \ + std::stringstream __ss; \ + __ss << args; \ + RCUTILS_LOG_WARN_NAMED(ROSBAG2_BAG_V2_PLUGINS_PACKAGE_NAME, __ss.str().c_str()); \ +} while (0) + +#define ROSBAG2_BAG_V2_PLUGINS_LOG_DEBUG(...) \ + RCUTILS_LOG_DEBUG_NAMED(ROSBAG2_BAG_V2_PLUGINS_PACKAGE_NAME, __VA_ARGS__) + +#define ROSBAG2_BAG_V2_PLUGINS_LOG_DEBUG_STREAM(args) do { \ + std::stringstream __ss; \ + __ss << args; \ + RCUTILS_LOG_DEBUG_NAMED(ROSBAG2_BAG_V2_PLUGINS_PACKAGE_NAME, __ss.str().c_str()); \ +} while (0) + +#endif // ROSBAG2_BAG_V2_PLUGINS__LOGGING_HPP_ diff --git a/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_output_stream.cpp b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_output_stream.cpp new file mode 100644 index 0000000000..dcee0e05f0 --- /dev/null +++ b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_output_stream.cpp @@ -0,0 +1,47 @@ +// 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 "rosbag_output_stream.hpp" + +#include +#include +#include + +#include "rosbag2_storage/ros_helper.hpp" + +namespace rosbag2_bag_v2_plugins +{ + +RosbagOutputStream::RosbagOutputStream(const std::string & type) +{ + char_array_ = rosbag2_storage::make_serialized_message(type.c_str(), type.length() + 1); +} + +uint8_t * RosbagOutputStream::advance(size_t size) +{ + auto old_capacity = char_array_->buffer_capacity; + auto ret = rcutils_uint8_array_resize(char_array_.get(), size + old_capacity); + if (ret != RCUTILS_RET_OK) { + throw std::runtime_error("No memory available. Error code " + std::to_string(ret)); + } + char_array_->buffer_length = char_array_->buffer_capacity; + return char_array_->buffer + old_capacity; +} + +std::shared_ptr RosbagOutputStream::get_content() +{ + return char_array_; +} + +} // namespace rosbag2_bag_v2_plugins diff --git a/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_output_stream.hpp b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_output_stream.hpp new file mode 100644 index 0000000000..00a11495d6 --- /dev/null +++ b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_output_stream.hpp @@ -0,0 +1,42 @@ +// 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_BAG_V2_PLUGINS__STORAGE__ROSBAG_OUTPUT_STREAM_HPP_ +#define ROSBAG2_BAG_V2_PLUGINS__STORAGE__ROSBAG_OUTPUT_STREAM_HPP_ + +#include +#include +#include + +#include "rcutils/types/uint8_array.h" + +namespace rosbag2_bag_v2_plugins +{ + +class RosbagOutputStream +{ +public: + explicit RosbagOutputStream(const std::string & type); + + uint8_t * advance(size_t size); + + std::shared_ptr get_content(); + +private: + std::shared_ptr char_array_; +}; + +} // namespace rosbag2_bag_v2_plugins + +#endif // ROSBAG2_BAG_V2_PLUGINS__STORAGE__ROSBAG_OUTPUT_STREAM_HPP_ diff --git a/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_v2_storage.cpp b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_v2_storage.cpp new file mode 100644 index 0000000000..3fcb0f4493 --- /dev/null +++ b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_v2_storage.cpp @@ -0,0 +1,169 @@ +// 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 "rosbag_v2_storage.hpp" + +#include +#include +#include + +#include "rosbag/message_instance.h" + +#include "rosbag2_storage/filesystem_helper.hpp" +#include "rosbag2_storage/ros_helper.hpp" +#include "rosbag_output_stream.hpp" +#include "../logging.hpp" +#include "../convert_rosbag_message.hpp" + +namespace rosbag2_bag_v2_plugins +{ + +RosbagV2Storage::RosbagV2Storage() +: ros_v2_bag_(std::make_unique()), bag_view_of_replayable_messages_(nullptr) {} + +RosbagV2Storage::~RosbagV2Storage() +{ + ros_v2_bag_->close(); +} + +void RosbagV2Storage::open( + const std::string & uri, rosbag2_storage::storage_interfaces::IOFlag flag) +{ + if (flag == rosbag2_storage::storage_interfaces::IOFlag::READ_WRITE) { + throw std::runtime_error("The rosbag_v2 storage plugin can only be used to read"); + } + + ros_v2_bag_->open(uri); + auto bag_view = std::make_unique(*ros_v2_bag_); + + std::vector topics_valid_in_ros2; + auto connection_info = bag_view->getConnections(); + for (const auto & connection : connection_info) { + std::string ros2_type_name; + if (get_1to2_mapping(connection->datatype, ros2_type_name)) { + if (!vector_has_already_element(topics_valid_in_ros2, connection->topic)) { + topics_valid_in_ros2.push_back(connection->topic); + } + } else { + ROSBAG2_BAG_V2_PLUGINS_LOG_INFO_STREAM("ROS 1 to ROS 2 type mapping is not available for " + "topic '" << connection->topic << "' which is of type '" << connection->datatype << + "'. Skipping messages of this topic when replaying."); + } + } + + bag_view_of_replayable_messages_ = std::make_unique( + *ros_v2_bag_, rosbag::TopicQuery(topics_valid_in_ros2)); + bag_iterator_ = bag_view_of_replayable_messages_->begin(); +} + +bool RosbagV2Storage::has_next() +{ + return bag_iterator_ != bag_view_of_replayable_messages_->end(); +} + +std::shared_ptr RosbagV2Storage::read_next() +{ + auto serialized_message = std::make_shared(); + auto message_instance = *bag_iterator_; + serialized_message->topic_name = message_instance.getTopic(); + serialized_message->time_stamp = message_instance.getTime().toNSec(); + + auto output_stream = RosbagOutputStream(message_instance.getDataType()); + message_instance.write(output_stream); + serialized_message->serialized_data = output_stream.get_content(); + + bag_iterator_++; + return serialized_message; +} + +std::vector RosbagV2Storage::get_all_topics_and_types() +{ + auto topics_with_type_including_ros1 = get_all_topics_and_types_including_ros1_topics(); + + std::vector topics_with_type; + for (const auto & topic_with_type : topics_with_type_including_ros1) { + std::string ros2_type_name; + if (get_1to2_mapping(topic_with_type.type, ros2_type_name)) { + topics_with_type.push_back(topic_with_type); + } + } + + return topics_with_type; +} + +rosbag2_storage::BagMetadata RosbagV2Storage::get_metadata() +{ + auto bag_view = std::make_unique(*ros_v2_bag_); + auto full_file_path = ros_v2_bag_->getFileName(); + rosbag2_storage::BagMetadata metadata; + metadata.storage_identifier = "rosbag_v2"; + metadata.bag_size = rosbag2_storage::FilesystemHelper::get_file_size(full_file_path); + metadata.relative_file_paths = { + rosbag2_storage::FilesystemHelper::get_file_name(full_file_path) + }; + metadata.duration = std::chrono::nanoseconds( + bag_view->getEndTime().toNSec() - bag_view->getBeginTime().toNSec()); + metadata.starting_time = std::chrono::time_point( + std::chrono::nanoseconds(bag_view->getBeginTime().toNSec())); + metadata.message_count = bag_view->size(); + metadata.topics_with_message_count = get_topic_information(); + + return metadata; +} + +std::vector RosbagV2Storage::get_topic_information() +{ + std::vector topic_information; + auto topics_with_type = get_all_topics_and_types_including_ros1_topics(); + + for (const auto & topic : topics_with_type) { + rosbag2_storage::TopicInformation topic_info; + rosbag::View view_with_topic_query(*ros_v2_bag_, rosbag::TopicQuery({topic.name})); + topic_info.topic_metadata = topic; + topic_info.message_count = view_with_topic_query.size(); + + topic_information.push_back(topic_info); + } + + return topic_information; +} + +std::vector +RosbagV2Storage::get_all_topics_and_types_including_ros1_topics() +{ + auto bag_view = std::make_unique(*ros_v2_bag_); + std::vector topics_with_type; + auto connection_info = bag_view->getConnections(); + + for (const auto & connection : connection_info) { + rosbag2_storage::TopicMetadata topic_metadata; + topic_metadata.name = connection->topic; + topic_metadata.type = connection->datatype; + topic_metadata.serialization_format = "rosbag_v2"; + + if (!vector_has_already_element( + topics_with_type, topic_metadata)) + { + topics_with_type.push_back(topic_metadata); + } + } + + return topics_with_type; +} + +} // namespace rosbag2_bag_v2_plugins + +#include "pluginlib/class_list_macros.hpp" // NOLINT +PLUGINLIB_EXPORT_CLASS( + rosbag2_bag_v2_plugins::RosbagV2Storage, rosbag2_storage::storage_interfaces::ReadOnlyInterface) diff --git a/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_v2_storage.hpp b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_v2_storage.hpp new file mode 100644 index 0000000000..253dd51579 --- /dev/null +++ b/rosbag2_bag_v2_plugins/src/rosbag2_bag_v2_plugins/storage/rosbag_v2_storage.hpp @@ -0,0 +1,62 @@ +// 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_BAG_V2_PLUGINS__STORAGE__ROSBAG_V2_STORAGE_HPP_ +#define ROSBAG2_BAG_V2_PLUGINS__STORAGE__ROSBAG_V2_STORAGE_HPP_ + +#include +#include +#include + +#include "rosbag2_storage/storage_interfaces/read_only_interface.hpp" +#include "rosbag/bag.h" +#include "rosbag/view.h" + +namespace rosbag2_bag_v2_plugins +{ + +class RosbagV2Storage : public rosbag2_storage::storage_interfaces::ReadOnlyInterface +{ +public: + RosbagV2Storage(); + + ~RosbagV2Storage() override; + + void open(const std::string & uri, rosbag2_storage::storage_interfaces::IOFlag flag) override; + + bool has_next() override; + + std::shared_ptr read_next() override; + + std::vector get_all_topics_and_types() override; + + rosbag2_storage::BagMetadata get_metadata() override; + +private: + template + bool vector_has_already_element(std::vector vector, const T & element) + { + return std::find(vector.begin(), vector.end(), element) != vector.end(); + } + std::vector get_all_topics_and_types_including_ros1_topics(); + std::vector get_topic_information(); + + std::unique_ptr ros_v2_bag_; + std::unique_ptr bag_view_of_replayable_messages_; + rosbag::View::iterator bag_iterator_; +}; + +} // namespace rosbag2_bag_v2_plugins + +#endif // ROSBAG2_BAG_V2_PLUGINS__STORAGE__ROSBAG_V2_STORAGE_HPP_ diff --git a/rosbag2_bag_v2_plugins/storage_plugin_description.xml b/rosbag2_bag_v2_plugins/storage_plugin_description.xml new file mode 100644 index 0000000000..6ed8da52b1 --- /dev/null +++ b/rosbag2_bag_v2_plugins/storage_plugin_description.xml @@ -0,0 +1,13 @@ + + + + This is a storage plugin which allows to read rosbag v2 bagfiles. + Use together with rosbag_v2_converter as the messages will still be in ROS 1 format + This plugin needs to be build from source if custom messages are to be supported. + + + \ No newline at end of file diff --git a/rosbag2_bag_v2_plugins/test/rosbag2_bag_v2_plugins/rosbag_v2_storage_test_fixture.hpp b/rosbag2_bag_v2_plugins/test/rosbag2_bag_v2_plugins/rosbag_v2_storage_test_fixture.hpp new file mode 100644 index 0000000000..4068cdb6ff --- /dev/null +++ b/rosbag2_bag_v2_plugins/test/rosbag2_bag_v2_plugins/rosbag_v2_storage_test_fixture.hpp @@ -0,0 +1,46 @@ +// 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_BAG_V2_PLUGINS__ROSBAG_V2_STORAGE_TEST_FIXTURE_HPP_ +#define ROSBAG2_BAG_V2_PLUGINS__ROSBAG_V2_STORAGE_TEST_FIXTURE_HPP_ + +#include +#include + +#include "rosbag2_test_common/temporary_directory_fixture.hpp" +#include "rosbag2_storage/serialized_bag_message.hpp" +#include "rosbag2_storage/filesystem_helper.hpp" +#include "../../src/rosbag2_bag_v2_plugins/storage/rosbag_v2_storage.hpp" +#include "rosbag/bag.h" +#include "rosbag/view.h" + +#include "std_msgs/String.h" + +class RosbagV2StorageTestFixture : public testing::Test +{ +public: + RosbagV2StorageTestFixture() + { + database_path_ = _SRC_RESOURCES_DIR_PATH; // variable defined in CMakeLists.txt + bag_path_ = rosbag2_storage::FilesystemHelper::concat({database_path_, "test_bag.bag"}); + storage_ = std::make_shared(); + storage_->open(bag_path_, rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY); + } + + std::shared_ptr storage_; + std::string database_path_; + std::string bag_path_; +}; + +#endif // ROSBAG2_BAG_V2_PLUGINS__ROSBAG_V2_STORAGE_TEST_FIXTURE_HPP_ diff --git a/rosbag2_bag_v2_plugins/test/rosbag2_bag_v2_plugins/test_rosbag_output_stream.cpp b/rosbag2_bag_v2_plugins/test/rosbag2_bag_v2_plugins/test_rosbag_output_stream.cpp new file mode 100644 index 0000000000..60332cb96b --- /dev/null +++ b/rosbag2_bag_v2_plugins/test/rosbag2_bag_v2_plugins/test_rosbag_output_stream.cpp @@ -0,0 +1,70 @@ +// 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 + +#include +#include + +#include "../../src/rosbag2_bag_v2_plugins/storage/rosbag_output_stream.hpp" + +using namespace ::testing; // NOLINT +using RosbagOutputStream = rosbag2_bag_v2_plugins::RosbagOutputStream; + +TEST(RosbagOutputStream, constructor_correctly_initializes_ros_message_type) +{ + auto rosbag_output_stream = RosbagOutputStream("std_msgs/String"); + + auto data_type = std::string( + reinterpret_cast(rosbag_output_stream.get_content()->buffer)); + EXPECT_THAT(data_type, StrEq("std_msgs/String")); +} + +TEST(RosbagOutputStream, advance_correctly_make_space_for_message) +{ + std::string expected_data_type = "std_msgs/String"; + auto rosbag_output_stream = RosbagOutputStream(expected_data_type); + + auto data_pointer = rosbag_output_stream.advance(10); + + auto serialized_message = rosbag_output_stream.get_content(); + auto data_type = std::string(reinterpret_cast(serialized_message->buffer)); + EXPECT_THAT(data_type, StrEq(expected_data_type)); + EXPECT_THAT(serialized_message->buffer_capacity, Eq(10 + expected_data_type.length() + 1)); + EXPECT_THAT(serialized_message->buffer_length, Eq(10 + expected_data_type.length() + 1)); + EXPECT_THAT(data_pointer, Eq(serialized_message->buffer + expected_data_type.length() + 1)); +} + +TEST(RosbagOutputStream, adding_data_to_message_works_correctly) +{ + std::string added_data = "some_added_data"; + std::string expected_data_type = "std_msgs/String"; + auto rosbag_output_stream = RosbagOutputStream(expected_data_type); + + memcpy( + rosbag_output_stream.advance(added_data.length() + 1), + added_data.c_str(), + added_data.size() + 1); + + auto serialized_message = rosbag_output_stream.get_content(); + auto data_type = std::string(reinterpret_cast(serialized_message->buffer)); + EXPECT_THAT(data_type, StrEq(expected_data_type)); + EXPECT_THAT( + serialized_message->buffer_capacity, Eq(added_data.length() + expected_data_type.length() + 2)); + EXPECT_THAT( + serialized_message->buffer_length, Eq(added_data.length() + expected_data_type.length() + 2)); + auto additional_data_pointer = reinterpret_cast( + serialized_message->buffer + expected_data_type.length() + 1); + EXPECT_THAT(std::string(additional_data_pointer), StrEq(added_data)); +} diff --git a/rosbag2_bag_v2_plugins/test/rosbag2_bag_v2_plugins/test_rosbag_v2_storage.cpp b/rosbag2_bag_v2_plugins/test/rosbag2_bag_v2_plugins/test_rosbag_v2_storage.cpp new file mode 100644 index 0000000000..61b78eeadd --- /dev/null +++ b/rosbag2_bag_v2_plugins/test/rosbag2_bag_v2_plugins/test_rosbag_v2_storage.cpp @@ -0,0 +1,144 @@ +// 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 + +#include +#include +#include +#include + +#include "rosbag2_storage/filesystem_helper.hpp" +#include "rosbag2_storage/topic_metadata.hpp" +#include "rosbag_v2_storage_test_fixture.hpp" + +using namespace ::testing; // NOLINT +using namespace std::chrono_literals; // NOLINT + +namespace rosbag2_storage +{ + +bool operator!=(const TopicMetadata & lhs, const TopicMetadata & rhs) +{ + return !(lhs == rhs); +} + +bool operator==(const TopicInformation & lhs, const TopicInformation & rhs) +{ + return lhs.topic_metadata == rhs.topic_metadata && + lhs.message_count == rhs.message_count; +} + +bool operator!=(const TopicInformation & lhs, const TopicInformation & rhs) +{ + return !(lhs == rhs); +} + +} // namespace rosbag2_storage + +TEST_F(RosbagV2StorageTestFixture, get_all_topics_and_types_returns_list_of_recorded_bag_file) { + std::vector expected_topic_metadata = { + {"/test_topic", "std_msgs/String", "rosbag_v2"}, + {"/test_topic2", "std_msgs/String", "rosbag_v2"}, + }; + + auto topic_metadata = storage_->get_all_topics_and_types(); + + for (size_t i = 0; i < expected_topic_metadata.size(); ++i) { + EXPECT_THAT(topic_metadata[i], expected_topic_metadata[i]); + } +} + +TEST_F(RosbagV2StorageTestFixture, get_metadata_returns_bagfile_description) +{ + std::vector expected_topics_with_message_count = { + {{"/rosout", "rosgraph_msgs/Log", "rosbag_v2"}, 3}, + {{"/test_topic", "std_msgs/String", "rosbag_v2"}, 1}, + {{"/test_topic2", "std_msgs/String", "rosbag_v2"}, 1} + }; + + auto bag_metadata = storage_->get_metadata(); + + EXPECT_THAT(bag_metadata.version, Eq(1)); + EXPECT_THAT(bag_metadata.storage_identifier, StrEq("rosbag_v2")); + EXPECT_THAT(bag_metadata.bag_size, Eq(9023u)); + EXPECT_THAT(bag_metadata.relative_file_paths, ElementsAre("test_bag.bag")); + EXPECT_THAT(bag_metadata.starting_time, + Eq(std::chrono::time_point(1543509813298505673ns))); + EXPECT_THAT(bag_metadata.duration, Eq(268533408ns)); + EXPECT_THAT(bag_metadata.message_count, Eq(5u)); + EXPECT_THAT( + bag_metadata.topics_with_message_count, SizeIs(expected_topics_with_message_count.size())); + for (size_t i = 0; i < expected_topics_with_message_count.size(); ++i) { + EXPECT_THAT( + bag_metadata.topics_with_message_count[i], Eq(expected_topics_with_message_count[i])); + } +} + +TEST_F(RosbagV2StorageTestFixture, has_next_only_counts_messages_with_ros2_counterpart) +{ + // There are only two messages that can be read + EXPECT_TRUE(storage_->has_next()); + storage_->read_next(); + EXPECT_TRUE(storage_->has_next()); + storage_->read_next(); + EXPECT_FALSE(storage_->has_next()); + EXPECT_FALSE(storage_->has_next()); // Once false, it stays false +} + +TEST_F(RosbagV2StorageTestFixture, read_next_will_not_read_messages_without_ros2_equivalent) +{ + EXPECT_TRUE(storage_->has_next()); + auto first_message = storage_->read_next(); + + EXPECT_TRUE(storage_->has_next()); + auto second_message = storage_->read_next(); + + EXPECT_THAT(first_message->topic_name, StrEq("/test_topic")); + EXPECT_THAT(second_message->topic_name, StrEq("/test_topic2")); +} + +TEST_F(RosbagV2StorageTestFixture, read_next_will_produce_messages_ordered_by_timestamp) +{ + EXPECT_TRUE(storage_->has_next()); + auto first_message = storage_->read_next(); + + + EXPECT_TRUE(storage_->has_next()); + auto second_message = storage_->read_next(); + + EXPECT_THAT(second_message->time_stamp, Ge(first_message->time_stamp)); +} + +TEST_F(RosbagV2StorageTestFixture, get_topics_and_types_will_only_return_one_entry_per_topic) +{ + bag_path_ = rosbag2_storage::FilesystemHelper::concat( + {database_path_, "test_bag_multiple_connections.bag"}); + storage_ = std::make_shared(); + storage_->open(bag_path_, rosbag2_storage::storage_interfaces::IOFlag::READ_ONLY); + + std::vector expected_topic_metadata = { + {"/test_topic", "std_msgs/String", "rosbag_v2"}, + {"/int_test_topic", "std_msgs/Int32", "rosbag_v2"}, + }; + + auto topic_metadata = storage_->get_all_topics_and_types(); + + EXPECT_THAT(topic_metadata, SizeIs(expected_topic_metadata.size())); + + for (size_t i = 0; i < expected_topic_metadata.size(); ++i) { + EXPECT_THAT(topic_metadata[i], expected_topic_metadata[i]); + } +} diff --git a/rosbag2_storage/include/rosbag2_storage/filesystem_helper.hpp b/rosbag2_storage/include/rosbag2_storage/filesystem_helper.hpp index 3ab7182702..a4151e1ac4 100644 --- a/rosbag2_storage/include/rosbag2_storage/filesystem_helper.hpp +++ b/rosbag2_storage/include/rosbag2_storage/filesystem_helper.hpp @@ -76,6 +76,23 @@ class FilesystemHelper } } + /** + * Returns the name of the file identified by a file system path + * \param path The file path + * \return The name of the file or an empty string, if the path ends with a separator + */ + static std::string get_file_name(const std::string & path) + { + auto last_separator = path.rfind(separator); + if (last_separator == path.size() - 1) { + return ""; + } else { + return path.substr( + last_separator == std::string::npos ? 0 : last_separator + 1, path.length()); + } + } + + /** * Calculates the size of a directory by summarizing the file size of all files * Note: This operation is not recursive diff --git a/rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp b/rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp index 044bb284c9..155b562a1e 100644 --- a/rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp +++ b/rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp @@ -25,6 +25,11 @@ struct TopicMetadata std::string name; std::string type; std::string serialization_format; + + bool operator==(const rosbag2_storage::TopicMetadata & rhs) const + { + return name == rhs.name && type == rhs.type && serialization_format == rhs.serialization_format; + } }; } // namespace rosbag2_storage diff --git a/rosbag2_storage/test/rosbag2_storage/test_filesystem_helper.cpp b/rosbag2_storage/test/rosbag2_storage/test_filesystem_helper.cpp index 01034c7ff3..225350f2a2 100644 --- a/rosbag2_storage/test/rosbag2_storage/test_filesystem_helper.cpp +++ b/rosbag2_storage/test/rosbag2_storage/test_filesystem_helper.cpp @@ -87,3 +87,22 @@ TEST(FilesystemHelper, get_folder_name_for_path_not_ending_with_separator) EXPECT_THAT(folder_name, Eq("folder")); } + +TEST(FilesystemHelper, get_file_name_returns_last_part_of_path) +{ + auto path = FilesystemHelper::concat({"some", "path", "to", "a", "file.txt"}); + + auto folder_name = FilesystemHelper::get_file_name(path); + + EXPECT_THAT(folder_name, Eq("file.txt")); +} + +TEST(FilesystemHelper, get_file_name_returns_empty_string_if_passed_a_path_with_trailing_separator) +{ + auto sep = std::string(FilesystemHelper::separator); + auto path = FilesystemHelper::concat({"some", "path", "to", "a", "folder"}) + sep; + + auto folder_name = FilesystemHelper::get_file_name(path); + + EXPECT_THAT(folder_name, Eq("")); +} diff --git a/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp b/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp index c5c210776d..6583f9c138 100644 --- a/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp +++ b/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp @@ -252,6 +252,7 @@ rosbag2_storage::BagMetadata SqliteStorage::get_metadata() metadata.starting_time = std::chrono::time_point(std::chrono::nanoseconds(min_time)); metadata.duration = std::chrono::nanoseconds(max_time) - std::chrono::nanoseconds(min_time); + metadata.bag_size = rosbag2_storage::FilesystemHelper::calculate_directory_size(database_name_); return metadata; } diff --git a/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/test_sqlite_storage.cpp b/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/test_sqlite_storage.cpp index df8d2feb75..5068078a9c 100644 --- a/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/test_sqlite_storage.cpp +++ b/rosbag2_storage_default_plugins/test/rosbag2_storage_default_plugins/sqlite/test_sqlite_storage.cpp @@ -30,11 +30,6 @@ using namespace ::testing; // NOLINT namespace rosbag2_storage { -bool operator==(const TopicMetadata & lhs, const TopicMetadata & rhs) -{ - return lhs.name == rhs.name && lhs.type == rhs.type; -} - bool operator!=(const TopicMetadata & lhs, const TopicMetadata & rhs) { return !(lhs == rhs); diff --git a/rosbag2_tests/CMakeLists.txt b/rosbag2_tests/CMakeLists.txt index a0c6a88a7f..ad1724b068 100644 --- a/rosbag2_tests/CMakeLists.txt +++ b/rosbag2_tests/CMakeLists.txt @@ -20,14 +20,34 @@ endif() find_package(ament_cmake REQUIRED) find_package(ament_index_cpp REQUIRED) +find_package(PkgConfig) +if(PKG_CONFIG_FOUND) + find_package(ros1_bridge REQUIRED) + include(${ros1_bridge_DIR}/find_ros1_interface_packages.cmake) + include(${ros1_bridge_DIR}/find_ros1_package.cmake) + find_ros1_package(roscpp) + if(NOT ros1_roscpp_FOUND) + set(SKIP_ROS1_TESTS "SKIP_TEST") + message(WARNING "Skipping build of tests for rosbag_v2 plugin. ROS 1 not found") + endif() +else() + set(SKIP_ROS1_TESTS "SKIP_TEST") + message(WARNING "Skipping build of tests for rosbag_v2 plugin. ROS 1 not found") +endif() + if(BUILD_TESTING) + include(cmake/skip_ros1_tests_if_necessary.cmake) + skip_ros1_tests_if_necessary() + find_package(ament_cmake_gmock REQUIRED) find_package(ament_lint_auto REQUIRED) find_package(rclcpp REQUIRED) + find_package(std_msgs REQUIRED) find_package(test_msgs REQUIRED) find_package(rosbag2_storage REQUIRED) find_package(rosbag2_storage_default_plugins REQUIRED) find_package(rosbag2_test_common REQUIRED) + find_package(rosbag2_bag_v2_plugins QUIET) ament_lint_auto_find_test_dependencies() @@ -72,6 +92,30 @@ if(BUILD_TESTING) rosbag2_test_common test_msgs) endif() + + ament_add_gmock(test_rosbag2_play_rosbag_v2_end_to_end + test/rosbag2_tests/test_rosbag2_play_rosbag_v2_end_to_end.cpp + WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR} + ${SKIP_ROS1_TESTS}) + if(TARGET test_rosbag2_play_rosbag_v2_end_to_end) + ament_target_dependencies(test_rosbag2_play_rosbag_v2_end_to_end + rosbag2_storage + rclcpp + rosbag2_test_common + std_msgs) + endif() + + ament_add_gmock(test_rosbag2_info_rosbag_v2_end_to_end + test/rosbag2_tests/test_rosbag2_info_rosbag_v2_end_to_end.cpp + WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR} + ${SKIP_ROS1_TESTS}) + if(TARGET test_rosbag2_info_rosbag_v2_end_to_end) + ament_target_dependencies(test_rosbag2_info_rosbag_v2_end_to_end + rosbag2_storage + rclcpp + rosbag2_test_common + std_msgs) + endif() endif() ament_package() diff --git a/rosbag2_tests/cmake/skip_ros1_tests_if_necessary.cmake b/rosbag2_tests/cmake/skip_ros1_tests_if_necessary.cmake new file mode 100644 index 0000000000..aaec62fe9b --- /dev/null +++ b/rosbag2_tests/cmake/skip_ros1_tests_if_necessary.cmake @@ -0,0 +1,37 @@ +# 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. + +# Macro to set variable SKIP_ROS1_TESTS if ros1 is not installed +# Some end to end tests rely on the plugin to read rosbags from ROS 1. +# Those tests should be marked with SKIP_ROS1_TESTS and will be skipped if the +# plugin is not available + +macro(skip_ros1_tests_if_necessary) + find_package(PkgConfig) + if(PKG_CONFIG_FOUND) + find_package(ros1_bridge REQUIRED) + include(${ros1_bridge_DIR}/find_ros1_interface_packages.cmake) + include(${ros1_bridge_DIR}/find_ros1_package.cmake) + find_ros1_package(roscpp) + if(NOT ros1_roscpp_FOUND) + set(SKIP_ROS1_TESTS "SKIP_TEST") + message(WARNING + "Skipping build of tests for rosbag_v2 plugin. ROS 1 not found") + endif() + else() + set(SKIP_ROS1_TESTS "SKIP_TEST") + message(WARNING + "Skipping build of tests for rosbag_v2 plugin. ROS 1 not found") + endif() +endmacro() \ No newline at end of file diff --git a/rosbag2_tests/package.xml b/rosbag2_tests/package.xml index 1afb7e90d8..3305335ae0 100644 --- a/rosbag2_tests/package.xml +++ b/rosbag2_tests/package.xml @@ -16,11 +16,13 @@ ament_lint_common rosbag2_storage_default_plugins rosbag2_converter_default_plugins + rosbag2_bag_v2_plugins rosbag2_test_common rosbag2_storage rosbag2 ros2bag rclcpp + std_msgs test_msgs diff --git a/rosbag2_tests/resources/test_bag.bag b/rosbag2_tests/resources/test_bag.bag new file mode 100644 index 0000000000000000000000000000000000000000..91c05cd2e39d71879fb19d625db7a2c0f514aa26 GIT binary patch literal 8522 zcmeHN&2Jk;6i+_`t0KM;MG=hTmL@@I<2WC7#2!+$DM6(vP6`K#tl6Dedtg0lc4m_r z2_dc=I3PH1rvCsZgb?bVzyWdPhPc6nGw^%+;drSfQURh!yYgy2-<$V-@4cDlv1{$^ zor@b+*lSDY7oE#fQ&W%N^?QkayW>ZRw(b$MAEv%Y>%8k2nvdaCTF6_SL1f&|ox&hW z^j+=;foLrHV%1v}vauM{mlj)%re9z4S6Yq0`w-Ln5P)}ON60{FWl5G=&8gMcj@*;6 zvO^Z45;Cl9EZ5dx%<+a+vP+jQ-nin{SxrbU>1NZik*#Z++wKx$wXW1M=Hd9*>l^KB z?lQ*qd90N#(Oqu0x7%)$)npt;@i^7y#_q;dx4z110k=H7;6pOyk2q%%Zz>szRKAxa z7cyqOw8&&iwQ!7$X-&=hlGU;z3YhIlrXwMX;lAl&G)IONy@3jeC@qMh825=;5J&yd z#63mMD~d`TbG!V+X4hmZFfIffN5kGPBdCPgBilgTWQ!r zPHxt*#yk*#a_5co0ggnZ2*YO6z7CpZj$sjqAP14(W3!O_`q1{^A7tx29xLv_v%nY* z9fIpQB04uW##yJVHP=zWKI3?>#$nhJmy9pzw9tdi;BsANk}d$m`hz&yQvwor!&Eju zR8m{`r5E#f=nz$=s#Dt}j4=sRsYOw8Vj}u3~9wU?XzoQQk38Zp=`(*m&(pRU~7tnFnL;I?Q z1Kl-%ju-HbSkq-}z6np$4Q#fxX0g{v8v%O9HrQ5c$(K!DUu~}W(r@}rPc)ki>8~|> zzFZge=P-T32Al6f1f25(twUOmqG~7Iqe?oD33j0K@6dTqUz?c*2f8y3qG%SyNSmW* z6xz@gbEXa4I#WfUYfKfvS6Yj$z>|%&CYL;DuE>?;HQB`R;nzKH?O9Bpph~uZrJ6iW zYm_wEqTQ{e$e2uJMLzg)dxnIa$6KO6yU?Ocar^Z3nR_;OiSZtdk^OeU^fZ?V(s9~erbVDg(Dp&Xpr5czrMVPda->>VG@NE`PMHdF#tKp zN?#zx3Uw`r3;Di9y|g5`)WMPzm3ah~mOO+0B6@!%xv&iR+{^hgWW7^=W=)QFc-9n8 z-{cyQXTG1aCKF!->$Bii0xFlYN-6WSvq~wel(I@G|0+}c-=>uJZQeIKzA=v_8`J+` z3MU{F<-^$@7w8`ePtyGbp7Me8D0-w8oirsc&dB^=IZ5duzOTecKgTn6oJFIf_-WMX Pp(Bw_QaV2g0xJIinW@D6 literal 0 HcmV?d00001 diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_rosbag_v2_end_to_end.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_rosbag_v2_end_to_end.cpp new file mode 100644 index 0000000000..7427fe6385 --- /dev/null +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_rosbag_v2_end_to_end.cpp @@ -0,0 +1,72 @@ +// 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 + +#include +#include +#include + +#include "process_execution_helpers.hpp" + +using namespace ::testing; // NOLINT + +class InfoV2EndToEndTestFixture : public Test +{ +public: + InfoV2EndToEndTestFixture() + { + database_path_ = _SRC_RESOURCES_DIR_PATH; // variable defined in CMakeLists.txt + } + + std::string database_path_; +}; + +TEST_F(InfoV2EndToEndTestFixture, info_end_to_end_test) { + internal::CaptureStdout(); + auto exit_code = execute_and_wait_until_completion( + "ros2 bag info test_bag.bag -s rosbag_v2", database_path_); + std::string output = internal::GetCapturedStdout(); + + EXPECT_THAT(exit_code, Eq(EXIT_SUCCESS)); +// The bag size depends on the os and is not asserted, the time is asserted time zone independent + EXPECT_THAT(output, ContainsRegex( + "\nFiles: test_bag\\.bag" + "\nBag size: .*B" + "\nStorage id: rosbag_v2" + "\nDuration: 3\\.0s" + "\nStart: Dec .+ 2018 .+:.+:06\\.974 \\(1544000766\\.974\\)" + "\nEnd Dec .+ 2018 .+:.+:09\\.975 \\(1544000769\\.975\\)" + "\nMessages: 11" + "\nTopic information: ")); + + EXPECT_THAT(output, HasSubstr( + "Topic: rosout | Type: rosgraph_msgs/Log | Count: 5 | Serialization Format: rosbag_v2\n")); + EXPECT_THAT(output, HasSubstr("Topic: string_topic | Type: std_msgs/String | Count: 3 | " + "Serialization Format: rosbag_v2\n")); + EXPECT_THAT(output, HasSubstr( + "Topic: int_topic | Type: std_msgs/Int32 | Count: 3 | Serialization Format: rosbag_v2" + )); +} + + +TEST_F(InfoV2EndToEndTestFixture, info_fails_gracefully_if_storage_format_is_not_specified) { + internal::CaptureStderr(); + auto exit_code = + execute_and_wait_until_completion("ros2 bag info test_bag.bag", database_path_); + auto error_output = internal::GetCapturedStderr(); + + EXPECT_THAT(exit_code, Eq(EXIT_SUCCESS)); + EXPECT_THAT(error_output, HasSubstr("Could not read metadata for test_bag.bag")); +} diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_play_rosbag_v2_end_to_end.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_play_rosbag_v2_end_to_end.cpp new file mode 100644 index 0000000000..cf9861ad34 --- /dev/null +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_play_rosbag_v2_end_to_end.cpp @@ -0,0 +1,92 @@ +// 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 + +#include +#include +#include +#include +#include +#include +#include + +// rclcpp must be included before process_execution_helpers.hpp +#include "rclcpp/rclcpp.hpp" +#include "process_execution_helpers.hpp" + +#include "std_msgs/msg/string.hpp" +#include "std_msgs/msg/int32.hpp" +#include "std_msgs/msg/int32_multi_array.hpp" +#include "rosbag2_test_common/subscription_manager.hpp" + +using namespace ::testing; // NOLINT +using namespace rosbag2_test_common; // NOLINT + +class PlayEndToEndTestFixture : public Test +{ +public: + PlayEndToEndTestFixture() + { + database_path_ = _SRC_RESOURCES_DIR_PATH; // variable defined in CMakeLists.txt + sub_ = std::make_unique(); + } + + static void SetUpTestCase() + { + rclcpp::init(0, nullptr); + } + + static void TearDownTestCase() + { + rclcpp::shutdown(); + } + + std::string database_path_; + std::unique_ptr sub_; +}; + +TEST_F(PlayEndToEndTestFixture, play_end_to_end_test_does_not_try_to_publish_ros1_topics) { + sub_->add_subscription("/string_topic", 2); + sub_->add_subscription("/int_topic", 2); + + auto subscription_future = sub_->spin_subscriptions(); + + auto exit_code = execute_and_wait_until_completion( + "ros2 bag play test_bag.bag -s rosbag_v2", database_path_); + + subscription_future.get(); + + auto string_messages = sub_->get_received_messages("/string_topic"); + auto int_messages = sub_->get_received_messages("/int_topic"); + + EXPECT_THAT(string_messages, SizeIs(Ge(2u))); + EXPECT_THAT(string_messages[0]->data, StrEq("foo")); + + EXPECT_THAT(int_messages, SizeIs(2)); + EXPECT_THAT(int_messages[0]->data, Eq(42)); + + EXPECT_THAT(exit_code, Eq(EXIT_SUCCESS)); +} + + +TEST_F(PlayEndToEndTestFixture, play_fails_gracefully_if_rosbag_v2_storage_id_is_not_specified) { + internal::CaptureStderr(); + auto exit_code = + execute_and_wait_until_completion("ros2 bag play test_bag.bag", database_path_); + auto error_output = internal::GetCapturedStderr(); + + EXPECT_THAT(exit_code, Eq(EXIT_SUCCESS)); + EXPECT_THAT(error_output, HasSubstr("No storage could be initialized")); +} diff --git a/rosbag2_transport/include/rosbag2_transport/rosbag2_transport.hpp b/rosbag2_transport/include/rosbag2_transport/rosbag2_transport.hpp index 9f1c07b4f6..09bde70cc9 100644 --- a/rosbag2_transport/include/rosbag2_transport/rosbag2_transport.hpp +++ b/rosbag2_transport/include/rosbag2_transport/rosbag2_transport.hpp @@ -82,7 +82,7 @@ class Rosbag2Transport * \param uri path to the metadata yaml file. */ ROSBAG2_TRANSPORT_PUBLIC - void print_bag_info(const std::string & uri); + void print_bag_info(const std::string & uri, const std::string & storage_id); private: std::shared_ptr setup_node(); diff --git a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport.cpp b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport.cpp index be85ebba12..115fd3b0b5 100644 --- a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport.cpp +++ b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport.cpp @@ -99,16 +99,16 @@ void Rosbag2Transport::play( } } -void Rosbag2Transport::print_bag_info(const std::string & uri) +void Rosbag2Transport::print_bag_info(const std::string & uri, const std::string & storage_id) { rosbag2::BagMetadata metadata; try { - metadata = info_->read_metadata(uri); + metadata = info_->read_metadata(uri, storage_id); } catch (std::runtime_error & e) { (void) e; ROSBAG2_TRANSPORT_LOG_ERROR_STREAM("Could not read metadata for " << uri << ". Please specify " - "the path to the folder containing an existing 'metadata.yaml' file and make sure that the " - "file 'metadata.yaml' exists and has the correct format."); + "the path to the folder containing an existing 'metadata.yaml' file or provide correct " + "storage id if metadata file doesn't exist (see help)."); return; } diff --git a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp index 3642b2c607..8e9185277f 100644 --- a/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp +++ b/rosbag2_transport/src/rosbag2_transport/rosbag2_transport_python.cpp @@ -122,17 +122,21 @@ rosbag2_transport_play(PyObject * Py_UNUSED(self), PyObject * args, PyObject * k static PyObject * rosbag2_transport_info(PyObject * Py_UNUSED(self), PyObject * args, PyObject * kwargs) { - static const char * kwlist[] = {"uri", nullptr}; + static const char * kwlist[] = {"uri", "storage_id", nullptr}; char * char_uri; - if (!PyArg_ParseTupleAndKeywords(args, kwargs, "s", const_cast(kwlist), &char_uri)) { + char * char_storage_id; + if (!PyArg_ParseTupleAndKeywords( + args, kwargs, "ss", const_cast(kwlist), &char_uri, &char_storage_id)) + { return nullptr; } std::string uri = std::string(char_uri); + std::string storage_id = std::string(char_storage_id); rosbag2_transport::Rosbag2Transport transport; - transport.print_bag_info(uri); + transport.print_bag_info(uri, storage_id); Py_RETURN_NONE; } diff --git a/rosbag2_transport/test/rosbag2_transport/test_info.cpp b/rosbag2_transport/test/rosbag2_transport/test_info.cpp index 884adf67a0..d7feb0e479 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_info.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_info.cpp @@ -43,7 +43,7 @@ TEST_F(Rosbag2TransportTestFixture, info_pretty_prints_information_from_bagfile) // the expected output uses a regex to handle different time zones. rosbag2_transport::Rosbag2Transport transport(reader_, writer_, info_); - transport.print_bag_info("test"); + transport.print_bag_info("test", "sqlite3"); std::string output = internal::GetCapturedStdout(); EXPECT_THAT(output, ContainsRegex(