From fc3b55bd9ee8b7c9b75edcda9a17d9b3ca9e0940 Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Tue, 19 Mar 2024 11:38:07 -0700 Subject: [PATCH 1/6] Add transactional state mutex for RecorderImpl class. (#1547) * add transactional state mutex for RecorderImpl class. Signed-off-by: Tomoya.Fujita * address uncrustify warning. Signed-off-by: Tomoya.Fujita * address review comments and suggested fixes. Signed-off-by: Tomoya Fujita * address review comment and clang-tidy warning. Signed-off-by: Tomoya Fujita * Add Recorder::start_discovery() API and protect discovery with mutex - Also use non-recursive mutex for the `state_transition_mutex_` Signed-off-by: Michael Orlov * Fix deadlocks in pause(), resume() and toggle_paused() methods - Removed mutex lock in pause(), resume() and toggle_paused() methods and use only atomic value change for `paused_` variable. - Renamed `state_transition_mutex_` to the `start_stop_transition_mutex_`. - Add unit test for `toggle_paused()` Signed-off-by: Michael Orlov * Fix for warning about breaking strict-aliasing rules - Changed type of the paused_ to the std::atomic_uchar Signed-off-by: Michael Orlov --------- Signed-off-by: Tomoya.Fujita Signed-off-by: Tomoya Fujita Signed-off-by: Michael Orlov Co-authored-by: Michael Orlov --- .../include/rosbag2_transport/recorder.hpp | 3 + .../src/rosbag2_transport/recorder.cpp | 100 +++++++++++++----- .../test/rosbag2_transport/test_record.cpp | 21 ++++ 3 files changed, 95 insertions(+), 29 deletions(-) diff --git a/rosbag2_transport/include/rosbag2_transport/recorder.hpp b/rosbag2_transport/include/rosbag2_transport/recorder.hpp index a81037bb99..6755fd5ff6 100644 --- a/rosbag2_transport/include/rosbag2_transport/recorder.hpp +++ b/rosbag2_transport/include/rosbag2_transport/recorder.hpp @@ -169,6 +169,9 @@ class Recorder : public rclcpp::Node ROSBAG2_TRANSPORT_PUBLIC rosbag2_transport::RecordOptions & get_record_options(); + ROSBAG2_TRANSPORT_PUBLIC + void start_discovery(); + ROSBAG2_TRANSPORT_PUBLIC void stop_discovery(); diff --git a/rosbag2_transport/src/rosbag2_transport/recorder.cpp b/rosbag2_transport/src/rosbag2_transport/recorder.cpp index 8d93e5a752..89d6128738 100644 --- a/rosbag2_transport/src/rosbag2_transport/recorder.cpp +++ b/rosbag2_transport/src/rosbag2_transport/recorder.cpp @@ -79,6 +79,12 @@ class RecorderImpl /// Return the current paused state. bool is_paused(); + /// Start discovery + void start_discovery(); + + /// Stop discovery + void stop_discovery(); + std::unordered_map get_requested_or_available_topics(); /// Public members for access by wrapper @@ -86,7 +92,6 @@ class RecorderImpl std::shared_ptr writer_; rosbag2_storage::StorageOptions storage_options_; rosbag2_transport::RecordOptions record_options_; - std::atomic stop_discovery_ = false; std::unordered_map> subscriptions_; private: @@ -135,7 +140,10 @@ class RecorderImpl rclcpp::Service::SharedPtr srv_snapshot_; rclcpp::Service::SharedPtr srv_split_bagfile_; - std::atomic paused_ = false; + std::mutex start_stop_transition_mutex_; + std::mutex discovery_mutex_; + std::atomic stop_discovery_ = false; + std::atomic_uchar paused_ = 0; std::atomic in_recording_ = false; std::shared_ptr keyboard_handler_; KeyboardHandler::callback_handle_t toggle_paused_key_callback_handle_ = @@ -160,7 +168,6 @@ RecorderImpl::RecorderImpl( : writer_(std::move(writer)), storage_options_(storage_options), record_options_(record_options), - stop_discovery_(record_options_.is_discovery_disabled), node(owner), paused_(record_options.start_paused), keyboard_handler_(std::move(keyboard_handler)) @@ -211,24 +218,19 @@ RecorderImpl::RecorderImpl( RecorderImpl::~RecorderImpl() { keyboard_handler_->delete_key_press_callback(toggle_paused_key_callback_handle_); - if (in_recording_) { - stop(); - } + stop(); } void RecorderImpl::stop() { - stop_discovery_ = true; - if (discovery_future_.valid()) { - auto status = discovery_future_.wait_for(2 * record_options_.topic_polling_interval); - if (status != std::future_status::ready) { - RCLCPP_ERROR_STREAM( - node->get_logger(), - "discovery_future_.wait_for(" << record_options_.topic_polling_interval.count() << - ") return status: " << (status == std::future_status::timeout ? "timeout" : "deferred")); - } + std::lock_guard state_lock(start_stop_transition_mutex_); + if (!in_recording_) { + RCLCPP_DEBUG(node->get_logger(), "Recording has already been stopped or not running."); + return; } - paused_ = true; + + stop_discovery(); + pause(); subscriptions_.clear(); writer_->close(); // Call writer->close() to finalize current bag file and write metadata @@ -246,6 +248,7 @@ void RecorderImpl::stop() void RecorderImpl::record() { + std::lock_guard state_lock(start_stop_transition_mutex_); if (in_recording_.exchange(true)) { RCLCPP_WARN_STREAM( node->get_logger(), @@ -253,7 +256,6 @@ void RecorderImpl::record() return; } paused_ = record_options_.start_paused; - stop_discovery_ = record_options_.is_discovery_disabled; topic_qos_profile_overrides_ = record_options_.topic_qos_profile_overrides; if (record_options_.rmw_serialization_format.empty()) { throw std::runtime_error("No serialization format specified!"); @@ -340,8 +342,7 @@ void RecorderImpl::record() subscribe_topics(get_requested_or_available_topics()); } if (!record_options_.is_discovery_disabled) { - discovery_future_ = - std::async(std::launch::async, std::bind(&RecorderImpl::topics_discovery, this)); + start_discovery(); } if (record_options_.start_paused) { RCLCPP_INFO( @@ -395,22 +396,28 @@ const rosbag2_cpp::Writer & RecorderImpl::get_writer_handle() void RecorderImpl::pause() { - paused_.store(true); - RCLCPP_INFO_STREAM(node->get_logger(), "Pausing recording."); + if (paused_.exchange(true)) { + RCLCPP_DEBUG(node->get_logger(), "Recorder is already in pause state."); + } else { + RCLCPP_INFO_STREAM(node->get_logger(), "Pausing recording."); + } } void RecorderImpl::resume() { - paused_.store(false); - RCLCPP_INFO_STREAM(node->get_logger(), "Resuming recording."); + if (paused_.exchange(false)) { + RCLCPP_DEBUG(node->get_logger(), "Already in the recording."); + } else { + RCLCPP_INFO_STREAM(node->get_logger(), "Resuming recording."); + } } void RecorderImpl::toggle_paused() { - if (paused_.load()) { - this->resume(); + if (atomic_fetch_xor(&paused_, 1)) { + RCLCPP_INFO_STREAM(node->get_logger(), "Resuming recording."); } else { - this->pause(); + RCLCPP_INFO_STREAM(node->get_logger(), "Pausing recording."); } } @@ -419,6 +426,37 @@ bool RecorderImpl::is_paused() return paused_.load(); } +void RecorderImpl::start_discovery() +{ + std::lock_guard state_lock(discovery_mutex_); + if (stop_discovery_.exchange(false)) { + RCLCPP_DEBUG(node->get_logger(), "Recorder topic discovery is already running."); + } else { + discovery_future_ = + std::async(std::launch::async, std::bind(&RecorderImpl::topics_discovery, this)); + } +} + +void RecorderImpl::stop_discovery() +{ + std::lock_guard state_lock(discovery_mutex_); + if (stop_discovery_.exchange(true)) { + RCLCPP_DEBUG( + node->get_logger(), "Recorder topic discovery has already been stopped or not running."); + } else { + if (discovery_future_.valid()) { + auto status = discovery_future_.wait_for(2 * record_options_.topic_polling_interval); + if (status != std::future_status::ready) { + RCLCPP_ERROR_STREAM( + node->get_logger(), + "discovery_future_.wait_for(" << record_options_.topic_polling_interval.count() << + ") return status: " << + (status == std::future_status::timeout ? "timeout" : "deferred")); + } + } + } +} + void RecorderImpl::topics_discovery() { // If using sim time - wait until /clock topic received before even creating subscriptions @@ -798,10 +836,14 @@ Recorder::get_record_options() return pimpl_->record_options_; } -void -Recorder::stop_discovery() +void Recorder::start_discovery() +{ + pimpl_->start_discovery(); +} + +void Recorder::stop_discovery() { - pimpl_->stop_discovery_ = true; + pimpl_->stop_discovery(); } } // namespace rosbag2_transport diff --git a/rosbag2_transport/test/rosbag2_transport/test_record.cpp b/rosbag2_transport/test/rosbag2_transport/test_record.cpp index 415a21cc04..520ebb17a8 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_record.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_record.cpp @@ -422,3 +422,24 @@ TEST_F(RecordIntegrationTestFixture, write_split_callback_is_called) EXPECT_EQ(closed_file, "BagFile0"); EXPECT_EQ(opened_file, "BagFile1"); } + +TEST_F(RecordIntegrationTestFixture, toggle_paused_do_pause_resume) +{ + rosbag2_transport::RecordOptions record_options{}; + auto recorder = std::make_shared( + std::move(writer_), storage_options_, record_options); + recorder->pause(); + ASSERT_TRUE(recorder->is_paused()); + + testing::internal::CaptureStderr(); + recorder->toggle_paused(); + std::string test_output = testing::internal::GetCapturedStderr(); + EXPECT_FALSE(recorder->is_paused()); + EXPECT_TRUE(test_output.find("Resuming recording.") != std::string::npos); + + testing::internal::CaptureStderr(); + recorder->toggle_paused(); + test_output = testing::internal::GetCapturedStderr(); + EXPECT_TRUE(recorder->is_paused()); + EXPECT_TRUE(test_output.find("Pausing recording.") != std::string::npos); +} From 0c5374e4a99aa1c1693b322aa9ea070a09be09b2 Mon Sep 17 00:00:00 2001 From: Roman Date: Tue, 19 Mar 2024 21:40:13 +0300 Subject: [PATCH 2/6] Add Python stubs for rosbag2_py (#1459) (#1569) * Add Python stubs for rosbag2_py Signed-off-by: Roman Sokolkov * Add note to DEVELOPING.md Signed-off-by: Roman Sokolkov * Add note to py.typed Signed-off-by: Roman Sokolkov --------- Signed-off-by: Roman Sokolkov --- .github/workflows/test.yml | 11 + DEVELOPING.md | 1 + rosbag2_py/README.md | 20 ++ rosbag2_py/rosbag2_py/__init__.pyi | 7 + .../rosbag2_py/_compression_options.pyi | 35 +++ rosbag2_py/rosbag2_py/_info.pyi | 6 + rosbag2_py/rosbag2_py/_reader.pyi | 31 +++ rosbag2_py/rosbag2_py/_reindexer.pyi | 5 + rosbag2_py/rosbag2_py/_storage.pyi | 212 ++++++++++++++++++ rosbag2_py/rosbag2_py/_transport.pyi | 64 ++++++ rosbag2_py/rosbag2_py/_writer.pyi | 25 +++ rosbag2_py/rosbag2_py/py.typed | 1 + 12 files changed, 418 insertions(+) create mode 100644 rosbag2_py/README.md create mode 100644 rosbag2_py/rosbag2_py/__init__.pyi create mode 100644 rosbag2_py/rosbag2_py/_compression_options.pyi create mode 100644 rosbag2_py/rosbag2_py/_info.pyi create mode 100644 rosbag2_py/rosbag2_py/_reader.pyi create mode 100644 rosbag2_py/rosbag2_py/_reindexer.pyi create mode 100644 rosbag2_py/rosbag2_py/_storage.pyi create mode 100644 rosbag2_py/rosbag2_py/_transport.pyi create mode 100644 rosbag2_py/rosbag2_py/_writer.pyi create mode 100644 rosbag2_py/rosbag2_py/py.typed diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index ae9ed4ed9b..fdee05c09c 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -88,6 +88,17 @@ jobs: source /opt/ros/rolling/setup.sh && colcon test --mixin linters-skip --packages-select ${rosbag2_packages} --packages-skip rosbag2_performance_benchmarking --event-handlers console_cohesion+ --return-code-on-test-failure --ctest-args "-L xfail" --pytest-args "-m xfail" working-directory: ${{ steps.action-ros-ci.outputs.ros-workspace-directory-name }} shell: bash + - name: Is regeneration of Python stubs required? + run: | + rosbag2_path=$(colcon list -p --packages-select rosbag2)/.. + sudo pip uninstall -y mypy + sudo apt update && sudo apt -y install mypy=0.942-1ubuntu1 + source install/setup.sh + stubgen -p rosbag2_py -o ${rosbag2_path}/rosbag2_py + cd ${rosbag2_path} + git diff --exit-code + working-directory: ${{ steps.action-ros-ci.outputs.ros-workspace-directory-name }} + shell: bash - uses: actions/upload-artifact@v1 with: name: colcon-logs diff --git a/DEVELOPING.md b/DEVELOPING.md index 83cb81f287..0d00a7fcb9 100644 --- a/DEVELOPING.md +++ b/DEVELOPING.md @@ -11,6 +11,7 @@ colcon build --packages-up-to rosbag2 Note: building Rosbag2 from source, overlaid on a debian installation of `ros-$ROS_DISTRO-rosbag2` has undefined behavior (but should work in most cases, just beware the build may find headers from the binaries instead of the local workspace.) +Note: make sure to [regenerate stub files](rosbag2_py/README.md), when making changes to pybind11-related files in `rosbag2_py`. ## Executing tests diff --git a/rosbag2_py/README.md b/rosbag2_py/README.md new file mode 100644 index 0000000000..9c016db74b --- /dev/null +++ b/rosbag2_py/README.md @@ -0,0 +1,20 @@ +# rosbag2_py + +## Regenerating Python stub files (.pyi) + +Python stub files allow to supply type-hinting information for binary Python modules (e.g. pybind-based). + +In rosbag2_py stub files are generated with utility called `stubgen`. + +To regenerate stub files +``` +cd +colcon build --packages-up-to rosbag2_py +source install/setup.sh +# Make sure rosbag2_py can be imported +python3 -c 'import rosbag2_py' + +sudo apt update && sudo apt install mypy=0.942-1ubuntu1 +cd +stubgen -p rosbag2_py -o rosbag2_py +``` diff --git a/rosbag2_py/rosbag2_py/__init__.pyi b/rosbag2_py/rosbag2_py/__init__.pyi new file mode 100644 index 0000000000..d0baa15c7a --- /dev/null +++ b/rosbag2_py/rosbag2_py/__init__.pyi @@ -0,0 +1,7 @@ +from rosbag2_py._compression_options import CompressionMode as CompressionMode, CompressionOptions as CompressionOptions, compression_mode_from_string as compression_mode_from_string, compression_mode_to_string as compression_mode_to_string +from rosbag2_py._info import Info as Info +from rosbag2_py._reader import SequentialCompressionReader as SequentialCompressionReader, SequentialReader as SequentialReader, get_registered_readers as get_registered_readers +from rosbag2_py._reindexer import Reindexer as Reindexer +from rosbag2_py._storage import BagMetadata as BagMetadata, ConverterOptions as ConverterOptions, FileInformation as FileInformation, MessageDefinition as MessageDefinition, MetadataIo as MetadataIo, ReadOrder as ReadOrder, ReadOrderSortBy as ReadOrderSortBy, StorageFilter as StorageFilter, StorageOptions as StorageOptions, TopicInformation as TopicInformation, TopicMetadata as TopicMetadata, get_default_storage_id as get_default_storage_id +from rosbag2_py._transport import PlayOptions as PlayOptions, Player as Player, RecordOptions as RecordOptions, Recorder as Recorder, bag_rewrite as bag_rewrite +from rosbag2_py._writer import SequentialCompressionWriter as SequentialCompressionWriter, SequentialWriter as SequentialWriter, get_registered_compressors as get_registered_compressors, get_registered_serializers as get_registered_serializers, get_registered_writers as get_registered_writers diff --git a/rosbag2_py/rosbag2_py/_compression_options.pyi b/rosbag2_py/rosbag2_py/_compression_options.pyi new file mode 100644 index 0000000000..b595168701 --- /dev/null +++ b/rosbag2_py/rosbag2_py/_compression_options.pyi @@ -0,0 +1,35 @@ +from typing import ClassVar + +FILE: CompressionMode +MESSAGE: CompressionMode +NONE: CompressionMode + +class CompressionMode: + __doc__: ClassVar[str] = ... # read-only + __members__: ClassVar[dict] = ... # read-only + FILE: ClassVar[CompressionMode] = ... + MESSAGE: ClassVar[CompressionMode] = ... + NONE: ClassVar[CompressionMode] = ... + __entries: ClassVar[dict] = ... + def __init__(self, value: int) -> None: ... + def __eq__(self, other: object) -> bool: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + def __int__(self) -> int: ... + def __ne__(self, other: object) -> bool: ... + def __setstate__(self, state: int) -> None: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class CompressionOptions: + compression_format: str + compression_mode: CompressionMode + compression_queue_size: int + compression_threads: int + def __init__(self, compression_format: str = ..., compression_mode: CompressionMode = ..., compression_queue_size: int = ..., compression_threads: int = ...) -> None: ... + +def compression_mode_from_string(arg0: str) -> CompressionMode: ... +def compression_mode_to_string(arg0: CompressionMode) -> str: ... diff --git a/rosbag2_py/rosbag2_py/_info.pyi b/rosbag2_py/rosbag2_py/_info.pyi new file mode 100644 index 0000000000..cee3f18c1c --- /dev/null +++ b/rosbag2_py/rosbag2_py/_info.pyi @@ -0,0 +1,6 @@ +import rosbag2_py._storage + +class Info: + def __init__(self) -> None: ... + def read_metadata(self, arg0: str, arg1: str) -> rosbag2_py._storage.BagMetadata: ... + def read_metadata_and_output_service_verbose(self, arg0: str, arg1: str) -> None: ... diff --git a/rosbag2_py/rosbag2_py/_reader.pyi b/rosbag2_py/rosbag2_py/_reader.pyi new file mode 100644 index 0000000000..3b79b1bf20 --- /dev/null +++ b/rosbag2_py/rosbag2_py/_reader.pyi @@ -0,0 +1,31 @@ +from typing import Any + +class SequentialCompressionReader: + def __init__(self) -> None: ... + def get_all_message_definitions(self, *args, **kwargs) -> Any: ... + def get_all_topics_and_types(self, *args, **kwargs) -> Any: ... + def get_metadata(self, *args, **kwargs) -> Any: ... + def has_next(self) -> bool: ... + def open(self, arg0, arg1) -> None: ... + def open_uri(self, arg0: str) -> None: ... + def read_next(self) -> tuple: ... + def reset_filter(self) -> None: ... + def seek(self, arg0: int) -> None: ... + def set_filter(self, arg0) -> None: ... + def set_read_order(self, arg0) -> bool: ... + +class SequentialReader: + def __init__(self) -> None: ... + def get_all_message_definitions(self, *args, **kwargs) -> Any: ... + def get_all_topics_and_types(self, *args, **kwargs) -> Any: ... + def get_metadata(self, *args, **kwargs) -> Any: ... + def has_next(self) -> bool: ... + def open(self, arg0, arg1) -> None: ... + def open_uri(self, arg0: str) -> None: ... + def read_next(self) -> tuple: ... + def reset_filter(self) -> None: ... + def seek(self, arg0: int) -> None: ... + def set_filter(self, arg0) -> None: ... + def set_read_order(self, arg0) -> bool: ... + +def get_registered_readers() -> Set[str]: ... diff --git a/rosbag2_py/rosbag2_py/_reindexer.pyi b/rosbag2_py/rosbag2_py/_reindexer.pyi new file mode 100644 index 0000000000..a91bef88e9 --- /dev/null +++ b/rosbag2_py/rosbag2_py/_reindexer.pyi @@ -0,0 +1,5 @@ +import rosbag2_py._storage + +class Reindexer: + def __init__(self) -> None: ... + def reindex(self, arg0: rosbag2_py._storage.StorageOptions) -> None: ... diff --git a/rosbag2_py/rosbag2_py/_storage.pyi b/rosbag2_py/rosbag2_py/_storage.pyi new file mode 100644 index 0000000000..fd1b5cb18b --- /dev/null +++ b/rosbag2_py/rosbag2_py/_storage.pyi @@ -0,0 +1,212 @@ +from typing import ClassVar, Dict, List + +import datetime + +class BagMetadata: + bag_size: int + compression_format: str + compression_mode: str + custom_data: Dict[str,str] + duration: object + files: List[FileInformation] + message_count: int + relative_file_paths: List[str] + ros_distro: str + starting_time: object + storage_identifier: str + topics_with_message_count: List[TopicInformation] + version: int + def __init__(self, version: int = ..., bag_size: int = ..., storage_identifier: str = ..., relative_file_paths: List[str] = ..., files: List[FileInformation] = ..., duration: object = ..., starting_time: object = ..., message_count: int = ..., topics_with_message_count: List[TopicInformation] = ..., compression_format: str = ..., compression_mode: str = ..., custom_data: Dict[str,str] = ..., ros_distro: str = ...) -> None: ... + +class ConverterOptions: + input_serialization_format: str + output_serialization_format: str + def __init__(self, input_serialization_format: str = ..., output_serialization_format: str = ...) -> None: ... + +class Duration: + def __init__(self, seconds: int, nanoseconds: int) -> None: ... + +class FileInformation: + duration: datetime.timedelta + message_count: int + path: str + starting_time: object + def __init__(self, path: str, starting_time: object, duration: object, message_count: int) -> None: ... + +class MessageDefinition: + encoded_message_definition: str + encoding: str + topic_type: str + type_hash: str + def __init__(self, topic_type: str, encoding: str, encoded_message_definition: str, type_hash: str) -> None: ... + +class MetadataIo: + def __init__(self) -> None: ... + def deserialize_metadata(self, arg0: str) -> BagMetadata: ... + def metadata_file_exists(self, arg0: str) -> bool: ... + def read_metadata(self, arg0: str) -> BagMetadata: ... + def serialize_metadata(self, arg0: BagMetadata) -> str: ... + def write_metadata(self, arg0: str, arg1: BagMetadata) -> None: ... + +class QoS: + def __init__(self, history_depth: int) -> None: ... + def avoid_ros_namespace_conventions(self, arg0: bool) -> QoS: ... + def best_effort(self) -> QoS: ... + def deadline(self, arg0: Duration) -> QoS: ... + def durability(self, arg0: rmw_qos_durability_policy_t) -> QoS: ... + def durability_volatile(self) -> QoS: ... + def history(self, arg0: rmw_qos_history_policy_t) -> QoS: ... + def keep_all(self) -> QoS: ... + def keep_last(self, arg0: int) -> QoS: ... + def lifespan(self, arg0: Duration) -> QoS: ... + def liveliness(self, arg0: rmw_qos_liveliness_policy_t) -> QoS: ... + def liveliness_lease_duration(self, arg0: Duration) -> QoS: ... + def reliability(self, arg0: rmw_qos_reliability_policy_t) -> QoS: ... + def reliable(self) -> QoS: ... + def transient_local(self) -> QoS: ... + +class ReadOrder: + reverse: bool + sort_by: ReadOrderSortBy + def __init__(self, sort_by: ReadOrderSortBy = ..., reverse: bool = ...) -> None: ... + +class ReadOrderSortBy: + __doc__: ClassVar[str] = ... # read-only + __members__: ClassVar[dict] = ... # read-only + File: ClassVar[ReadOrderSortBy] = ... + PublishedTimestamp: ClassVar[ReadOrderSortBy] = ... + ReceivedTimestamp: ClassVar[ReadOrderSortBy] = ... + __entries: ClassVar[dict] = ... + def __init__(self, value: int) -> None: ... + def __eq__(self, other: object) -> bool: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + def __int__(self) -> int: ... + def __ne__(self, other: object) -> bool: ... + def __setstate__(self, state: int) -> None: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class StorageFilter: + topics: List[str] + topics_regex: str + topics_regex_to_exclude: str + def __init__(self, topics: List[str] = ..., topics_regex: str = ..., topics_regex_to_exclude: str = ...) -> None: ... + +class StorageOptions: + custom_data: Dict[str,str] + end_time_ns: int + max_bagfile_duration: int + max_bagfile_size: int + max_cache_size: int + snapshot_mode: bool + start_time_ns: int + storage_config_uri: str + storage_id: str + storage_preset_profile: str + uri: str + def __init__(self, uri: str, storage_id: str = ..., max_bagfile_size: int = ..., max_bagfile_duration: int = ..., max_cache_size: int = ..., storage_preset_profile: str = ..., storage_config_uri: str = ..., snapshot_mode: bool = ..., start_time_ns: int = ..., end_time_ns: int = ..., custom_data: Dict[str,str] = ...) -> None: ... + +class TopicInformation: + message_count: int + topic_metadata: TopicMetadata + def __init__(self, topic_metadata: TopicMetadata, message_count: int) -> None: ... + +class TopicMetadata: + id: int + name: str + offered_qos_profiles: List[QoS] + serialization_format: str + type: str + type_description_hash: str + def __init__(self, id: int, name: str, type: str, serialization_format: str, offered_qos_profiles: List[QoS] = ..., type_description_hash: str = ...) -> None: ... + def equals(self, arg0: TopicMetadata) -> bool: ... + +class rmw_qos_durability_policy_t: + __doc__: ClassVar[str] = ... # read-only + __members__: ClassVar[dict] = ... # read-only + RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT: ClassVar[rmw_qos_durability_policy_t] = ... + RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL: ClassVar[rmw_qos_durability_policy_t] = ... + RMW_QOS_POLICY_DURABILITY_UNKNOWN: ClassVar[rmw_qos_durability_policy_t] = ... + RMW_QOS_POLICY_DURABILITY_VOLATILE: ClassVar[rmw_qos_durability_policy_t] = ... + __entries: ClassVar[dict] = ... + def __init__(self, value: int) -> None: ... + def __eq__(self, other: object) -> bool: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + def __int__(self) -> int: ... + def __ne__(self, other: object) -> bool: ... + def __setstate__(self, state: int) -> None: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class rmw_qos_history_policy_t: + __doc__: ClassVar[str] = ... # read-only + __members__: ClassVar[dict] = ... # read-only + RMW_QOS_POLICY_HISTORY_KEEP_ALL: ClassVar[rmw_qos_history_policy_t] = ... + RMW_QOS_POLICY_HISTORY_KEEP_LAST: ClassVar[rmw_qos_history_policy_t] = ... + RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT: ClassVar[rmw_qos_history_policy_t] = ... + RMW_QOS_POLICY_HISTORY_UNKNOWN: ClassVar[rmw_qos_history_policy_t] = ... + __entries: ClassVar[dict] = ... + def __init__(self, value: int) -> None: ... + def __eq__(self, other: object) -> bool: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + def __int__(self) -> int: ... + def __ne__(self, other: object) -> bool: ... + def __setstate__(self, state: int) -> None: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class rmw_qos_liveliness_policy_t: + __doc__: ClassVar[str] = ... # read-only + __members__: ClassVar[dict] = ... # read-only + RMW_QOS_POLICY_LIVELINESS_AUTOMATIC: ClassVar[rmw_qos_liveliness_policy_t] = ... + RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC: ClassVar[rmw_qos_liveliness_policy_t] = ... + RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT: ClassVar[rmw_qos_liveliness_policy_t] = ... + RMW_QOS_POLICY_LIVELINESS_UNKNOWN: ClassVar[rmw_qos_liveliness_policy_t] = ... + __entries: ClassVar[dict] = ... + def __init__(self, value: int) -> None: ... + def __eq__(self, other: object) -> bool: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + def __int__(self) -> int: ... + def __ne__(self, other: object) -> bool: ... + def __setstate__(self, state: int) -> None: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +class rmw_qos_reliability_policy_t: + __doc__: ClassVar[str] = ... # read-only + __members__: ClassVar[dict] = ... # read-only + RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT: ClassVar[rmw_qos_reliability_policy_t] = ... + RMW_QOS_POLICY_RELIABILITY_RELIABLE: ClassVar[rmw_qos_reliability_policy_t] = ... + RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT: ClassVar[rmw_qos_reliability_policy_t] = ... + RMW_QOS_POLICY_RELIABILITY_UNKNOWN: ClassVar[rmw_qos_reliability_policy_t] = ... + __entries: ClassVar[dict] = ... + def __init__(self, value: int) -> None: ... + def __eq__(self, other: object) -> bool: ... + def __getstate__(self) -> int: ... + def __hash__(self) -> int: ... + def __index__(self) -> int: ... + def __int__(self) -> int: ... + def __ne__(self, other: object) -> bool: ... + def __setstate__(self, state: int) -> None: ... + @property + def name(self) -> str: ... + @property + def value(self) -> int: ... + +def get_default_storage_id() -> str: ... diff --git a/rosbag2_py/rosbag2_py/_transport.pyi b/rosbag2_py/rosbag2_py/_transport.pyi new file mode 100644 index 0000000000..2e7ca0c8bf --- /dev/null +++ b/rosbag2_py/rosbag2_py/_transport.pyi @@ -0,0 +1,64 @@ +from typing import Any, List + +import datetime +import rosbag2_py._storage + +class PlayOptions: + clock_publish_frequency: float + clock_publish_on_topic_publish: bool + clock_topics: List[str] + delay: float + disable_keyboard_controls: bool + disable_loan_message: bool + loop: bool + node_prefix: str + playback_duration: float + playback_until_timestamp: int + rate: float + read_ahead_queue_size: int + start_offset: float + start_paused: bool + topic_qos_profile_overrides: dict + topic_remapping_options: List[str] + topics_regex_to_exclude: str + topics_regex_to_filter: str + topics_to_filter: List[str] + wait_acked_timeout: int + def __init__(self) -> None: ... + +class Player: + def __init__(self) -> None: ... + def burst(self, arg0: rosbag2_py._storage.StorageOptions, arg1: PlayOptions, arg2: int) -> None: ... + def play(self, storage_options: rosbag2_py._storage.StorageOptions, play_options: PlayOptions) -> None: ... + +class RecordOptions: + all_services: bool + all_topics: bool + compression_format: str + compression_mode: str + compression_queue_size: int + compression_threads: int + exclude_regex: str + exclude_service_events: List[str] + exclude_topics: List[str] + ignore_leaf_topics: bool + include_hidden_topics: bool + include_unpublished_topics: bool + is_discovery_disabled: bool + node_prefix: str + regex: str + rmw_serialization_format: str + services: List[str] + start_paused: bool + topic_polling_interval: datetime.timedelta + topic_qos_profile_overrides: dict + topics: List[str] + use_sim_time: bool + def __init__(self) -> None: ... + +class Recorder: + def __init__(self) -> None: ... + def cancel(self, *args, **kwargs) -> Any: ... + def record(self, storage_options: rosbag2_py._storage.StorageOptions, record_options: RecordOptions, node_name: str = ...) -> None: ... + +def bag_rewrite(arg0: List[rosbag2_py._storage.StorageOptions], arg1: str) -> None: ... diff --git a/rosbag2_py/rosbag2_py/_writer.pyi b/rosbag2_py/rosbag2_py/_writer.pyi new file mode 100644 index 0000000000..00d3b2e639 --- /dev/null +++ b/rosbag2_py/rosbag2_py/_writer.pyi @@ -0,0 +1,25 @@ +import rosbag2_py._compression_options +import rosbag2_py._storage + +class SequentialCompressionWriter: + def __init__(self, arg0: rosbag2_py._compression_options.CompressionOptions) -> None: ... + def create_topic(self, arg0: rosbag2_py._storage.TopicMetadata) -> None: ... + def open(self, arg0: rosbag2_py._storage.StorageOptions, arg1: rosbag2_py._storage.ConverterOptions) -> None: ... + def remove_topic(self, arg0: rosbag2_py._storage.TopicMetadata) -> None: ... + def split_bagfile(self) -> None: ... + def take_snapshot(self) -> bool: ... + def write(self, arg0: str, arg1: str, arg2: int) -> None: ... + +class SequentialWriter: + def __init__(self) -> None: ... + def close(self) -> None: ... + def create_topic(self, arg0: rosbag2_py._storage.TopicMetadata) -> None: ... + def open(self, arg0: rosbag2_py._storage.StorageOptions, arg1: rosbag2_py._storage.ConverterOptions) -> None: ... + def remove_topic(self, arg0: rosbag2_py._storage.TopicMetadata) -> None: ... + def split_bagfile(self) -> None: ... + def take_snapshot(self) -> bool: ... + def write(self, arg0: str, arg1: str, arg2: int) -> None: ... + +def get_registered_compressors() -> Set[str]: ... +def get_registered_serializers() -> Set[str]: ... +def get_registered_writers() -> Set[str]: ... diff --git a/rosbag2_py/rosbag2_py/py.typed b/rosbag2_py/rosbag2_py/py.typed new file mode 100644 index 0000000000..3f9083ebdf --- /dev/null +++ b/rosbag2_py/rosbag2_py/py.typed @@ -0,0 +1 @@ +See https://peps.python.org/pep-0561/ for details about py.typed files. From 8001ef1c56ecf91ef8b3f3d1e0643aaa560de9f4 Mon Sep 17 00:00:00 2001 From: Roman Date: Wed, 20 Mar 2024 21:41:59 +0300 Subject: [PATCH 3/6] Update rosbag2_py stubs (#1593) Signed-off-by: Roman Sokolkov --- rosbag2_py/rosbag2_py/_transport.pyi | 1 + 1 file changed, 1 insertion(+) diff --git a/rosbag2_py/rosbag2_py/_transport.pyi b/rosbag2_py/rosbag2_py/_transport.pyi index 2e7ca0c8bf..3ec90a5018 100644 --- a/rosbag2_py/rosbag2_py/_transport.pyi +++ b/rosbag2_py/rosbag2_py/_transport.pyi @@ -52,6 +52,7 @@ class RecordOptions: start_paused: bool topic_polling_interval: datetime.timedelta topic_qos_profile_overrides: dict + topic_types: List[str] topics: List[str] use_sim_time: bool def __init__(self) -> None: ... From 66af3999f145a8910b567a6ab48993c83410754e Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Wed, 20 Mar 2024 17:00:22 -0700 Subject: [PATCH 4/6] Fix for false negative tests in rosbag2_py (#1592) * Fix for false negative tests in rosbag2_py - wait_for(condition: Callable, timout) was incorrectly returning True after the first iteration even if condition was false. Signed-off-by: Michael Orlov * Address review comments in regards bag_path optimization Signed-off-by: Michael Orlov --------- Signed-off-by: Michael Orlov --- rosbag2_py/test/common.py | 2 +- rosbag2_py/test/test_transport.py | 11 +++++------ 2 files changed, 6 insertions(+), 7 deletions(-) diff --git a/rosbag2_py/test/common.py b/rosbag2_py/test/common.py index 2a606c2381..56056b71a0 100644 --- a/rosbag2_py/test/common.py +++ b/rosbag2_py/test/common.py @@ -51,4 +51,4 @@ def wait_for( if clock.now() - start > timeout: return False time.sleep(sleep_time) - return True + return True diff --git a/rosbag2_py/test/test_transport.py b/rosbag2_py/test/test_transport.py index fe01d28b93..e33da3bdfe 100644 --- a/rosbag2_py/test/test_transport.py +++ b/rosbag2_py/test/test_transport.py @@ -13,7 +13,6 @@ # limitations under the License. import datetime -from pathlib import Path import threading from common import get_rosbag_options, wait_for @@ -44,8 +43,8 @@ def test_options_qos_conversion(): @pytest.mark.parametrize('storage_id', TESTED_STORAGE_IDS) def test_record_cancel(tmp_path, storage_id): - bag_path = str(tmp_path / 'test_record_cancel') - storage_options, converter_options = get_rosbag_options(bag_path, storage_id) + bag_path = tmp_path / 'test_record_cancel' + storage_options, converter_options = get_rosbag_options(str(bag_path), storage_id) recorder = rosbag2_py.Recorder() @@ -78,12 +77,12 @@ def test_record_cancel(tmp_path, storage_id): recorder.cancel() metadata_io = rosbag2_py.MetadataIo() - assert wait_for(lambda: metadata_io.metadata_file_exists(bag_path), + assert wait_for(lambda: metadata_io.metadata_file_exists(str(bag_path)), timeout=rclpy.duration.Duration(seconds=3)) record_thread.join() - metadata = metadata_io.read_metadata(bag_path) + metadata = metadata_io.read_metadata(str(bag_path)) assert len(metadata.relative_file_paths) - storage_path = Path(metadata.relative_file_paths[0]) + storage_path = bag_path / metadata.relative_file_paths[0] assert wait_for(lambda: storage_path.is_file(), timeout=rclpy.duration.Duration(seconds=3)) From 30328006f872de4e1c82fef4ecca8ca815b2d4dc Mon Sep 17 00:00:00 2001 From: Adam Aposhian Date: Fri, 22 Mar 2024 13:05:40 -0600 Subject: [PATCH 5/6] add note about MCAP compression (#1588) Signed-off-by: Adam Aposhian --- README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/README.md b/README.md index c8e1058c74..1edfe12403 100644 --- a/README.md +++ b/README.md @@ -91,6 +91,8 @@ Currently, the only `compression-format` available is `zstd`. Both the mode and It is recommended to use this feature with the splitting options. +**Note**: Some storage plugins may have their own compression methods, which are separate from the rosbag2 compression specified by the CLI options `--compression-mode` and `--compression-format`. Notably, the MCAP file format offered by the `rosbag2_storage_mcap` storage plugin supports compression in a way that produces files that are still indexable (whereas using the rosbag2 compression will not). To utilize storage plugin specific compression or other options, see [Recording with a storage configuration](#Recording-with-a-storage-configuration). + #### Recording with a storage configuration Storage configuration can be specified in a YAML file passed through the `--storage-config-file` option. From 415dddab6dde1d1801eca7dd0737f0550aa862c9 Mon Sep 17 00:00:00 2001 From: Roman Date: Tue, 26 Mar 2024 02:26:30 +0300 Subject: [PATCH 6/6] Use std::filesystem instead of rcpputils::fs (#1576) * Remove rcpputils::fs dependency from rosbag2_cpp Signed-off-by: Kenta Yonekura * Remove rcpputils::fs dependency from tests Signed-off-by: Kenta Yonekura * Replace rcpputils::fs with std::filesystem Signed-off-by: Roman Sokolkov * Use .generic_string() in tests Signed-off-by: Roman Sokolkov * Revert remove_all from fixture Signed-off-by: Roman Sokolkov --------- Signed-off-by: Kenta Yonekura Signed-off-by: Roman Sokolkov Co-authored-by: Kenta Yonekura --- .../sequential_compression_reader.cpp | 12 ++-- .../sequential_compression_writer.cpp | 22 ++++--- .../rosbag2_compression/fake_decompressor.cpp | 11 ++-- .../test_sequential_compression_reader.cpp | 24 +++---- .../test_sequential_compression_writer.cpp | 14 ++-- rosbag2_compression_zstd/CMakeLists.txt | 4 +- rosbag2_compression_zstd/package.xml | 1 - .../compression_utils.hpp | 3 +- .../zstd_compressor.cpp | 2 - .../zstd_decompressor.cpp | 9 +-- .../test_zstd_compressor.cpp | 65 +++++++++--------- rosbag2_cpp/include/rosbag2_cpp/reindexer.hpp | 17 +++-- rosbag2_cpp/src/rosbag2_cpp/info.cpp | 10 +-- .../rosbag2_cpp/readers/sequential_reader.cpp | 19 +++--- rosbag2_cpp/src/rosbag2_cpp/reindexer.cpp | 55 ++++++++-------- .../rosbag2_cpp/writers/sequential_writer.cpp | 23 ++++--- rosbag2_cpp/test/rosbag2_cpp/test_info.cpp | 20 +++--- .../rosbag2_cpp/test_multifile_reader.cpp | 22 +++---- .../rosbag2_cpp/test_sequential_reader.cpp | 34 +++++----- .../rosbag2_cpp/test_sequential_writer.cpp | 25 +++---- .../src/rosbag2_storage/metadata_io.cpp | 6 +- .../test/rosbag2_tests/record_fixture.hpp | 44 ++++++------- .../test/rosbag2_tests/test_reindexer.cpp | 13 ++-- .../rosbag2_tests/test_rosbag2_cpp_api.cpp | 10 +-- .../test_rosbag2_cpp_get_service_info.cpp | 10 +-- .../test_rosbag2_info_end_to_end.cpp | 7 +- .../test_rosbag2_play_end_to_end.cpp | 5 +- .../test_rosbag2_record_end_to_end.cpp | 66 ++++++++++--------- .../test_rosbag2_storage_api.cpp | 16 +++-- .../test_composable_player.cpp | 6 +- .../test_composable_recorder.cpp | 20 +++--- .../test_load_composable_components.cpp | 4 +- .../test/rosbag2_transport/test_play_seek.cpp | 7 +- .../test/rosbag2_transport/test_rewrite.cpp | 18 ++--- 34 files changed, 333 insertions(+), 291 deletions(-) diff --git a/rosbag2_compression/src/rosbag2_compression/sequential_compression_reader.cpp b/rosbag2_compression/src/rosbag2_compression/sequential_compression_reader.cpp index 2cf29b0312..70519603db 100644 --- a/rosbag2_compression/src/rosbag2_compression/sequential_compression_reader.cpp +++ b/rosbag2_compression/src/rosbag2_compression/sequential_compression_reader.cpp @@ -14,6 +14,7 @@ #include "rosbag2_compression/sequential_compression_reader.hpp" +#include #include #include #include @@ -21,12 +22,13 @@ #include #include "rcpputils/asserts.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "rosbag2_compression/compression_options.hpp" #include "logging.hpp" +namespace fs = std::filesystem; + namespace rosbag2_compression { SequentialCompressionReader::SequentialCompressionReader( @@ -67,17 +69,17 @@ void SequentialCompressionReader::preprocess_current_file() * Because we have no way to check whether the bag was written correctly, * check for the existence of the prefixed file as a fallback. */ - const rcpputils::fs::path base{base_folder_}; - const rcpputils::fs::path relative{get_current_file()}; + const fs::path base{base_folder_}; + const fs::path relative{get_current_file()}; const auto resolved = base / relative; - if (!resolved.exists()) { + if (!fs::exists(resolved)) { const auto base_stripped = relative.filename(); const auto resolved_stripped = base / base_stripped; ROSBAG2_COMPRESSION_LOG_DEBUG_STREAM( "Unable to find specified bagfile " << resolved.string() << ". Falling back to checking for " << resolved_stripped.string()); rcpputils::require_true( - resolved_stripped.exists(), + fs::exists(resolved_stripped), "Unable to resolve relative file path either as a V3 or V4 relative path"); *current_file_iterator_ = resolved_stripped.string(); } diff --git a/rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp b/rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp index 7d0f7fb1a5..ff9cece328 100644 --- a/rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp +++ b/rosbag2_compression/src/rosbag2_compression/sequential_compression_writer.cpp @@ -17,16 +17,15 @@ #include #include #include +#include #include #include #include #include +#include #include #include "rcpputils/asserts.hpp" -#include "rcpputils/filesystem_helper.hpp" - -#include "rcutils/filesystem.h" #include "rosbag2_cpp/info.hpp" @@ -41,6 +40,8 @@ #include #endif +namespace fs = std::filesystem; + namespace rosbag2_compression { @@ -294,14 +295,14 @@ void SequentialCompressionWriter::compress_file( BaseCompressorInterface & compressor, const std::string & file_relative_to_bag) { - using rcpputils::fs::path; - - const auto file_relative_to_pwd = path(base_folder_) / file_relative_to_bag; + const auto file_relative_to_pwd = fs::path(base_folder_) / file_relative_to_bag; ROSBAG2_COMPRESSION_LOG_INFO_STREAM("Compressing file: " << file_relative_to_pwd.string()); - if (file_relative_to_pwd.exists() && file_relative_to_pwd.file_size() > 0u) { + if (fs::exists(file_relative_to_pwd) && + fs::file_size(file_relative_to_pwd) > 0u) + { const auto compressed_uri = compressor.compress_uri(file_relative_to_pwd.string()); - const auto relative_compressed_uri = path(compressed_uri).filename(); + const auto relative_compressed_uri = fs::path(compressed_uri).filename(); { // After we've compressed the file, replace the name in the file list with the new name. // Must search for the entry because other threads may have changed the order of the vector @@ -320,10 +321,11 @@ void SequentialCompressionWriter::compress_file( } } - if (!rcpputils::fs::remove(file_relative_to_pwd)) { + if (std::error_code ec;!fs::remove(file_relative_to_pwd, ec)) { ROSBAG2_COMPRESSION_LOG_ERROR_STREAM( "Failed to remove original pre-compressed bag file: \"" << - file_relative_to_pwd.string() << "\". This should never happen - but execution " << + file_relative_to_pwd.string() << "\"." << ec.message() << + "This should never happen - but execution " << "will not be halted because the compressed output was successfully created."); } } else { diff --git a/rosbag2_compression/test/rosbag2_compression/fake_decompressor.cpp b/rosbag2_compression/test/rosbag2_compression/fake_decompressor.cpp index aa052db561..ab63e65933 100644 --- a/rosbag2_compression/test/rosbag2_compression/fake_decompressor.cpp +++ b/rosbag2_compression/test/rosbag2_compression/fake_decompressor.cpp @@ -12,19 +12,20 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include "pluginlib/class_list_macros.hpp" -#include "rcpputils/filesystem_helper.hpp" - #include "fake_decompressor.hpp" +namespace fs = std::filesystem; + std::string FakeDecompressor::decompress_uri(const std::string & uri) { - auto uri_path = rcpputils::fs::path{uri}; - const auto decompressed_path = rcpputils::fs::remove_extension(uri_path); - return decompressed_path.string(); + auto uri_path = fs::path{uri}; + const auto decompressed_path = uri_path.replace_extension(); + return decompressed_path.generic_string(); } void FakeDecompressor::decompress_serialized_bag_message( diff --git a/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_reader.cpp b/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_reader.cpp index d3332aff64..76f3e9b6b3 100644 --- a/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_reader.cpp +++ b/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_reader.cpp @@ -14,6 +14,7 @@ #include +#include #include #include #include @@ -21,7 +22,6 @@ #include #include "rcpputils/asserts.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "rosbag2_compression/sequential_compression_reader.hpp" @@ -37,6 +37,8 @@ using namespace testing; // NOLINT +namespace fs = std::filesystem; + static constexpr const char * DefaultTestCompressor = "fake_comp"; class SequentialCompressionReaderTest : public Test @@ -48,10 +50,10 @@ class SequentialCompressionReaderTest : public Test converter_factory_{std::make_shared>()}, metadata_io_{std::make_unique>()}, storage_serialization_format_{"rmw1_format"}, - tmp_dir_{rcpputils::fs::temp_directory_path() / bag_name_}, + tmp_dir_{fs::temp_directory_path() / bag_name_}, converter_options_{"", storage_serialization_format_} { - rcpputils::fs::remove_all(tmp_dir_); + fs::remove_all(tmp_dir_); storage_options_.uri = tmp_dir_.string(); topic_with_type_ = rosbag2_storage::TopicMetadata{ 0U, "topic", "test_msgs/BasicTypes", storage_serialization_format_, {}, ""}; @@ -92,7 +94,7 @@ class SequentialCompressionReaderTest : public Test void initialize_dummy_storage_files() { // Initialize some dummy files so that they can be found - rcpputils::fs::create_directories(tmp_dir_); + fs::create_directories(tmp_dir_); for (auto relative : metadata_.relative_file_paths) { std::ofstream output((tmp_dir_ / relative).string()); output << "Fake storage data" << std::endl; @@ -104,9 +106,9 @@ class SequentialCompressionReaderTest : public Test auto decompressor = std::make_unique>(); ON_CALL(*decompressor, decompress_uri).WillByDefault( [](auto uri) { - auto path = rcpputils::fs::path(uri); - EXPECT_TRUE(path.exists()); - return rcpputils::fs::remove_extension(path).string(); + auto path = fs::path(uri); + EXPECT_TRUE(fs::exists(path)); + return path.replace_extension().generic_string(); }); auto compression_factory = std::make_unique>(); ON_CALL(*compression_factory, create_decompressor(_)) @@ -126,7 +128,7 @@ class SequentialCompressionReaderTest : public Test std::string storage_serialization_format_; rosbag2_storage::TopicMetadata topic_with_type_; const std::string bag_name_ = "SequentialCompressionReaderTest"; - rcpputils::fs::path tmp_dir_; + fs::path tmp_dir_; rosbag2_storage::StorageOptions storage_options_; rosbag2_storage::BagMetadata metadata_; rosbag2_cpp::ConverterOptions converter_options_; @@ -254,7 +256,7 @@ TEST_F(SequentialCompressionReaderTest, throws_on_incorrect_filenames) { for (auto & relative_file_path : metadata_.relative_file_paths) { relative_file_path = ( - rcpputils::fs::path(bag_name_) / (relative_file_path + ".something")).string(); + fs::path(bag_name_) / (relative_file_path + ".something")).string(); } auto reader = create_reader(); EXPECT_THROW(reader->open(storage_options_, converter_options_), std::invalid_argument); @@ -264,7 +266,7 @@ TEST_F(SequentialCompressionReaderTest, can_find_prefixed_filenames) { // By prefixing the bag name, this imitates the V3 filename logic for (auto & relative_file_path : metadata_.relative_file_paths) { - relative_file_path = (rcpputils::fs::path(bag_name_) / relative_file_path).string(); + relative_file_path = (fs::path(bag_name_) / relative_file_path).string(); } auto reader = create_reader(); @@ -278,7 +280,7 @@ TEST_F(SequentialCompressionReaderTest, can_find_prefixed_filenames_in_renamed_b // was recorded using V3 logic, then the directory was moved to be a new name - this is the // use case the V4 relative path logic was intended to fix for (auto & relative_file_path : metadata_.relative_file_paths) { - relative_file_path = (rcpputils::fs::path("OtherBagName") / relative_file_path).string(); + relative_file_path = (fs::path("OtherBagName") / relative_file_path).string(); } auto reader = create_reader(); diff --git a/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp b/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp index 9cb3140240..c17a0da25d 100644 --- a/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp +++ b/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp @@ -14,6 +14,7 @@ #include +#include #include #include #include @@ -21,7 +22,6 @@ #include #include "rcpputils/asserts.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "rosbag2_compression/compression_options.hpp" #include "rosbag2_compression/sequential_compression_writer.hpp" @@ -47,6 +47,8 @@ using namespace testing; // NOLINT +namespace fs = std::filesystem; + static constexpr const char * DefaultTestCompressor = "fake_comp"; class SequentialCompressionWriterTest : public TestWithParam @@ -57,12 +59,12 @@ class SequentialCompressionWriterTest : public TestWithParam storage_{std::make_shared>()}, converter_factory_{std::make_shared>()}, metadata_io_{std::make_unique>()}, - tmp_dir_{rcpputils::fs::temp_directory_path() / "SequentialCompressionWriterTest"}, + tmp_dir_{fs::temp_directory_path() / "SequentialCompressionWriterTest"}, tmp_dir_storage_options_{}, serialization_format_{"rmw_format"} { tmp_dir_storage_options_.uri = tmp_dir_.string(); - rcpputils::fs::remove_all(tmp_dir_); + fs::remove_all(tmp_dir_); ON_CALL(*storage_factory_, open_read_write(_)).WillByDefault(Return(storage_)); EXPECT_CALL(*storage_factory_, open_read_write(_)).Times(AtLeast(0)); // intercept the metadata write so we can analyze it. @@ -79,7 +81,7 @@ class SequentialCompressionWriterTest : public TestWithParam ~SequentialCompressionWriterTest() override { - rcpputils::fs::remove_all(tmp_dir_); + fs::remove_all(tmp_dir_); } void initializeFakeFileStorage() @@ -139,7 +141,7 @@ class SequentialCompressionWriterTest : public TestWithParam std::shared_ptr> converter_factory_; std::unique_ptr metadata_io_; - rcpputils::fs::path tmp_dir_; + fs::path tmp_dir_; rosbag2_storage::StorageOptions tmp_dir_storage_options_; rosbag2_storage::BagMetadata intercepted_write_metadata_; std::vector v_intercepted_update_metadata_; @@ -212,7 +214,7 @@ TEST_F(SequentialCompressionWriterTest, open_succeeds_on_supported_compression_f kDefaultCompressionQueueThreadsPriority}; initializeWriter(compression_options); - auto tmp_dir = rcpputils::fs::temp_directory_path() / "path_not_empty"; + auto tmp_dir = fs::temp_directory_path() / "path_not_empty"; auto storage_options = rosbag2_storage::StorageOptions(); storage_options.uri = tmp_dir.string(); diff --git a/rosbag2_compression_zstd/CMakeLists.txt b/rosbag2_compression_zstd/CMakeLists.txt index f6422dd067..46d76c7ee5 100644 --- a/rosbag2_compression_zstd/CMakeLists.txt +++ b/rosbag2_compression_zstd/CMakeLists.txt @@ -23,7 +23,6 @@ endif() find_package(ament_cmake REQUIRED) find_package(pluginlib REQUIRED) -find_package(rcpputils REQUIRED) find_package(rosbag2_compression REQUIRED) find_package(zstd_vendor REQUIRED) find_package(zstd REQUIRED) @@ -37,7 +36,6 @@ target_include_directories(${PROJECT_NAME} $ $) target_link_libraries(${PROJECT_NAME} - rcpputils::rcpputils rosbag2_compression::rosbag2_compression zstd::zstd ) @@ -63,7 +61,7 @@ ament_export_libraries(${PROJECT_NAME}) ament_export_targets(export_${PROJECT_NAME}) # order matters here, first vendor, then zstd -ament_export_dependencies(rcpputils rosbag2_compression zstd_vendor zstd) +ament_export_dependencies(rosbag2_compression zstd_vendor zstd) if(BUILD_TESTING) diff --git a/rosbag2_compression_zstd/package.xml b/rosbag2_compression_zstd/package.xml index 25ca6ea972..a7c14c7be3 100644 --- a/rosbag2_compression_zstd/package.xml +++ b/rosbag2_compression_zstd/package.xml @@ -15,7 +15,6 @@ ament_cmake pluginlib - rcpputils rcutils rosbag2_compression zstd_vendor diff --git a/rosbag2_compression_zstd/src/rosbag2_compression_zstd/compression_utils.hpp b/rosbag2_compression_zstd/src/rosbag2_compression_zstd/compression_utils.hpp index 2ecaabae2e..b49fe6b6b0 100644 --- a/rosbag2_compression_zstd/src/rosbag2_compression_zstd/compression_utils.hpp +++ b/rosbag2_compression_zstd/src/rosbag2_compression_zstd/compression_utils.hpp @@ -23,8 +23,7 @@ #include #include "logging.hpp" - -#include "rcpputils/filesystem_helper.hpp" +#include "rcutils/types/rcutils_ret.h" namespace rosbag2_compression_zstd { diff --git a/rosbag2_compression_zstd/src/rosbag2_compression_zstd/zstd_compressor.cpp b/rosbag2_compression_zstd/src/rosbag2_compression_zstd/zstd_compressor.cpp index 65e14e0948..1f33def90f 100644 --- a/rosbag2_compression_zstd/src/rosbag2_compression_zstd/zstd_compressor.cpp +++ b/rosbag2_compression_zstd/src/rosbag2_compression_zstd/zstd_compressor.cpp @@ -19,8 +19,6 @@ #include #include -#include "rcpputils/filesystem_helper.hpp" - #include "compression_utils.hpp" #include "rosbag2_compression_zstd/zstd_compressor.hpp" #include "rosbag2_storage/ros_helper.hpp" diff --git a/rosbag2_compression_zstd/src/rosbag2_compression_zstd/zstd_decompressor.cpp b/rosbag2_compression_zstd/src/rosbag2_compression_zstd/zstd_decompressor.cpp index f7692c8f8e..e67fe79d7f 100644 --- a/rosbag2_compression_zstd/src/rosbag2_compression_zstd/zstd_decompressor.cpp +++ b/rosbag2_compression_zstd/src/rosbag2_compression_zstd/zstd_decompressor.cpp @@ -15,15 +15,16 @@ #include #include #include +#include #include #include #include -#include "rcpputils/filesystem_helper.hpp" - #include "compression_utils.hpp" #include "rosbag2_compression_zstd/zstd_decompressor.hpp" +namespace fs = std::filesystem; + namespace rosbag2_compression_zstd { ZstdDecompressor::ZstdDecompressor() @@ -45,8 +46,8 @@ ZstdDecompressor::~ZstdDecompressor() std::string ZstdDecompressor::decompress_uri(const std::string & uri) { const auto start = std::chrono::high_resolution_clock::now(); - const auto uri_path = rcpputils::fs::path{uri}; - const auto decompressed_uri = rcpputils::fs::remove_extension(uri_path).string(); + auto uri_path = fs::path{uri}; + auto decompressed_uri = uri_path.replace_extension().generic_string(); std::ifstream input(uri, std::ios::in | std::ios::binary); if (!input.is_open()) { diff --git a/rosbag2_compression_zstd/test/rosbag2_compression_zstd/test_zstd_compressor.cpp b/rosbag2_compression_zstd/test/rosbag2_compression_zstd/test_zstd_compressor.cpp index 387ee19f98..c8e33ce3d5 100644 --- a/rosbag2_compression_zstd/test/rosbag2_compression_zstd/test_zstd_compressor.cpp +++ b/rosbag2_compression_zstd/test/rosbag2_compression_zstd/test_zstd_compressor.cpp @@ -14,15 +14,15 @@ #include #include +#include #include #include #include +#include #include #include "rclcpp/rclcpp.hpp" -#include "rcpputils/filesystem_helper.hpp" - #include "rosbag2_compression_zstd/zstd_compressor.hpp" #include "rosbag2_compression_zstd/zstd_decompressor.hpp" @@ -32,6 +32,8 @@ #include "gmock/gmock.h" +namespace fs = std::filesystem; + namespace { constexpr const char kGarbageStatement[] = "garbage"; @@ -134,62 +136,63 @@ class CompressionHelperFixture : public rosbag2_test_common::TemporaryDirectoryF TEST_F(CompressionHelperFixture, zstd_compress_file_uri) { - const auto uri = (rcpputils::fs::path(temporary_dir_path_) / "file1.txt").string(); + const auto uri = (fs::path(temporary_dir_path_) / "file1.txt").generic_string(); create_garbage_file(uri); - ASSERT_TRUE(rcpputils::fs::exists(uri)) << + ASSERT_TRUE(fs::exists(uri)) << "Expected uncompressed URI: \"" << uri << "\" to exist."; auto zstd_compressor = rosbag2_compression_zstd::ZstdCompressor{}; const auto compressed_uri = zstd_compressor.compress_uri(uri); - ASSERT_TRUE(rcpputils::fs::exists(compressed_uri)) << + ASSERT_TRUE(fs::exists(compressed_uri)) << "Expected compressed URI: \"" << compressed_uri << "\" to exist."; const auto expected_compressed_uri = uri + "." + zstd_compressor.get_compression_identifier(); - const auto uncompressed_file_size = rcpputils::fs::file_size(rcpputils::fs::path{uri}); - const auto compressed_file_size = rcpputils::fs::file_size(rcpputils::fs::path{compressed_uri}); + const auto uncompressed_file_size = fs::file_size(fs::path(uri)); + const auto compressed_file_size = + fs::file_size(fs::path{compressed_uri}); EXPECT_NE(compressed_uri, uri); EXPECT_EQ(compressed_uri, expected_compressed_uri); EXPECT_LT(compressed_file_size, uncompressed_file_size); EXPECT_GT(compressed_file_size, 0u); - EXPECT_TRUE(rcpputils::fs::exists(compressed_uri)) << + EXPECT_TRUE(fs::exists(compressed_uri)) << "Expected compressed path: \"" << compressed_uri << "\" to exist!"; } TEST_F(CompressionHelperFixture, zstd_decompress_file_uri) { - const auto uri = (rcpputils::fs::path(temporary_dir_path_) / "file1.txt").string(); + const auto uri = (fs::path(temporary_dir_path_) / "file1.txt").generic_string(); create_garbage_file(uri); - const auto initial_file_path = rcpputils::fs::path{uri}; + const auto initial_file_path = fs::path{uri}; - ASSERT_TRUE(initial_file_path.exists()) << - "Expected initial file: \"" << initial_file_path.string() << + ASSERT_TRUE(fs::exists(initial_file_path)) << + "Expected initial file: \"" << initial_file_path.generic_string() << "\" to exist."; - const auto initial_file_size = initial_file_path.file_size(); + const auto initial_file_size = fs::file_size(initial_file_path); auto zstd_compressor = rosbag2_compression_zstd::ZstdCompressor{}; const auto compressed_uri = zstd_compressor.compress_uri(uri); // The test is invalid if the initial file is not deleted - ASSERT_TRUE(rcpputils::fs::remove(initial_file_path)) << - "Removal of \"" << initial_file_path.string() << + ASSERT_TRUE(fs::remove(initial_file_path)) << + "Removal of \"" << initial_file_path.generic_string() << "\" failed! The remaining tests require \"" << - initial_file_path.string() << "\" to be deleted!"; + initial_file_path.generic_string() << "\" to be deleted!"; auto zstd_decompressor = rosbag2_compression_zstd::ZstdDecompressor{}; const auto decompressed_uri = zstd_decompressor.decompress_uri(compressed_uri); - const auto decompressed_file_path = rcpputils::fs::path{decompressed_uri}; + const auto decompressed_file_path = fs::path{decompressed_uri}; const auto expected_decompressed_uri = uri; - ASSERT_TRUE(decompressed_file_path.exists()) << - "Expected decompressed file: \"" << decompressed_file_path.string() << + ASSERT_TRUE(fs::exists(decompressed_file_path)) << + "Expected decompressed file: \"" << decompressed_file_path.generic_string() << "\" to exist."; - const auto decompressed_file_size = decompressed_file_path.file_size(); + const auto decompressed_file_size = fs::file_size(decompressed_file_path); EXPECT_NE(compressed_uri, uri); EXPECT_NE(decompressed_uri, compressed_uri); @@ -199,15 +202,15 @@ TEST_F(CompressionHelperFixture, zstd_decompress_file_uri) TEST_F(CompressionHelperFixture, zstd_decompress_file_contents) { - const auto uri = (rcpputils::fs::path(temporary_dir_path_) / "file2.txt").string(); + const auto uri = (fs::path(temporary_dir_path_) / "file2.txt").generic_string(); create_garbage_file(uri); - const auto initial_file_path = rcpputils::fs::path{uri}; - ASSERT_TRUE(initial_file_path.exists()) << + const auto initial_file_path = fs::path{uri}; + ASSERT_TRUE(fs::exists(initial_file_path)) << "Expected initial file: \"" << uri << "\" to exist!"; const auto initial_data = read_file(uri); - const auto initial_file_size = initial_file_path.file_size(); + const auto initial_file_size = fs::file_size(initial_file_path); EXPECT_EQ( initial_data.size() * sizeof(decltype(initial_data)::value_type), @@ -216,7 +219,7 @@ TEST_F(CompressionHelperFixture, zstd_decompress_file_contents) auto compressor = rosbag2_compression_zstd::ZstdCompressor{}; const auto compressed_uri = compressor.compress_uri(uri); - ASSERT_TRUE(rcpputils::fs::exists(compressed_uri)) << + ASSERT_TRUE(fs::exists(compressed_uri)) << "Expected compressed file: \"" << compressed_uri << "\" to exist!"; ASSERT_EQ(0, std::remove(uri.c_str())) << @@ -225,16 +228,16 @@ TEST_F(CompressionHelperFixture, zstd_decompress_file_contents) auto decompressor = rosbag2_compression_zstd::ZstdDecompressor{}; const auto decompressed_uri = decompressor.decompress_uri(compressed_uri); - const auto decompressed_file_path = rcpputils::fs::path{decompressed_uri}; + const auto decompressed_file_path = fs::path{decompressed_uri}; - ASSERT_TRUE(decompressed_file_path.exists()) << - "Decompressed file: \"" << decompressed_file_path.string() << "\" must exist!"; + ASSERT_TRUE(fs::exists(decompressed_file_path)) << + "Decompressed file: \"" << decompressed_file_path.generic_string() << "\" must exist!"; EXPECT_EQ(uri, decompressed_uri) << "Expected decompressed file name to be same as initial!"; const auto decompressed_data = read_file(decompressed_uri); - const auto decompressed_file_size = decompressed_file_path.file_size(); + const auto decompressed_file_size = fs::file_size(decompressed_file_path); EXPECT_EQ( decompressed_data.size() * sizeof(decltype(initial_data)::value_type), @@ -249,7 +252,7 @@ TEST_F(CompressionHelperFixture, zstd_decompress_file_contents) TEST_F(CompressionHelperFixture, zstd_decompress_fails_on_bad_file) { - const auto uri = (rcpputils::fs::path(temporary_dir_path_) / "file3.txt").string(); + const auto uri = (fs::path(temporary_dir_path_) / "file3.txt").generic_string(); create_garbage_file(uri); auto decompressor = rosbag2_compression_zstd::ZstdDecompressor{}; @@ -259,7 +262,7 @@ TEST_F(CompressionHelperFixture, zstd_decompress_fails_on_bad_file) TEST_F(CompressionHelperFixture, zstd_decompress_fails_on_bad_uri) { - const auto bad_uri = (rcpputils::fs::path(temporary_dir_path_) / "bad_uri.txt").string(); + const auto bad_uri = (fs::path(temporary_dir_path_) / "bad_uri.txt").generic_string(); auto decompressor = rosbag2_compression_zstd::ZstdDecompressor{}; EXPECT_THROW(decompressor.decompress_uri(bad_uri), std::runtime_error) << diff --git a/rosbag2_cpp/include/rosbag2_cpp/reindexer.hpp b/rosbag2_cpp/include/rosbag2_cpp/reindexer.hpp index 9c0c04a794..23c3f4103d 100644 --- a/rosbag2_cpp/include/rosbag2_cpp/reindexer.hpp +++ b/rosbag2_cpp/include/rosbag2_cpp/reindexer.hpp @@ -23,13 +23,12 @@ #ifndef ROSBAG2_CPP__REINDEXER_HPP_ #define ROSBAG2_CPP__REINDEXER_HPP_ +#include #include #include #include #include -#include "rcpputils/filesystem_helper.hpp" - #include "rosbag2_cpp/converter.hpp" #include "rosbag2_cpp/reader.hpp" #include "rosbag2_cpp/serialization_format_converter_factory.hpp" @@ -91,27 +90,27 @@ class ROSBAG2_CPP_PUBLIC Reindexer private: std::string regex_bag_pattern_; - rcpputils::fs::path base_folder_; // The folder that the bag files are in + std::filesystem::path base_folder_; // The folder that the bag files are in std::shared_ptr converter_factory_{}; void get_bag_files( - const rcpputils::fs::path & base_folder, - std::vector & output); + const std::filesystem::path & base_folder, + std::vector & output); // Prepares the metadata by setting initial values. void init_metadata( - const std::vector & files, + const std::vector & files, const rosbag2_storage::StorageOptions & storage_options); // Attempts to harvest metadata from all bag files, and aggregates the result void aggregate_metadata( - const std::vector & files, + const std::vector & files, const std::unique_ptr & bag_reader, const rosbag2_storage::StorageOptions & storage_options); // Comparison function for std::sort with our filepath convention bool compare_relative_file( - const rcpputils::fs::path & first_path, - const rcpputils::fs::path & second_path); + const std::filesystem::path & first_path, + const std::filesystem::path & second_path); }; } // namespace rosbag2_cpp diff --git a/rosbag2_cpp/src/rosbag2_cpp/info.cpp b/rosbag2_cpp/src/rosbag2_cpp/info.cpp index 9e00cb742c..995595fbb1 100644 --- a/rosbag2_cpp/src/rosbag2_cpp/info.cpp +++ b/rosbag2_cpp/src/rosbag2_cpp/info.cpp @@ -14,6 +14,7 @@ #include "rosbag2_cpp/info.hpp" +#include #include #include #include @@ -21,21 +22,22 @@ #include "rmw/rmw.h" #include "rosidl_typesupport_cpp/message_type_support.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "service_msgs/msg/service_event_info.hpp" #include "rosbag2_cpp/service_utils.hpp" #include "rosbag2_storage/metadata_io.hpp" #include "rosbag2_storage/storage_factory.hpp" +namespace fs = std::filesystem; + namespace rosbag2_cpp { rosbag2_storage::BagMetadata Info::read_metadata( const std::string & uri, const std::string & storage_id) { - const rcpputils::fs::path bag_path{uri}; - if (!bag_path.exists()) { + const fs::path bag_path{uri}; + if (!fs::exists(bag_path)) { throw std::runtime_error("Bag path " + uri + " does not exist."); } @@ -44,7 +46,7 @@ rosbag2_storage::BagMetadata Info::read_metadata( return metadata_io.read_metadata(uri); } - if (bag_path.is_directory()) { + if (fs::is_directory(bag_path)) { throw std::runtime_error("Could not find metadata in bag directory " + uri); } diff --git a/rosbag2_cpp/src/rosbag2_cpp/readers/sequential_reader.cpp b/rosbag2_cpp/src/rosbag2_cpp/readers/sequential_reader.cpp index 9bdd802fcf..8c8634bd62 100644 --- a/rosbag2_cpp/src/rosbag2_cpp/readers/sequential_reader.cpp +++ b/rosbag2_cpp/src/rosbag2_cpp/readers/sequential_reader.cpp @@ -12,6 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include #include @@ -19,11 +20,11 @@ #include #include "rcpputils/asserts.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "rosbag2_cpp/logging.hpp" #include "rosbag2_cpp/readers/sequential_reader.hpp" +namespace fs = std::filesystem; namespace rosbag2_cpp { @@ -34,23 +35,23 @@ namespace details std::vector resolve_relative_paths( const std::string & base_folder, std::vector relative_files, const int version = 4) { - auto base_path = rcpputils::fs::path(base_folder); + auto base_path = fs::path(base_folder); if (version < 4) { // In older rosbags (version <=3) relative files are prefixed with the rosbag folder name - base_path = rcpputils::fs::path(base_folder).parent_path(); + base_path = fs::path(base_folder).parent_path(); } rcpputils::require_true( - base_path.exists(), "base folder does not exist: " + base_folder); + fs::exists(base_path), "base folder does not exist: " + base_folder); rcpputils::require_true( - base_path.is_directory(), "base folder has to be a directory: " + base_folder); + fs::is_directory(base_path), "base folder has to be a directory: " + base_folder); for (auto & file : relative_files) { - auto path = rcpputils::fs::path(file); + auto path = fs::path(file); if (path.is_absolute()) { continue; } - file = (base_path / path).string(); + file = (base_path / path).generic_string(); } return relative_files; @@ -307,8 +308,8 @@ std::string SequentialReader::get_current_file() const std::string SequentialReader::get_current_uri() const { auto current_file = get_current_file(); - auto current_uri = rcpputils::fs::remove_extension(current_file); - return current_uri.string(); + auto current_uri = fs::path(current_file).stem(); + return current_uri.generic_string(); } void SequentialReader::check_topics_serialization_formats( diff --git a/rosbag2_cpp/src/rosbag2_cpp/reindexer.cpp b/rosbag2_cpp/src/rosbag2_cpp/reindexer.cpp index 1a55a0a472..199d94f882 100644 --- a/rosbag2_cpp/src/rosbag2_cpp/reindexer.cpp +++ b/rosbag2_cpp/src/rosbag2_cpp/reindexer.cpp @@ -21,6 +21,7 @@ // This notice must appear in all copies of this file and its derivatives. #include +#include #include #include #include @@ -31,9 +32,6 @@ #include #include "rcpputils/asserts.hpp" -#include "rcpputils/filesystem_helper.hpp" - -#include "rcutils/filesystem.h" #include "rosbag2_cpp/logging.hpp" #include "rosbag2_cpp/reader.hpp" @@ -41,6 +39,8 @@ #include "rosbag2_storage/storage_options.hpp" +namespace fs = std::filesystem; + namespace rosbag2_cpp { Reindexer::Reindexer( @@ -58,29 +58,29 @@ Reindexer::Reindexer( * don't guarantee a preserved order */ bool Reindexer::compare_relative_file( - const rcpputils::fs::path & first_path, - const rcpputils::fs::path & second_path) + const fs::path & first_path, + const fs::path & second_path) { std::regex regex_rule(regex_bag_pattern_, std::regex_constants::ECMAScript); std::smatch first_match; std::smatch second_match; - auto first_path_string = first_path.string(); - auto second_path_string = second_path.string(); + auto first_path_string = first_path.generic_string(); + auto second_path_string = second_path.generic_string(); auto first_regex_good = std::regex_match(first_path_string, first_match, regex_rule); auto second_regex_good = std::regex_match(second_path_string, second_match, regex_rule); if (!first_regex_good) { std::stringstream ss; - ss << "Path " << first_path.string() << + ss << "Path " << first_path.generic_string() << "didn't meet expected naming convention: " << regex_bag_pattern_; std::string error_text = ss.str(); throw std::runtime_error(error_text.c_str()); } else if (!second_regex_good) { std::stringstream ss; - ss << "Path " << second_path.string() << + ss << "Path " << second_path.generic_string() << "didn't meet expected naming convention: " << regex_bag_pattern_; std::string error_text = ss.str(); throw std::runtime_error(error_text.c_str()); @@ -99,33 +99,30 @@ bool Reindexer::compare_relative_file( * The files will be `emplace_back`-ed on the passed vector */ void Reindexer::get_bag_files( - const rcpputils::fs::path & base_folder, - std::vector & output) + const fs::path & base_folder, + std::vector & output) { - std::regex regex_rule(regex_bag_pattern_, std::regex_constants::ECMAScript); - auto allocator = rcutils_get_default_allocator(); - auto dir_iter = rcutils_dir_iter_start(base_folder.string().c_str(), allocator); - // Make sure there are files in the directory - if (dir_iter == nullptr) { + if (fs::is_empty(base_folder)) { throw std::runtime_error("Empty directory."); } + std::regex regex_rule(regex_bag_pattern_, std::regex_constants::ECMAScript); // Get all file names in directory - do { - auto found_file = rcpputils::fs::path(dir_iter->entry_name); - ROSBAG2_CPP_LOG_DEBUG_STREAM("Found file: " << found_file.string()); + for (const auto & entry : fs::directory_iterator(base_folder)) { + auto found_file = entry.path().filename(); + ROSBAG2_CPP_LOG_DEBUG_STREAM("Found file: " << found_file.generic_string()); - if (std::regex_match(found_file.string(), regex_rule)) { + if (std::regex_match(found_file.generic_string(), regex_rule)) { auto full_path = base_folder / found_file; output.emplace_back(full_path); } - } while (rcutils_dir_iter_next(dir_iter)); + } // Sort relative file path by number std::sort( output.begin(), output.end(), - [&, this](rcpputils::fs::path a, rcpputils::fs::path b) { + [&, this](fs::path a, fs::path b) { return compare_relative_file(a, b); }); } @@ -136,7 +133,7 @@ void Reindexer::get_bag_files( * Also fills in `starting_time` with a dummy default value. Important for later functions */ void Reindexer::init_metadata( - const std::vector & files, + const std::vector & files, const rosbag2_storage::StorageOptions & storage_options) { metadata_ = rosbag2_storage::BagMetadata{}; @@ -147,7 +144,7 @@ void Reindexer::init_metadata( // Record the relative paths to the metadata for (const auto & path : files) { - auto cleaned_path = path.filename().string(); + auto cleaned_path = path.filename().generic_string(); metadata_.relative_file_paths.push_back(cleaned_path); } } @@ -160,7 +157,7 @@ void Reindexer::init_metadata( * @param: storage_options Used to construct the `Reader` needed to parse the bag files */ void Reindexer::aggregate_metadata( - const std::vector & files, + const std::vector & files, const std::unique_ptr & bag_reader, const rosbag2_storage::StorageOptions & storage_options) { @@ -171,9 +168,9 @@ void Reindexer::aggregate_metadata( // open them, read the info, and write it into an aggregated metadata object. ROSBAG2_CPP_LOG_DEBUG_STREAM("Extracting metadata from bag file(s)"); for (const auto & f_ : files) { - ROSBAG2_CPP_LOG_DEBUG_STREAM("Extracting from file: " + f_.string()); + ROSBAG2_CPP_LOG_DEBUG_STREAM("Extracting from file: " + f_.generic_string()); - metadata_.bag_size += f_.file_size(); + metadata_.bag_size += fs::file_size(f_); // Set up reader rosbag2_storage::StorageOptions temp_so = { @@ -247,7 +244,7 @@ void Reindexer::reindex(const rosbag2_storage::StorageOptions & storage_options) std::move(storage_factory_), converter_factory_, std::move(metadata_io_default)); // Identify all bag files - std::vector files; + std::vector files; get_bag_files(base_folder_, files); if (files.empty()) { throw std::runtime_error("No storage files found for reindexing. Abort"); @@ -260,7 +257,7 @@ void Reindexer::reindex(const rosbag2_storage::StorageOptions & storage_options) aggregate_metadata(files, bag_reader, storage_options); ROSBAG2_CPP_LOG_DEBUG_STREAM("Completed aggregate_metadata"); - metadata_io_->write_metadata(base_folder_.string(), metadata_); + metadata_io_->write_metadata(base_folder_.generic_string(), metadata_); ROSBAG2_CPP_LOG_INFO("Reindexing complete."); } } // namespace rosbag2_cpp diff --git a/rosbag2_cpp/src/rosbag2_cpp/writers/sequential_writer.cpp b/rosbag2_cpp/src/rosbag2_cpp/writers/sequential_writer.cpp index 37d3d49b0e..eaaaff25e7 100644 --- a/rosbag2_cpp/src/rosbag2_cpp/writers/sequential_writer.cpp +++ b/rosbag2_cpp/src/rosbag2_cpp/writers/sequential_writer.cpp @@ -16,6 +16,7 @@ #include #include +#include #include #include #include @@ -25,7 +26,6 @@ #include #include "rcpputils/env.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "rosbag2_cpp/info.hpp" #include "rosbag2_cpp/logging.hpp" @@ -34,6 +34,8 @@ #include "rosbag2_storage/default_storage_id.hpp" #include "rosbag2_storage/storage_options.hpp" +namespace fs = std::filesystem; + namespace rosbag2_cpp { namespace writers @@ -43,7 +45,7 @@ namespace { std::string strip_parent_path(const std::string & relative_path) { - return rcpputils::fs::path(relative_path).filename().string(); + return fs::path(relative_path).filename().generic_string(); } } // namespace @@ -107,15 +109,15 @@ void SequentialWriter::open( converter_ = std::make_unique(converter_options, converter_factory_); } - rcpputils::fs::path storage_path(storage_options.uri); - if (storage_path.is_directory()) { + fs::path storage_path(storage_options.uri); + if (fs::is_directory(storage_path)) { std::stringstream error; error << "Bag directory already exists (" << storage_path.string() << "), can't overwrite existing bag"; throw std::runtime_error{error.str()}; } - bool dir_created = rcpputils::fs::create_directories(storage_path); + bool dir_created = fs::create_directories(storage_path); if (!dir_created) { std::stringstream error; error << "Failed to create bag directory (" << storage_path.string() << ")."; @@ -287,9 +289,10 @@ std::string SequentialWriter::format_storage_uri( // The name of the folder needs to be queried in case // SequentialWriter is opened with a relative path. std::stringstream storage_file_name; - storage_file_name << rcpputils::fs::path(base_folder).filename().string() << "_" << storage_count; + storage_file_name << fs::path(base_folder).filename().generic_string() << "_" << + storage_count; - return (rcpputils::fs::path(base_folder) / storage_file_name.str()).string(); + return (fs::path(base_folder) / storage_file_name.str()).generic_string(); } void SequentialWriter::switch_to_next_storage() @@ -468,10 +471,10 @@ void SequentialWriter::finalize_metadata() metadata_.bag_size = 0; for (const auto & path : metadata_.relative_file_paths) { - const auto bag_path = rcpputils::fs::path{path}; + const auto bag_path = fs::path{path}; - if (bag_path.exists()) { - metadata_.bag_size += bag_path.file_size(); + if (fs::exists(bag_path)) { + metadata_.bag_size += fs::file_size(bag_path); } } diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp index a4fa57985a..ebb0d63c5d 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp @@ -14,13 +14,12 @@ #include +#include #include #include #include #include -#include "rcpputils/filesystem_helper.hpp" - #include "rosbag2_cpp/info.hpp" #include "rosbag2_cpp/writer.hpp" @@ -34,6 +33,7 @@ using namespace ::testing; // NOLINT using rosbag2_test_common::ParametrizedTemporaryDirectoryFixture; +namespace fs = std::filesystem; TEST_P(ParametrizedTemporaryDirectoryFixture, read_metadata_supports_version_2) { const auto expected_storage_id = GetParam(); @@ -62,8 +62,8 @@ TEST_P(ParametrizedTemporaryDirectoryFixture, read_metadata_supports_version_2) { std::ofstream fout { - (rcpputils::fs::path(temporary_dir_path_) / rosbag2_storage::MetadataIo::metadata_filename) - .string()}; + (fs::path(temporary_dir_path_) / rosbag2_storage::MetadataIo::metadata_filename) + .generic_string()}; fout << bagfile; } @@ -150,8 +150,8 @@ TEST_P(ParametrizedTemporaryDirectoryFixture, read_metadata_supports_version_6) { std::ofstream fout { - (rcpputils::fs::path(temporary_dir_path_) / rosbag2_storage::MetadataIo::metadata_filename) - .string()}; + (fs::path(temporary_dir_path_) / rosbag2_storage::MetadataIo::metadata_filename) + .generic_string()}; fout << bagfile; } @@ -240,8 +240,8 @@ TEST_P( " compression_mode: \"FILE\"\n"); std::ofstream fout { - (rcpputils::fs::path(temporary_dir_path_) / rosbag2_storage::MetadataIo::metadata_filename) - .string()}; + (fs::path(temporary_dir_path_) / rosbag2_storage::MetadataIo::metadata_filename) + .generic_string()}; fout << bagfile; fout.close(); @@ -293,13 +293,13 @@ TEST_P( TEST_P(ParametrizedTemporaryDirectoryFixture, info_for_standalone_bagfile) { const auto storage_id = GetParam(); - const auto bag_path = rcpputils::fs::path(temporary_dir_path_) / "bag"; + const auto bag_path = fs::path(temporary_dir_path_) / "bag"; { // Create an empty bag with default storage rosbag2_cpp::Writer writer; rosbag2_storage::StorageOptions storage_options; storage_options.storage_id = storage_id; - storage_options.uri = bag_path.string(); + storage_options.uri = bag_path.generic_string(); writer.open(storage_options); test_msgs::msg::BasicTypes msg; writer.write(msg, "testtopic", rclcpp::Time{}); diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_multifile_reader.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_multifile_reader.cpp index 3e41c43621..9a44659718 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_multifile_reader.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_multifile_reader.cpp @@ -14,13 +14,12 @@ #include +#include #include #include #include #include -#include "rcpputils/filesystem_helper.hpp" - #include "rosbag2_cpp/reader.hpp" #include "rosbag2_cpp/readers/sequential_reader.hpp" @@ -33,6 +32,7 @@ #include "mock_storage_factory.hpp" using namespace testing; // NOLINT +namespace fs = std::filesystem; class MultifileReaderTest : public Test { @@ -41,10 +41,10 @@ class MultifileReaderTest : public Test : storage_(std::make_shared>()), converter_factory_(std::make_shared>()), storage_serialization_format_("rmw1_format"), - storage_uri_(rcpputils::fs::temp_directory_path().string()), + storage_uri_(fs::temp_directory_path().generic_string()), relative_path_1_("some_relative_path_1"), relative_path_2_("some_relative_path_2"), - absolute_path_1_((rcpputils::fs::path(storage_uri_) / "some/folder").string()), + absolute_path_1_((fs::path(storage_uri_) / "some/folder").generic_string()), default_storage_options_({storage_uri_, ""}) {} @@ -108,7 +108,7 @@ class MultifileReaderTestVersion3 : public MultifileReaderTest { relative_path_1_ = "rosbag_name/some_relative_path_1"; relative_path_2_ = "rosbag_name/some_relative_path_2"; - absolute_path_1_ = (rcpputils::fs::path(storage_uri_) / "some/folder").string(); + absolute_path_1_ = (fs::path(storage_uri_) / "some/folder").generic_string(); } rosbag2_storage::BagMetadata get_metadata() const override @@ -138,11 +138,11 @@ TEST_F(MultifileReaderTest, has_next_reads_next_file) reader_->get_implementation_handle()); auto resolved_relative_path_1 = - (rcpputils::fs::path(storage_uri_) / relative_path_1_).string(); + (fs::path(storage_uri_) / relative_path_1_).generic_string(); auto resolved_relative_path_2 = - (rcpputils::fs::path(storage_uri_) / relative_path_2_).string(); + (fs::path(storage_uri_) / relative_path_2_).generic_string(); auto resolved_absolute_path_1 = - rcpputils::fs::path(absolute_path_1_).string(); + fs::path(absolute_path_1_).generic_string(); EXPECT_EQ(sr.get_current_file(), resolved_relative_path_1); reader_->read_next(); // calls has_next false then true EXPECT_EQ(sr.get_current_file(), resolved_relative_path_2); @@ -170,11 +170,11 @@ TEST_F(MultifileReaderTestVersion3, has_next_reads_next_file_version3) // Legacy version <=3 have a parent_path() prefixed in the relative files auto resolved_relative_path_1 = - (rcpputils::fs::path(storage_uri_).parent_path() / relative_path_1_).string(); + (fs::path(storage_uri_).parent_path() / relative_path_1_).generic_string(); auto resolved_relative_path_2 = - (rcpputils::fs::path(storage_uri_).parent_path() / relative_path_2_).string(); + (fs::path(storage_uri_).parent_path() / relative_path_2_).generic_string(); auto resolved_absolute_path_1 = - rcpputils::fs::path(absolute_path_1_).string(); + fs::path(absolute_path_1_).generic_string(); EXPECT_EQ(sr.get_current_file(), resolved_relative_path_1); reader_->read_next(); // calls has_next false then true EXPECT_EQ(sr.get_current_file(), resolved_relative_path_2); diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp index 9ec24ac9c2..7d67ed7ffb 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp @@ -14,13 +14,12 @@ #include +#include #include #include #include #include -#include "rcpputils/filesystem_helper.hpp" - #include "rosbag2_cpp/readers/sequential_reader.hpp" #include "rosbag2_cpp/reader.hpp" #include "rosbag2_cpp/writer.hpp" @@ -44,6 +43,7 @@ using namespace testing; // NOLINT using rosbag2_test_common::ParametrizedTemporaryDirectoryFixture; +namespace fs = std::filesystem; class SequentialReaderTest : public Test { @@ -52,7 +52,7 @@ class SequentialReaderTest : public Test : storage_(std::make_shared>()), converter_factory_(std::make_shared>()), storage_serialization_format_("rmw1_format"), - storage_uri_(rcpputils::fs::temp_directory_path().string()), + storage_uri_(fs::temp_directory_path().generic_string()), default_storage_options_({storage_uri_, "mock_storage"}) { rosbag2_storage::TopicMetadata topic_with_type; @@ -66,12 +66,15 @@ class SequentialReaderTest : public Test message->topic_name = topic_with_type.name; relative_file_path_ = - (rcpputils::fs::path(storage_uri_) / "some/folder").string(); + (fs::path(storage_uri_) / "some/folder").generic_string(); auto storage_factory = std::make_unique>(); auto metadata_io = std::make_unique>(); bag_file_1_path_ = relative_file_path_ / "bag_file1"; bag_file_2_path_ = relative_file_path_ / "bag_file2"; - metadata_.relative_file_paths = {bag_file_1_path_.string(), bag_file_2_path_.string()}; + metadata_.relative_file_paths = { + bag_file_1_path_.generic_string(), + bag_file_2_path_.generic_string() + }; metadata_.version = 4; metadata_.topics_with_message_count.push_back({{topic_with_type}, 6}); metadata_.storage_identifier = "mock_storage"; @@ -121,9 +124,9 @@ class SequentialReaderTest : public Test std::string storage_serialization_format_; std::string storage_uri_; rosbag2_storage::BagMetadata metadata_; - rcpputils::fs::path relative_file_path_; - rcpputils::fs::path bag_file_1_path_; - rcpputils::fs::path bag_file_2_path_; + fs::path relative_file_path_; + fs::path bag_file_1_path_; + fs::path bag_file_2_path_; rosbag2_storage::StorageOptions default_storage_options_; size_t num_next_ = 0; }; @@ -218,30 +221,30 @@ TEST_F(SequentialReaderTest, next_file_calls_callback) { reader_->read_next(); ASSERT_TRUE(callback_called); - EXPECT_EQ(closed_file, bag_file_1_path_.string()); - EXPECT_EQ(opened_file, bag_file_2_path_.string()); + EXPECT_EQ(closed_file, bag_file_1_path_.generic_string()); + EXPECT_EQ(opened_file, bag_file_2_path_.generic_string()); } TEST_P(ParametrizedTemporaryDirectoryFixture, reader_accepts_bare_file) { - const auto bag_path = rcpputils::fs::path(temporary_dir_path_) / "bag"; + const auto bag_path = fs::path(temporary_dir_path_) / "bag"; const auto storage_id = GetParam(); { // Create an empty bag with default storage rosbag2_cpp::Writer writer; rosbag2_storage::StorageOptions options; - options.uri = bag_path.string(); + options.uri = bag_path.generic_string(); options.storage_id = storage_id; writer.open(options); test_msgs::msg::BasicTypes msg; writer.write(msg, "testtopic", rclcpp::Time{}); } rosbag2_storage::MetadataIo metadata_io; - auto metadata = metadata_io.read_metadata(bag_path.string()); + auto metadata = metadata_io.read_metadata(bag_path.generic_string()); auto first_storage = bag_path / metadata.relative_file_paths[0]; rosbag2_cpp::Reader reader; - EXPECT_NO_THROW(reader.open(first_storage.string())); + EXPECT_NO_THROW(reader.open(first_storage.generic_string())); EXPECT_TRUE(reader.has_next()); EXPECT_THAT(reader.get_metadata().topics_with_message_count, SizeIs(1)); } @@ -258,7 +261,8 @@ class ReadOrderTest : public ParametrizedTemporaryDirectoryFixture public: ReadOrderTest() { - storage_options.uri = (rcpputils::fs::path(temporary_dir_path_) / "ordertest").string(); + storage_options.uri = + (fs::path(temporary_dir_path_) / "ordertest").generic_string(); storage_options.storage_id = GetParam(); write_sample_split_bag(storage_options, fake_messages, split_every); } diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp index 511a4e0ec8..8433d47386 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp @@ -14,14 +14,13 @@ #include +#include #include #include #include #include #include -#include "rcpputils/filesystem_helper.hpp" - #include "rosbag2_cpp/writers/sequential_writer.hpp" #include "rosbag2_cpp/writer.hpp" @@ -41,6 +40,7 @@ using namespace testing; // NOLINT using rosbag2_test_common::ParametrizedTemporaryDirectoryFixture; +namespace fs = std::filesystem; class SequentialWriterTest : public Test { @@ -54,8 +54,8 @@ class SequentialWriterTest : public Test storage_options_ = rosbag2_storage::StorageOptions{}; storage_options_.uri = "uri"; - rcpputils::fs::path dir(storage_options_.uri); - rcpputils::fs::remove_all(dir); + fs::path dir(storage_options_.uri); + fs::remove_all(dir); ON_CALL(*storage_factory_, open_read_write(_)).WillByDefault( DoAll( @@ -77,8 +77,8 @@ class SequentialWriterTest : public Test ~SequentialWriterTest() override { - rcpputils::fs::path dir(storage_options_.uri); - rcpputils::fs::remove_all(dir); + fs::path dir(storage_options_.uri); + fs::remove_all(dir); } std::unique_ptr> storage_factory_; @@ -636,8 +636,9 @@ TEST_F(SequentialWriterTest, split_event_calls_callback) } ASSERT_TRUE(callback_called); - auto expected_closed = rcpputils::fs::path(storage_options_.uri) / (storage_options_.uri + "_0"); - EXPECT_EQ(closed_file, expected_closed.string()); + auto expected_closed = fs::path(storage_options_.uri) / + (storage_options_.uri + "_0"); + EXPECT_EQ(closed_file, expected_closed.generic_string()); EXPECT_EQ(opened_file, fake_storage_uri_); } @@ -696,8 +697,9 @@ TEST_F(SequentialWriterTest, split_event_calls_on_writer_close) writer_->close(); ASSERT_TRUE(callback_called); - auto expected_closed = rcpputils::fs::path(storage_options_.uri) / (storage_options_.uri + "_0"); - EXPECT_EQ(closed_file, expected_closed.string()); + auto expected_closed = fs::path(storage_options_.uri) / + (storage_options_.uri + "_0"); + EXPECT_EQ(closed_file, expected_closed.generic_string()); EXPECT_TRUE(opened_file.empty()); } @@ -711,7 +713,8 @@ TEST_P(ParametrizedTemporaryDirectoryFixture, split_bag_metadata_has_full_durati {600, 6} }; rosbag2_storage::StorageOptions storage_options; - storage_options.uri = (rcpputils::fs::path(temporary_dir_path_) / "split_duration_bag").string(); + storage_options.uri = + (fs::path(temporary_dir_path_) / "split_duration_bag").generic_string(); storage_options.storage_id = GetParam(); write_sample_split_bag(storage_options, fake_messages, 3); diff --git a/rosbag2_storage/src/rosbag2_storage/metadata_io.cpp b/rosbag2_storage/src/rosbag2_storage/metadata_io.cpp index 5dae0a85b7..061df94758 100644 --- a/rosbag2_storage/src/rosbag2_storage/metadata_io.cpp +++ b/rosbag2_storage/src/rosbag2_storage/metadata_io.cpp @@ -24,6 +24,8 @@ #include "rosbag2_storage/topic_metadata.hpp" #include "rosbag2_storage/yaml.hpp" +namespace fs = std::filesystem; + namespace rosbag2_storage { @@ -55,14 +57,14 @@ BagMetadata MetadataIo::read_metadata(const std::string & uri) std::string MetadataIo::get_metadata_file_name(const std::string & uri) { - std::string metadata_file = (std::filesystem::path(uri) / metadata_filename).generic_string(); + std::string metadata_file = (fs::path(uri) / metadata_filename).generic_string(); return metadata_file; } bool MetadataIo::metadata_file_exists(const std::string & uri) { - return std::filesystem::exists(std::filesystem::path(get_metadata_file_name(uri))); + return fs::exists(fs::path(get_metadata_file_name(uri))); } std::string MetadataIo::serialize_metadata(const BagMetadata & metadata) diff --git a/rosbag2_tests/test/rosbag2_tests/record_fixture.hpp b/rosbag2_tests/test/rosbag2_tests/record_fixture.hpp index 694e6e4973..9a44487f71 100644 --- a/rosbag2_tests/test/rosbag2_tests/record_fixture.hpp +++ b/rosbag2_tests/test/rosbag2_tests/record_fixture.hpp @@ -17,14 +17,13 @@ #include +#include #include #include #include #include #include -#include "rcpputils/filesystem_helper.hpp" - #include "rclcpp/rclcpp.hpp" #include "rosbag2_compression/sequential_compression_reader.hpp" @@ -50,12 +49,12 @@ class RecordFixture : public ParametrizedTemporaryDirectoryFixture void SetUp() override { auto bag_name = get_test_name() + "_" + GetParam(); - root_bag_path_ = rcpputils::fs::path(temporary_dir_path_) / bag_name; + root_bag_path_ = std::filesystem::path(temporary_dir_path_) / bag_name; // Clean up potentially leftover bag files. // There may be leftovers if the system reallocates a temp directory // used by a previous test execution and the test did not have a clean exit. - rcpputils::fs::remove_all(root_bag_path_); + std::filesystem::remove_all(root_bag_path_); } static void SetUpTestCase() @@ -65,7 +64,7 @@ class RecordFixture : public ParametrizedTemporaryDirectoryFixture void TearDown() override { - rcpputils::fs::remove_all(root_bag_path_); + std::filesystem::remove_all(root_bag_path_); } static void TearDownTestCase() @@ -75,7 +74,8 @@ class RecordFixture : public ParametrizedTemporaryDirectoryFixture std::string get_base_record_command() const { - return "ros2 bag record --storage " + GetParam() + " --output " + root_bag_path_.string(); + return "ros2 bag record --storage " + GetParam() + " --output " + + root_bag_path_.generic_string(); } std::string get_test_name() const @@ -95,20 +95,20 @@ class RecordFixture : public ParametrizedTemporaryDirectoryFixture return bag_file_name.str(); } - rcpputils::fs::path get_compressed_bag_file_path(int split_index) + std::filesystem::path get_compressed_bag_file_path(int split_index) { - return rcpputils::fs::path(get_bag_file_path(split_index).string() + ".zstd"); + return std::filesystem::path(get_bag_file_path(split_index).generic_string() + ".zstd"); } - rcpputils::fs::path get_bag_file_path(int split_index) + std::filesystem::path get_bag_file_path(int split_index) { return root_bag_path_ / get_relative_bag_file_path(split_index); } - rcpputils::fs::path get_relative_bag_file_path(int split_index) + std::filesystem::path get_relative_bag_file_path(int split_index) { const auto storage_id = GetParam(); - return rcpputils::fs::path( + return std::filesystem::path( rosbag2_test_common::bag_filename_for_storage_id( get_bag_file_name(split_index), storage_id)); } @@ -117,7 +117,7 @@ class RecordFixture : public ParametrizedTemporaryDirectoryFixture { rosbag2_storage::MetadataIo metadata_io; const auto start_time = std::chrono::steady_clock::now(); - const auto bag_path = root_bag_path_.string(); + const auto bag_path = root_bag_path_.generic_string(); while (std::chrono::steady_clock::now() - start_time < timeout && rclcpp::ok()) { if (metadata_io.metadata_file_exists(bag_path)) { @@ -134,13 +134,13 @@ class RecordFixture : public ParametrizedTemporaryDirectoryFixture const auto storage_path = get_bag_file_path(0); const auto start_time = std::chrono::steady_clock::now(); while (std::chrono::steady_clock::now() - start_time < timeout && rclcpp::ok()) { - if (storage_path.exists()) { + if (std::filesystem::exists(storage_path)) { return; } std::this_thread::sleep_for(50ms); // wait a bit to not query constantly } - ASSERT_EQ(storage_path.exists(), true) - << "Could not find storage file: \"" << storage_path.string() << "\""; + ASSERT_EQ(std::filesystem::exists(storage_path), true) + << "Could not find storage file: \"" << storage_path.generic_string() << "\""; } template @@ -157,7 +157,7 @@ class RecordFixture : public ParametrizedTemporaryDirectoryFixture reader = std::make_unique( std::make_unique()); } - reader->open(root_bag_path_.string()); + reader->open(root_bag_path_.generic_string()); reader->set_filter(filter); auto messages = std::vector>{}; @@ -171,7 +171,7 @@ class RecordFixture : public ParametrizedTemporaryDirectoryFixture std::string get_serialization_format_for_topic(const std::string & topic_name) { auto reader = rosbag2_cpp::Reader{}; - reader.open(root_bag_path_.string()); + reader.open(root_bag_path_.generic_string()); auto topics_and_types = reader.get_all_topics_and_types(); auto topic_it = std::find_if( topics_and_types.begin(), topics_and_types.end(), @@ -192,15 +192,15 @@ class RecordFixture : public ParametrizedTemporaryDirectoryFixture rosbag2_storage::BagMetadata metadata{}; metadata.storage_identifier = rosbag2_storage::get_default_storage_id(); for (int i = 0; i <= expected_splits; i++) { - rcpputils::fs::path bag_file_path; + std::filesystem::path bag_file_path; if (!compression_format.empty()) { bag_file_path = get_bag_file_path(i); } else { bag_file_path = get_compressed_bag_file_path(i); } - if (rcpputils::fs::exists(bag_file_path)) { - metadata.relative_file_paths.push_back(bag_file_path.string()); + if (std::filesystem::exists(bag_file_path)) { + metadata.relative_file_paths.push_back(bag_file_path.generic_string()); } } metadata.duration = std::chrono::nanoseconds(0); @@ -211,7 +211,7 @@ class RecordFixture : public ParametrizedTemporaryDirectoryFixture metadata.compression_format = compression_format; rosbag2_storage::MetadataIo metadata_io; - metadata_io.write_metadata(root_bag_path_.string(), metadata); + metadata_io.write_metadata(root_bag_path_.generic_string(), metadata); #else (void)expected_splits; (void)compression_format; @@ -220,7 +220,7 @@ class RecordFixture : public ParametrizedTemporaryDirectoryFixture } // relative path to the root of the bag file. - rcpputils::fs::path root_bag_path_; + std::filesystem::path root_bag_path_; MemoryManagement memory_management_; }; diff --git a/rosbag2_tests/test/rosbag2_tests/test_reindexer.cpp b/rosbag2_tests/test/rosbag2_tests/test_reindexer.cpp index 69b7582e8a..42a7d9c0c5 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_reindexer.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_reindexer.cpp @@ -23,6 +23,7 @@ #include #include +#include #include #include #include @@ -30,7 +31,6 @@ #include "rclcpp/rclcpp.hpp" #include "rcpputils/asserts.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "rosbag2_cpp/readers/sequential_reader.hpp" #include "rosbag2_cpp/reindexer.hpp" @@ -49,6 +49,7 @@ using namespace testing; // NOLINT using namespace rosbag2_test_common; // NOLINT +namespace fs = std::filesystem; class ReindexTestFixture : public ParametrizedTemporaryDirectoryFixture { @@ -56,12 +57,12 @@ class ReindexTestFixture : public ParametrizedTemporaryDirectoryFixture void SetUp() override { auto bag_name = get_test_name() + "_" + GetParam(); - root_bag_path_ = rcpputils::fs::path(temporary_dir_path_) / bag_name; + root_bag_path_ = fs::path(temporary_dir_path_) / bag_name; } void TearDown() override { - rcpputils::fs::remove_all(root_bag_path_); + fs::remove_all(root_bag_path_); } std::string get_test_name() const @@ -104,11 +105,11 @@ class ReindexTestFixture : public ParametrizedTemporaryDirectoryFixture } rosbag2_storage::MetadataIo metadata_io; - original_metadata_ = metadata_io.read_metadata(root_bag_path_.string()); - rcpputils::fs::remove(root_bag_path_ / "metadata.yaml"); + original_metadata_ = metadata_io.read_metadata(root_bag_path_.generic_string()); + fs::remove(root_bag_path_ / "metadata.yaml"); } - rcpputils::fs::path root_bag_path_; + fs::path root_bag_path_; rosbag2_storage::BagMetadata original_metadata_; }; diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_api.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_api.cpp index 8ec6de1ce0..273543b0ee 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_api.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_api.cpp @@ -14,6 +14,7 @@ #include +#include #include #include #include @@ -22,7 +23,6 @@ #include "rclcpp/serialization.hpp" #include "rclcpp/serialized_message.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "rcutils/time.h" #include "rosbag2_cpp/reader.hpp" @@ -36,6 +36,8 @@ using namespace ::testing; // NOLINT +namespace fs = std::filesystem; + class TestRosbag2CPPAPI : public Test, public WithParamInterface {}; @@ -49,9 +51,9 @@ TEST_P(TestRosbag2CPPAPI, minimal_writer_example) rclcpp::Serialization serialization; serialization.serialize_message(&test_msg, &serialized_msg); - auto rosbag_directory = rcpputils::fs::path("test_rosbag2_writer_api_bag"); + auto rosbag_directory = fs::path("test_rosbag2_writer_api_bag"); // in case the bag was previously not cleaned up - rcpputils::fs::remove_all(rosbag_directory); + fs::remove_all(rosbag_directory); { rosbag2_cpp::Writer writer; @@ -137,7 +139,7 @@ TEST_P(TestRosbag2CPPAPI, minimal_writer_example) } // remove the rosbag again after the test - EXPECT_TRUE(rcpputils::fs::remove_all(rosbag_directory)); + EXPECT_TRUE(fs::remove_all(rosbag_directory)); } INSTANTIATE_TEST_SUITE_P( diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp index 2b8e2d6e68..3112b0b066 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_cpp_get_service_info.cpp @@ -33,6 +33,8 @@ #include "test_msgs/msg/basic_types.hpp" #include "test_msgs/srv/basic_types.hpp" +namespace fs = std::filesystem; + class SequentialWriterForTest : public rosbag2_cpp::writers::SequentialWriter { public: @@ -53,17 +55,17 @@ class Rosbag2CPPGetServiceInfoTest void SetUp() override { auto bag_name = get_test_name() + "_" + GetParam(); - root_bag_path_ = std::filesystem::path(temporary_dir_path_) / bag_name; + root_bag_path_ = fs::path(temporary_dir_path_) / bag_name; // Clean up potentially leftover bag files. // There may be leftovers if the system reallocates a temp directory // used by a previous test execution and the test did not have a clean exit. - std::filesystem::remove_all(root_bag_path_); + fs::remove_all(root_bag_path_); } void TearDown() override { - std::filesystem::remove_all(root_bag_path_); + fs::remove_all(root_bag_path_); } static void SetUpTestCase() @@ -143,7 +145,7 @@ class Rosbag2CPPGetServiceInfoTest } // relative path to the root of the bag file. - std::filesystem::path root_bag_path_; + fs::path root_bag_path_; std::future node_spinner_future_; std::atomic_bool exit_from_node_spinner_{false}; }; diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp index cd5f0a41c0..2d193f3b0f 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_info_end_to_end.cpp @@ -15,23 +15,24 @@ #include #include +#include #include #include -#include "rcpputils/filesystem_helper.hpp" - #include "rosbag2_test_common/process_execution_helpers.hpp" #include "rosbag2_test_common/tested_storage_ids.hpp" using namespace ::testing; // NOLINT +namespace fs = std::filesystem; + class InfoEndToEndTestFixture : public Test, public WithParamInterface { public: InfoEndToEndTestFixture() { // _SRC_RESOURCES_DIR_PATH defined in CMakeLists.txt - bags_path_ = (rcpputils::fs::path(_SRC_RESOURCES_DIR_PATH) / GetParam()).string(); + bags_path_ = (fs::path(_SRC_RESOURCES_DIR_PATH) / GetParam()).generic_string(); } std::string bags_path_; diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_play_end_to_end.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_play_end_to_end.cpp index de3ce26812..2b9ea1004e 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_play_end_to_end.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_play_end_to_end.cpp @@ -15,6 +15,7 @@ #include #include +#include #include #include #include @@ -31,6 +32,8 @@ using namespace ::testing; // NOLINT using namespace rosbag2_test_common; // NOLINT +namespace fs = std::filesystem; + class PlayEndToEndTestFixture : public Test, public WithParamInterface { public: @@ -42,7 +45,7 @@ class PlayEndToEndTestFixture : public Test, public WithParamInterface(); client_node_ = std::make_shared("test_record_client"); cli_resume_ = client_node_->create_client("/rosbag2_player/resume"); diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp index 74277e4965..5d059cf4b4 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_record_end_to_end.cpp @@ -14,14 +14,13 @@ #include +#include #include #include #include #include "rclcpp/rclcpp.hpp" -#include "rcpputils/filesystem_helper.hpp" #include "rcpputils/scope_exit.hpp" -#include "rcutils/filesystem.h" #include "rosbag2_compression_zstd/zstd_decompressor.hpp" #include "rosbag2_storage/metadata_io.hpp" #include "rosbag2_test_common/publication_manager.hpp" @@ -30,6 +29,8 @@ #include "record_fixture.hpp" +namespace fs = std::filesystem; + namespace { /** @@ -96,18 +97,19 @@ TEST_P(RecordFixture, record_end_to_end_test_with_zstd_file_compression) { const auto compressed_bag_file_path = get_compressed_bag_file_path(0); - ASSERT_TRUE(compressed_bag_file_path.exists()) << + ASSERT_TRUE(fs::exists(compressed_bag_file_path)) << "Expected compressed bag file path: \"" << - compressed_bag_file_path.string() << "\" to exist!"; + compressed_bag_file_path.generic_string() << "\" to exist!"; rosbag2_compression_zstd::ZstdDecompressor decompressor; - const auto decompressed_uri = decompressor.decompress_uri(compressed_bag_file_path.string()); - const auto bag_path = get_bag_file_path(0).string(); + const auto decompressed_uri = decompressor.decompress_uri( + compressed_bag_file_path.generic_string()); + const auto bag_path = get_bag_file_path(0).generic_string(); ASSERT_EQ(decompressed_uri, bag_path) << "Expected decompressed URI to be same as uncompressed bag file path!"; - ASSERT_TRUE(rcpputils::fs::exists(bag_path)) << + ASSERT_TRUE(fs::exists(bag_path)) << "Expected decompressed first bag file to exist!"; auto test_topic_messages = get_messages_for_topic( @@ -258,7 +260,7 @@ TEST_P(RecordFixture, record_end_to_end_with_splitting_metadata_contains_all_top wait_for_metadata(); rosbag2_storage::MetadataIo metadataIo; - const auto metadata = metadataIo.read_metadata(root_bag_path_.string()); + const auto metadata = metadataIo.read_metadata(root_bag_path_.generic_string()); // Verify at least 2 topics are in the metadata. // There may be more if the test system is noisy. EXPECT_GT(metadata.topics_with_message_count.size(), 1u); @@ -310,7 +312,7 @@ TEST_P(RecordFixture, record_end_to_end_with_splitting_bagsize_split_is_at_least finalize_metadata_kludge(expected_splits); wait_for_metadata(); rosbag2_storage::MetadataIo metadata_io; - const auto metadata = metadata_io.read_metadata(root_bag_path_.string()); + const auto metadata = metadata_io.read_metadata(root_bag_path_.generic_string()); const auto actual_splits = static_cast(metadata.files.size()); // TODO(zmichaels11): Support reliable sync-to-disk for more accurate splits. @@ -320,11 +322,11 @@ TEST_P(RecordFixture, record_end_to_end_with_splitting_bagsize_split_is_at_least // Don't include the last bagfile since it won't be full for (int i = 0; i < actual_splits - 1; ++i) { - const auto bagfile_path = root_bag_path_ / rcpputils::fs::path{metadata.files[i].path}; - ASSERT_TRUE(bagfile_path.exists()) << - "Expected bag file: \"" << bagfile_path.string() << "\" to exist."; + const auto bagfile_path = root_bag_path_ / fs::path{metadata.files[i].path}; + ASSERT_TRUE(fs::exists(bagfile_path)) << + "Expected bag file: \"" << bagfile_path.generic_string() << "\" to exist."; - const auto actual_split_size = static_cast(bagfile_path.file_size()); + const auto actual_split_size = static_cast(fs::file_size(bagfile_path)); // Actual size is guaranteed to be >= bagfile_split size EXPECT_LT(bagfile_split_size, actual_split_size); } @@ -365,18 +367,18 @@ TEST_P(RecordFixture, record_end_to_end_with_splitting_max_size_not_reached) { finalize_metadata_kludge(); wait_for_metadata(); rosbag2_storage::MetadataIo metadata_io; - const auto metadata = metadata_io.read_metadata(root_bag_path_.string()); + const auto metadata = metadata_io.read_metadata(root_bag_path_.generic_string()); // Check that there's only 1 bagfile and that it exists. ASSERT_EQ(1u, metadata.files.size()); - const auto bagfile_path = root_bag_path_ / rcpputils::fs::path{metadata.files[0].path}; - ASSERT_TRUE(bagfile_path.exists()) << - "Expected bag file: \"" << bagfile_path.string() << "\" to exist."; + const auto bagfile_path = root_bag_path_ / fs::path{metadata.files[0].path}; + ASSERT_TRUE(fs::exists(bagfile_path)) << + "Expected bag file: \"" << bagfile_path.generic_string() << "\" to exist."; // Check that the next bagfile does not exist. const auto next_bag_file = get_bag_file_path(1); - EXPECT_FALSE(next_bag_file.exists()) << "Expected next bag file: \"" << - next_bag_file.string() << "\" to not exist!"; + EXPECT_FALSE(fs::exists(next_bag_file)) << "Expected next bag file: \"" << + next_bag_file.generic_string() << "\" to not exist!"; } TEST_P(RecordFixture, record_end_to_end_with_splitting_splits_bagfile) { @@ -415,13 +417,13 @@ TEST_P(RecordFixture, record_end_to_end_with_splitting_splits_bagfile) { wait_for_metadata(); finalize_metadata_kludge(expected_splits); rosbag2_storage::MetadataIo metadata_io; - const auto metadata = metadata_io.read_metadata(root_bag_path_.string()); + const auto metadata = metadata_io.read_metadata(root_bag_path_.generic_string()); ASSERT_GE(metadata.relative_file_paths.size(), 1u) << "Bagfile never split!"; for (const auto & file : metadata.files) { - auto path = root_bag_path_ / rcpputils::fs::path(file.path); - EXPECT_TRUE(rcpputils::fs::exists(path)); + auto path = root_bag_path_ / fs::path(file.path); + EXPECT_TRUE(fs::exists(path)); } } @@ -462,11 +464,11 @@ TEST_P(RecordFixture, record_end_to_end_with_duration_splitting_splits_bagfile) finalize_metadata_kludge(); wait_for_metadata(); rosbag2_storage::MetadataIo metadata_io; - const auto metadata = metadata_io.read_metadata(root_bag_path_.string()); + const auto metadata = metadata_io.read_metadata(root_bag_path_.generic_string()); for (const auto & file : metadata.files) { - auto path = root_bag_path_ / rcpputils::fs::path(file.path); - EXPECT_TRUE(rcpputils::fs::exists(path)); + auto path = root_bag_path_ / fs::path(file.path); + EXPECT_TRUE(fs::exists(path)); } } @@ -509,15 +511,15 @@ TEST_P(RecordFixture, record_end_to_end_test_with_zstd_file_compression_compress finalize_metadata_kludge(expected_splits); wait_for_metadata(); rosbag2_storage::MetadataIo metadata_io; - const auto metadata = metadata_io.read_metadata(root_bag_path_.string()); + const auto metadata = metadata_io.read_metadata(root_bag_path_.generic_string()); for (const auto & path : metadata.relative_file_paths) { - const auto file_path = root_bag_path_ / rcpputils::fs::path{path}; + const auto file_path = root_bag_path_ / fs::path{path}; - EXPECT_TRUE(file_path.exists()) << "File: \"" << - file_path.string() << "\" does not exist!"; - EXPECT_EQ(file_path.extension().string(), ".zstd") << "File :\"" << - file_path.string() << "\" does not have proper \".zstd\" extension!"; + EXPECT_TRUE(fs::exists(file_path)) << "File: \"" << + file_path.generic_string() << "\" does not exist!"; + EXPECT_EQ(file_path.extension().generic_string(), ".zstd") << "File :\"" << + file_path.generic_string() << "\" does not have proper \".zstd\" extension!"; } } @@ -645,7 +647,7 @@ TEST_P(RecordFixture, rosbag2_record_and_play_multiple_topics_with_filter) { auto sub_future = sub->spin_subscriptions(); std::stringstream command_play; - command_play << "ros2 bag play " << root_bag_path_.string() << " --topics " << + command_play << "ros2 bag play " << root_bag_path_.generic_string() << " --topics " << second_topic_name; int exit_code = execute_and_wait_until_completion(command_play.str(), "."); diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_storage_api.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_storage_api.cpp index 2ca5f65be4..dff1275a7b 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_storage_api.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_storage_api.cpp @@ -29,6 +29,8 @@ using namespace std::chrono_literals; // NOLINT using namespace ::testing; // NOLINT using namespace rosbag2_test_common; // NOLINT +namespace fs = std::filesystem; + class Rosbag2StorageAPITests : public rosbag2_test_common::ParametrizedTemporaryDirectoryFixture { public: @@ -40,17 +42,17 @@ class Rosbag2StorageAPITests : public rosbag2_test_common::ParametrizedTemporary void SetUp() override { auto bag_name = get_test_name() + "_" + GetParam(); - root_bag_path_ = std::filesystem::path(temporary_dir_path_) / bag_name; + root_bag_path_ = fs::path(temporary_dir_path_) / bag_name; // Clean up potentially leftover bag files. // There may be leftovers if the system reallocates a temp directory // used by a previous test execution and the test did not have a clean exit. - std::filesystem::remove_all(root_bag_path_); + fs::remove_all(root_bag_path_); } void TearDown() override { - std::filesystem::remove_all(root_bag_path_); + fs::remove_all(root_bag_path_); } static std::string get_test_name() @@ -111,14 +113,14 @@ class Rosbag2StorageAPITests : public rosbag2_test_common::ParametrizedTemporary } } - std::filesystem::path root_bag_path_; + fs::path root_bag_path_; std::unique_ptr memory_management_; }; TEST_P(Rosbag2StorageAPITests, get_bagfile_size_read_write_interface) { const std::string FILE_EXTENSION = (GetParam() == "mcap") ? ".mcap" : ".db3"; - std::filesystem::path full_bagfile_path = root_bag_path_; + fs::path full_bagfile_path = root_bag_path_; full_bagfile_path.replace_extension(FILE_EXTENSION); rosbag2_storage::StorageFactory factory{}; @@ -136,7 +138,7 @@ TEST_P(Rosbag2StorageAPITests, get_bagfile_size_read_write_interface) rw_storage->write(serialized_messages); uint64_t storage_bagfile_size = rw_storage->get_bagfile_size(); - size_t fs_bagfile_size = std::filesystem::file_size(full_bagfile_path); + size_t fs_bagfile_size = fs::file_size(full_bagfile_path); auto tolerance = static_cast(fs_bagfile_size * 0.001); // tolerance = 0.1% size_t filesize_difference = @@ -150,7 +152,7 @@ TEST_P(Rosbag2StorageAPITests, get_bagfile_size_read_write_interface) rw_storage->write(serialized_messages); storage_bagfile_size = rw_storage->get_bagfile_size(); - fs_bagfile_size = std::filesystem::file_size(full_bagfile_path); + fs_bagfile_size = fs::file_size(full_bagfile_path); tolerance = static_cast(fs_bagfile_size * 0.001); // tolerance = 0.1% filesize_difference = diff --git a/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp b/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp index 0efd3a1654..70826d4189 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_composable_player.cpp @@ -31,6 +31,8 @@ using namespace std::chrono_literals; // NOLINT using namespace ::testing; // NOLINT +namespace fs = std::filesystem; + class ComposablePlayerTests : public ::testing::Test, public WithParamInterface { @@ -128,7 +130,7 @@ TEST_P(ComposablePlayerTests, player_can_parse_parameters_from_file) { "play.qos_profile_overrides_path", _SRC_RESOURCES_DIR_PATH "/qos_profile_overrides.yaml"); opts.append_parameter_override("storage.storage_id", GetParam()); - const std::string uri_str = (std::filesystem::path( + const std::string uri_str = (fs::path( _SRC_RESOURCES_DIR_PATH) / GetParam() / "test_bag_for_seek").generic_string(); opts.append_parameter_override("storage.uri", uri_str); @@ -181,7 +183,7 @@ TEST_P(ComposablePlayerIntegrationTests, player_can_automatically_play_file_afte load_node_request->package_name = "rosbag2_transport"; load_node_request->plugin_name = "rosbag2_transport::Player"; - const std::string uri_str = (std::filesystem::path( + const std::string uri_str = (fs::path( _SRC_RESOURCES_DIR_PATH) / GetParam() / "test_bag_for_seek").generic_string(); rclcpp::Parameter uri("storage.uri", rclcpp::ParameterValue(uri_str)); rclcpp::Parameter start_paused("play.start_paused", rclcpp::ParameterValue(true)); diff --git a/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp b/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp index ab66a183e5..1877bbc91a 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_composable_recorder.cpp @@ -30,6 +30,8 @@ using namespace std::chrono_literals; // NOLINT using namespace ::testing; // NOLINT using namespace rosbag2_test_common; // NOLINT +namespace fs = std::filesystem; + class ComposableRecorderIntegrationTests : public CompositionManagerTestFixture { public: @@ -41,15 +43,15 @@ class ComposableRecorderIntegrationTests : public CompositionManagerTestFixture return bag_file_name.str(); } - std::filesystem::path get_bag_file_path(int split_index) + fs::path get_bag_file_path(int split_index) { return root_bag_path_ / get_relative_bag_file_path(split_index); } - std::filesystem::path get_relative_bag_file_path(int split_index) const + fs::path get_relative_bag_file_path(int split_index) const { const auto storage_id = GetParam(); - return std::filesystem::path( + return fs::path( rosbag2_test_common::bag_filename_for_storage_id(get_bag_file_name(split_index), storage_id)); } @@ -74,12 +76,12 @@ class ComposableRecorderIntegrationTests : public CompositionManagerTestFixture const auto storage_path = get_bag_file_path(0); const auto start_time = std::chrono::steady_clock::now(); while (std::chrono::steady_clock::now() - start_time < timeout && rclcpp::ok()) { - if (std::filesystem::exists(storage_path)) { + if (fs::exists(storage_path)) { return; } std::this_thread::sleep_for(50ms); // wait a bit to not query constantly } - ASSERT_EQ(std::filesystem::exists(storage_path), true) + ASSERT_EQ(fs::exists(storage_path), true) << "Could not find storage file: \"" << storage_path.generic_string() << "\""; } @@ -113,18 +115,18 @@ class ComposableRecorderTests { rclcpp::init(0, nullptr); auto bag_name = get_test_name() + "_" + GetParam(); - root_bag_path_ = std::filesystem::path(temporary_dir_path_) / bag_name; + root_bag_path_ = fs::path(temporary_dir_path_) / bag_name; // Clean up potentially leftover bag files. // There may be leftovers if the system reallocates a temp directory // used by a previous test execution and the test did not have a clean exit. - std::filesystem::remove_all(root_bag_path_); + fs::remove_all(root_bag_path_); } void TearDown() override { rclcpp::shutdown(); - std::filesystem::remove_all(root_bag_path_); + fs::remove_all(root_bag_path_); } std::string get_test_name() const @@ -136,7 +138,7 @@ class ComposableRecorderTests return test_name; } - std::filesystem::path root_bag_path_; + fs::path root_bag_path_; }; class MockComposableRecorder : public rosbag2_transport::Recorder diff --git a/rosbag2_transport/test/rosbag2_transport/test_load_composable_components.cpp b/rosbag2_transport/test/rosbag2_transport/test_load_composable_components.cpp index 10829e46b7..db6c554dc3 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_load_composable_components.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_load_composable_components.cpp @@ -19,6 +19,8 @@ using namespace std::chrono_literals; // NOLINT +namespace fs = std::filesystem; + TEST_P(CompositionManagerTestFixture, test_load_play_component) { std::string path{_SRC_RESOURCES_DIR_PATH "/player_node_params.yaml"}; @@ -34,7 +36,7 @@ TEST_P(CompositionManagerTestFixture, test_load_play_component) rclcpp::Parameter qos_profile_overrides_path("play.qos_profile_overrides_path", rclcpp::ParameterValue(_SRC_RESOURCES_DIR_PATH "/qos_profile_overrides.yaml")); - const std::string uri_str = (std::filesystem::path( + const std::string uri_str = (fs::path( _SRC_RESOURCES_DIR_PATH) / GetParam() / "test_bag_for_seek").generic_string(); rclcpp::Parameter uri("storage.uri", rclcpp::ParameterValue(uri_str)); rclcpp::Parameter storage_id("storage.storage_id", GetParam()); diff --git a/rosbag2_transport/test/rosbag2_transport/test_play_seek.cpp b/rosbag2_transport/test/rosbag2_transport/test_play_seek.cpp index f0d482b478..65359904e1 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play_seek.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play_seek.cpp @@ -15,6 +15,7 @@ #include #include +#include #include #include #include @@ -33,6 +34,8 @@ using namespace ::testing; // NOLINT using namespace rosbag2_transport; // NOLINT using namespace rosbag2_test_common; // NOLINT +namespace fs = std::filesystem; + class RosBag2PlaySeekTestFixture : public RosBag2PlayTestFixture, public WithParamInterface @@ -44,8 +47,8 @@ class RosBag2PlaySeekTestFixture topic_types_ = std::vector{ {1u, "topic1", "test_msgs/BasicTypes", rmw_get_serialization_format(), {}, ""}}; - const rcpputils::fs::path base{_SRC_RESOURCES_DIR_PATH}; - const rcpputils::fs::path bag_path = base / GetParam() / "test_bag_for_seek"; + const fs::path base{_SRC_RESOURCES_DIR_PATH}; + const fs::path bag_path = base / GetParam() / "test_bag_for_seek"; storage_options_ = rosbag2_storage::StorageOptions({bag_path.string(), "", 0, 0, 0}); play_options_.read_ahead_queue_size = 2; diff --git a/rosbag2_transport/test/rosbag2_transport/test_rewrite.cpp b/rosbag2_transport/test/rosbag2_transport/test_rewrite.cpp index 8086787c5e..6cbf911fac 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_rewrite.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_rewrite.cpp @@ -14,17 +14,18 @@ #include +#include #include #include #include -#include "rcpputils/filesystem_helper.hpp" #include "rosbag2_test_common/tested_storage_ids.hpp" #include "rosbag2_transport/bag_rewrite.hpp" #include "rosbag2_transport/reader_writer_factory.hpp" using namespace ::testing; // NOLINT +namespace fs = std::filesystem; /* Builtin knowledge about the bags under test: @@ -51,10 +52,11 @@ class TestRewrite : public Test, public WithParamInterface { public: TestRewrite() - : output_dir_(rcpputils::fs::create_temp_directory("test_bag_rewrite")) { + auto tmp_dir = rcpputils::fs::create_temp_directory("test_bag_rewrite"); + output_dir_ = fs::path(tmp_dir.string()); storage_id_ = GetParam(); - bags_path_ = rcpputils::fs::path{_SRC_RESOURCES_DIR_PATH} / storage_id_; + bags_path_ = fs::path(_SRC_RESOURCES_DIR_PATH) / storage_id_; } void use_input_a() @@ -75,11 +77,11 @@ class TestRewrite : public Test, public WithParamInterface ~TestRewrite() { - // rcpputils::fs::remove_all(output_dir_); + fs::remove_all(output_dir_); } - const rcpputils::fs::path output_dir_; - rcpputils::fs::path bags_path_{_SRC_RESOURCES_DIR_PATH}; + fs::path output_dir_; + fs::path bags_path_{_SRC_RESOURCES_DIR_PATH}; std::string storage_id_; std::vector input_bags_; std::vector> @@ -244,8 +246,8 @@ TEST_P(TestRewrite, test_compress) { auto first_storage = out_bag / metadata.relative_file_paths[0]; EXPECT_EQ(first_storage.extension().string(), ".zstd"); - EXPECT_TRUE(first_storage.exists()); - EXPECT_TRUE(first_storage.is_regular_file()); + EXPECT_TRUE(fs::exists(first_storage)); + EXPECT_TRUE(fs::is_regular_file(first_storage)); } INSTANTIATE_TEST_SUITE_P(