Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ros2 bag convert now excludes messages not in [start_time;end_time] #1455

Merged
merged 14 commits into from
Sep 28, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -117,6 +117,7 @@ class ROSBAG2_CPP_PUBLIC SequentialWriter

/**
* Write a message to a bagfile. The topic needs to have been created before writing is possible.
* Only writes message if within start_time_ns and end_time_ns (from storage_options).
*
* \param message to be written to the bagfile
* \throws runtime_error if the Writer is not open.
Expand Down Expand Up @@ -174,6 +175,10 @@ class ROSBAG2_CPP_PUBLIC SequentialWriter
bool should_split_bagfile(
const std::chrono::time_point<std::chrono::high_resolution_clock> & current_time) const;

// Checks if the message to be written is within accepted time range
bool message_within_accepted_time_range(
const rcutils_time_point_value_t current_time) const;

// Prepares the metadata by setting initial values.
virtual void init_metadata();

Expand Down
22 changes: 22 additions & 0 deletions rosbag2_cpp/src/rosbag2_cpp/writers/sequential_writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -340,6 +340,10 @@ void SequentialWriter::write(std::shared_ptr<const rosbag2_storage::SerializedBa
throw std::runtime_error("Bag is not open. Call open() before writing.");
}

if (!message_within_accepted_time_range(message->time_stamp)) {
return;
}

// Get TopicInformation handler for counting messages.
rosbag2_storage::TopicInformation * topic_information {nullptr};
try {
Expand Down Expand Up @@ -432,6 +436,24 @@ bool SequentialWriter::should_split_bagfile(
return should_split;
}

bool SequentialWriter::message_within_accepted_time_range(
const rcutils_time_point_value_t current_time) const
{
if (storage_options_.start_time_ns >= 0 &&
static_cast<int64_t>(current_time) < storage_options_.start_time_ns)
{
return false;
}

if (storage_options_.end_time_ns >= 0 &&
static_cast<int64_t>(current_time) > storage_options_.end_time_ns)
{
return false;
}

return true;
}

void SequentialWriter::finalize_metadata()
{
metadata_.bag_size = 0;
Expand Down
10 changes: 9 additions & 1 deletion rosbag2_py/src/rosbag2_py/_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ PYBIND11_MODULE(_storage, m) {
.def(
pybind11::init<
std::string, std::string, uint64_t, uint64_t, uint64_t, std::string, std::string, bool,
KEY_VALUE_MAP>(),
int64_t, int64_t, KEY_VALUE_MAP>(),
pybind11::arg("uri"),
pybind11::arg("storage_id") = "",
pybind11::arg("max_bagfile_size") = 0,
Expand All @@ -93,6 +93,8 @@ PYBIND11_MODULE(_storage, m) {
pybind11::arg("storage_preset_profile") = "",
pybind11::arg("storage_config_uri") = "",
pybind11::arg("snapshot_mode") = false,
pybind11::arg("start_time_ns") = -1,
pybind11::arg("end_time_ns") = -1,
pybind11::arg("custom_data") = KEY_VALUE_MAP{})
.def_readwrite("uri", &rosbag2_storage::StorageOptions::uri)
.def_readwrite("storage_id", &rosbag2_storage::StorageOptions::storage_id)
Expand All @@ -114,6 +116,12 @@ PYBIND11_MODULE(_storage, m) {
.def_readwrite(
"snapshot_mode",
&rosbag2_storage::StorageOptions::snapshot_mode)
.def_readwrite(
"start_time_ns",
&rosbag2_storage::StorageOptions::start_time_ns)
.def_readwrite(
"end_time_ns",
&rosbag2_storage::StorageOptions::end_time_ns)
.def_readwrite(
"custom_data",
&rosbag2_storage::StorageOptions::custom_data);
Expand Down
4 changes: 4 additions & 0 deletions rosbag2_storage/include/rosbag2_storage/storage_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,10 @@ struct StorageOptions
// Defaults to disabled.
bool snapshot_mode = false;

// Start and end time for cutting
int64_t start_time_ns = -1;
int64_t end_time_ns = -1;

pfavr2 marked this conversation as resolved.
Show resolved Hide resolved
// Stores the custom data
std::unordered_map<std::string, std::string> custom_data{};
};
Expand Down
4 changes: 4 additions & 0 deletions rosbag2_storage/src/rosbag2_storage/storage_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@ Node convert<rosbag2_storage::StorageOptions>::encode(
node["storage_preset_profile"] = storage_options.storage_preset_profile;
node["storage_config_uri"] = storage_options.storage_config_uri;
node["snapshot_mode"] = storage_options.snapshot_mode;
node["start_time_ns"] = storage_options.start_time_ns;
node["end_time_ns"] = storage_options.end_time_ns;
node["custom_data"] = storage_options.custom_data;
return node;
}
Expand All @@ -48,6 +50,8 @@ bool convert<rosbag2_storage::StorageOptions>::decode(
node, "storage_preset_profile", storage_options.storage_preset_profile);
optional_assign<std::string>(node, "storage_config_uri", storage_options.storage_config_uri);
optional_assign<bool>(node, "snapshot_mode", storage_options.snapshot_mode);
optional_assign<int64_t>(node, "start_time_ns", storage_options.start_time_ns);
optional_assign<int64_t>(node, "end_time_ns", storage_options.end_time_ns);
using KEY_VALUE_MAP = std::unordered_map<std::string, std::string>;
optional_assign<KEY_VALUE_MAP>(node, "custom_data", storage_options.custom_data);
return true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@ TEST(storage_options, test_yaml_serialization)
original.storage_preset_profile = "profile";
original.storage_config_uri = "config_uri";
original.snapshot_mode = true;
original.start_time_ns = 12345000;
original.end_time_ns = 23456000;
original.custom_data["key1"] = "value1";
original.custom_data["key2"] = "value2";

Expand All @@ -48,5 +50,7 @@ TEST(storage_options, test_yaml_serialization)
ASSERT_EQ(original.storage_preset_profile, reconstructed.storage_preset_profile);
ASSERT_EQ(original.storage_config_uri, reconstructed.storage_config_uri);
ASSERT_EQ(original.snapshot_mode, reconstructed.snapshot_mode);
ASSERT_EQ(original.start_time_ns, reconstructed.start_time_ns);
ASSERT_EQ(original.end_time_ns, reconstructed.end_time_ns);
ASSERT_EQ(original.custom_data, reconstructed.custom_data);
}
Loading