Skip to content

Commit 7986ede

Browse files
committed
Change type for snapshot_duration to the rclcpp::Duration
Signed-off-by: Michael Orlov <[email protected]>
1 parent a126442 commit 7986ede

File tree

7 files changed

+65
-20
lines changed

7 files changed

+65
-20
lines changed

Diff for: ros2bag/ros2bag/verb/record.py

+4-3
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818

1919
from rclpy.qos import InvalidQoSProfileException
2020
from ros2bag.api import add_writer_storage_plugin_extensions
21+
from ros2bag.api import check_not_negative_float
2122
from ros2bag.api import convert_service_to_service_event_topic
2223
from ros2bag.api import convert_yaml_to_qos_profile
2324
from ros2bag.api import print_error
@@ -177,8 +178,8 @@ def add_recorder_arguments(parser: ArgumentParser) -> None:
177178
'the "/rosbag2_recorder/snapshot" service is called. e.g. \n '
178179
'ros2 service call /rosbag2_recorder/snapshot rosbag2_interfaces/Snapshot')
179180
parser.add_argument(
180-
'--snapshot-duration', type=int, default=0,
181-
help='Maximum snapshot duration in milliseconds.\n'
181+
'--snapshot-duration', type=check_not_negative_float, default=0.0,
182+
help='Maximum snapshot duration in a fraction of seconds.\n'
182183
'Default: %(default)d, indicates that the snapshot will be limited by the'
183184
' --max-cache-size parameter only. If the value is more than 0, the cyclic buffer'
184185
' for the snapshot will be limited by both the series of messages duration and the'
@@ -290,7 +291,7 @@ def validate_parsed_arguments(args, uri) -> str:
290291
if args.compression_queue_size < 0:
291292
return print_error('Compression queue size must be at least 0.')
292293

293-
if args.snapshot_mode and args.snapshot_duration == 0 and args.max_cache_size == 0:
294+
if args.snapshot_mode and args.snapshot_duration == 0.0 and args.max_cache_size == 0:
294295
return print_error('In snapshot mode, either the snapshot_duration or max_bytes_size shall'
295296
' not be set to zero.')
296297

Diff for: rosbag2_cpp/src/rosbag2_cpp/writers/sequential_writer.cpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -146,7 +146,7 @@ void SequentialWriter::open(
146146
}
147147

148148
use_cache_ = storage_options.max_cache_size > 0u ||
149-
(storage_options.snapshot_mode && storage_options.snapshot_duration > 0);
149+
(storage_options.snapshot_mode && storage_options.snapshot_duration.nanoseconds() > 0);
150150
if (storage_options.snapshot_mode && !use_cache_) {
151151
throw std::runtime_error(
152152
"Either the max cache size or the maximum snapshot duration must be greater than 0"
@@ -155,9 +155,8 @@ void SequentialWriter::open(
155155

156156
if (use_cache_) {
157157
if (storage_options.snapshot_mode) {
158-
int64_t max_buffer_duration_ns = storage_options.snapshot_duration * 1000000;
159158
message_cache_ = std::make_shared<rosbag2_cpp::cache::CircularMessageCache>(
160-
storage_options.max_cache_size, max_buffer_duration_ns);
159+
storage_options.max_cache_size, storage_options.snapshot_duration.nanoseconds());
161160
} else {
162161
message_cache_ = std::make_shared<rosbag2_cpp::cache::MessageCache>(
163162
storage_options.max_cache_size);

Diff for: rosbag2_py/rosbag2_py/_storage.pyi

+2-2
Original file line numberDiff line numberDiff line change
@@ -101,14 +101,14 @@ class StorageOptions:
101101
max_bagfile_duration: int
102102
max_bagfile_size: int
103103
max_cache_size: int
104-
snapshot_duration: int
104+
snapshot_duration: float
105105
snapshot_mode: bool
106106
start_time_ns: int
107107
storage_config_uri: str
108108
storage_id: str
109109
storage_preset_profile: str
110110
uri: str
111-
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 = ..., snapshot_duration: int = ..., start_time_ns: int = ..., end_time_ns: int = ..., custom_data: Dict[str, str] = ...) -> None: ...
111+
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 = ..., snapshot_duration: Duration = ..., start_time_ns: int = ..., end_time_ns: int = ..., custom_data: Dict[str, str] = ...) -> None: ...
112112

113113
class TopicInformation:
114114
message_count: int

Diff for: rosbag2_py/src/rosbag2_py/_storage.cpp

+50-7
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
// limitations under the License.
1414

1515
#include <string>
16+
#include <utility>
1617
#include <vector>
1718

1819
#include "rosbag2_cpp/converter_options.hpp"
@@ -44,6 +45,16 @@ std::chrono::nanoseconds from_rclpy_duration(const pybind11::object & duration)
4445
return std::chrono::nanoseconds(nanos);
4546
}
4647

48+
pybind11::object rclcpp_duration_to_py_float(const rclcpp::Duration & duration)
49+
{
50+
return pybind11::cast(duration.seconds());
51+
}
52+
53+
rclcpp::Duration py_float_to_rclcpp_duration(const pybind11::object & obj)
54+
{
55+
return rclcpp::Duration::from_seconds(obj.cast<double>());
56+
}
57+
4758
template<typename T>
4859
pybind11::object to_rclpy_time(T time)
4960
{
@@ -81,9 +92,36 @@ PYBIND11_MODULE(_storage, m) {
8192
using KEY_VALUE_MAP = std::unordered_map<std::string, std::string>;
8293
pybind11::class_<rosbag2_storage::StorageOptions>(m, "StorageOptions")
8394
.def(
84-
pybind11::init<
85-
std::string, std::string, uint64_t, uint64_t, uint64_t, std::string, std::string, bool,
86-
int64_t, int64_t, int64_t, KEY_VALUE_MAP>(),
95+
pybind11::init(
96+
[](
97+
std::string uri,
98+
std::string storage_id,
99+
uint64_t max_bagfile_size,
100+
uint64_t max_bagfile_duration,
101+
uint64_t max_cache_size,
102+
std::string storage_preset_profile,
103+
std::string storage_config_uri,
104+
bool snapshot_mode,
105+
const pybind11::object & snapshot_duration,
106+
int64_t start_time_ns,
107+
int64_t end_time_ns,
108+
KEY_VALUE_MAP custom_data)
109+
{
110+
return rosbag2_storage::StorageOptions{
111+
std::move(uri),
112+
std::move(storage_id),
113+
max_bagfile_size,
114+
max_bagfile_duration,
115+
max_cache_size,
116+
std::move(storage_preset_profile),
117+
std::move(storage_config_uri),
118+
snapshot_mode,
119+
py_float_to_rclcpp_duration(snapshot_duration),
120+
start_time_ns,
121+
end_time_ns,
122+
std::move(custom_data),
123+
};
124+
}),
87125
pybind11::arg("uri"),
88126
pybind11::arg("storage_id") = "",
89127
pybind11::arg("max_bagfile_size") = 0,
@@ -92,7 +130,7 @@ PYBIND11_MODULE(_storage, m) {
92130
pybind11::arg("storage_preset_profile") = "",
93131
pybind11::arg("storage_config_uri") = "",
94132
pybind11::arg("snapshot_mode") = false,
95-
pybind11::arg("snapshot_duration") = 0,
133+
pybind11::arg("snapshot_duration") = rclcpp_duration_to_py_float(rclcpp::Duration(0, 0)),
96134
pybind11::arg("start_time_ns") = -1,
97135
pybind11::arg("end_time_ns") = -1,
98136
pybind11::arg("custom_data") = KEY_VALUE_MAP{})
@@ -116,9 +154,14 @@ PYBIND11_MODULE(_storage, m) {
116154
.def_readwrite(
117155
"snapshot_mode",
118156
&rosbag2_storage::StorageOptions::snapshot_mode)
119-
.def_readwrite(
120-
"snapshot_duration",
121-
&rosbag2_storage::StorageOptions::snapshot_duration)
157+
.def_property(
158+
"snapshot_duration",
159+
[](const rosbag2_storage::StorageOptions & self) {
160+
return rclcpp_duration_to_py_float(self.snapshot_duration);
161+
},
162+
[](rosbag2_storage::StorageOptions & self, const pybind11::object & obj) {
163+
self.snapshot_duration = py_float_to_rclcpp_duration(obj);
164+
})
122165
.def_readwrite(
123166
"start_time_ns",
124167
&rosbag2_storage::StorageOptions::start_time_ns)

Diff for: rosbag2_storage/include/rosbag2_storage/storage_options.hpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include <string>
2020
#include <unordered_map>
2121

22+
#include "rclcpp/duration.hpp"
2223
#include "rosbag2_storage/visibility_control.hpp"
2324
#include "rosbag2_storage/yaml.hpp"
2425

@@ -56,9 +57,9 @@ struct StorageOptions
5657
// Defaults to disabled.
5758
bool snapshot_mode = false;
5859

59-
// The maximum snapshot duration in milliseconds.
60-
// A value of 0 indicates that snapshot will be limited by the max_cache_size only.
61-
int64_t snapshot_duration = 0;
60+
// The maximum snapshot duration.
61+
// A value of 0.0 indicates that snapshot will be limited by the max_cache_size only.
62+
rclcpp::Duration snapshot_duration{0, 0};
6263

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

Diff for: rosbag2_storage/src/rosbag2_storage/storage_options.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#include <string>
1616
#include <unordered_map>
1717

18+
#include "rclcpp/duration.hpp"
1819
#include "rosbag2_storage/storage_options.hpp"
1920

2021
namespace YAML
@@ -51,7 +52,7 @@ bool convert<rosbag2_storage::StorageOptions>::decode(
5152
node, "storage_preset_profile", storage_options.storage_preset_profile);
5253
optional_assign<std::string>(node, "storage_config_uri", storage_options.storage_config_uri);
5354
optional_assign<bool>(node, "snapshot_mode", storage_options.snapshot_mode);
54-
optional_assign<int64_t>(node, "snapshot_duration", storage_options.snapshot_duration);
55+
optional_assign<rclcpp::Duration>(node, "snapshot_duration", storage_options.snapshot_duration);
5556
optional_assign<int64_t>(node, "start_time_ns", storage_options.start_time_ns);
5657
optional_assign<int64_t>(node, "end_time_ns", storage_options.end_time_ns);
5758
using KEY_VALUE_MAP = std::unordered_map<std::string, std::string>;

Diff for: rosbag2_storage/test/rosbag2_storage/test_storage_options.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ TEST(storage_options, test_yaml_serialization)
2929
original.storage_preset_profile = "profile";
3030
original.storage_config_uri = "config_uri";
3131
original.snapshot_mode = true;
32-
original.snapshot_duration = 1500;
32+
original.snapshot_duration = rclcpp::Duration::from_seconds(1.5);
3333
original.start_time_ns = 12345000;
3434
original.end_time_ns = 23456000;
3535
original.custom_data["key1"] = "value1";

0 commit comments

Comments
 (0)