Skip to content

Commit

Permalink
Address merge conflicts
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Orlov <[email protected]>
  • Loading branch information
MichaelOrlov committed Jun 13, 2023
1 parent 632ffd7 commit 208b862
Show file tree
Hide file tree
Showing 2 changed files with 1 addition and 31 deletions.
21 changes: 1 addition & 20 deletions rosbag2_py/src/rosbag2_py/_transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -211,22 +211,9 @@ class Recorder
std::mutex wait_for_exit_mutex_;
};

<<<<<<< HEAD
=======
std::atomic_bool Recorder::exit_{false};
std::condition_variable Recorder::wait_for_exit_cv_{};

// Return a RecordOptions struct with defaults set for rewriting bags.
rosbag2_transport::RecordOptions bag_rewrite_default_record_options()
{
rosbag2_transport::RecordOptions options{};
// We never want to drop messages when converting bags, so set the compression queue size to 0
// (unbounded).
options.compression_queue_size = 0;
return options;
}

>>>>>>> 46a23e9 (Gracefully handle SIGINT and SIGTERM in rosbag2 recorder (#1301))
// Simple wrapper to read the output config YAML into structs
void bag_rewrite(
const std::vector<rosbag2_storage::StorageOptions> & input_options,
Expand Down Expand Up @@ -323,15 +310,9 @@ PYBIND11_MODULE(_transport, m) {

py::class_<rosbag2_py::Recorder>(m, "Recorder")
.def(py::init())
<<<<<<< HEAD
.def("record", &rosbag2_py::Recorder::record)
.def("cancel", &rosbag2_py::Recorder::cancel)
=======
.def(
"record", &rosbag2_py::Recorder::record, py::arg("storage_options"), py::arg("record_options"),
py::arg("node_name") = "rosbag2_recorder")
"record", &rosbag2_py::Recorder::record, py::arg("storage_options"), py::arg("record_options"))
.def_static("cancel", &rosbag2_py::Recorder::cancel)
>>>>>>> 46a23e9 (Gracefully handle SIGINT and SIGTERM in rosbag2 recorder (#1301))
;

m.def(
Expand Down
11 changes: 0 additions & 11 deletions rosbag2_py/test/test_transport.py
Original file line number Diff line number Diff line change
Expand Up @@ -81,19 +81,8 @@ def test_record_cancel(tmp_path):

recorder.cancel()

<<<<<<< HEAD
metadata_path = Path(bag_path) / 'metadata.yaml'
db3_path = Path(bag_path) / 'test_record_cancel_0.db3'
assert wait_for(lambda: metadata_path.is_file() and db3_path.is_file(),
=======
metadata_io = rosbag2_py.MetadataIo()
assert wait_for(lambda: metadata_io.metadata_file_exists(bag_path),
timeout=rclpy.duration.Duration(seconds=3))
record_thread.join()

metadata = metadata_io.read_metadata(bag_path)
assert(len(metadata.relative_file_paths))
storage_path = Path(metadata.relative_file_paths[0])
assert wait_for(lambda: storage_path.is_file(),
>>>>>>> 46a23e9 (Gracefully handle SIGINT and SIGTERM in rosbag2 recorder (#1301))
timeout=rclpy.duration.Duration(seconds=3))

0 comments on commit 208b862

Please sign in to comment.