-
Notifications
You must be signed in to change notification settings - Fork 231
/
_transport.cpp
397 lines (349 loc) · 12.8 KB
/
_transport.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
// Copyright 2021 Amazon.com, Inc. or its affiliates. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <csignal>
#include <chrono>
#include <memory>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>
#include "rosbag2_storage/storage_options.hpp"
#include "rosbag2_storage/yaml.hpp"
#include "rosbag2_transport/bag_rewrite.hpp"
#include "rosbag2_transport/play_options.hpp"
#include "rosbag2_transport/player.hpp"
#include "rosbag2_transport/reader_writer_factory.hpp"
#include "rosbag2_transport/record_options.hpp"
#include "rosbag2_transport/recorder.hpp"
#include "./pybind11.hpp"
namespace py = pybind11;
typedef std::unordered_map<std::string, rclcpp::QoS> QoSMap;
namespace
{
rclcpp::QoS qos_from_handle(const py::handle source)
{
PyObject * raw_obj = PyObject_CallMethod(source.ptr(), "get_c_qos_profile", "");
const auto py_obj = py::cast<py::object>(raw_obj);
const auto rmw_qos_profile = py_obj.cast<rmw_qos_profile_t>();
const auto qos_init = rclcpp::QoSInitialization::from_rmw(rmw_qos_profile);
return rclcpp::QoS{qos_init, rmw_qos_profile};
}
QoSMap qos_map_from_py_dict(const py::dict & dict)
{
QoSMap value;
for (const auto & item : dict) {
auto key = std::string(py::str(item.first));
value.insert({key, qos_from_handle(item.second)});
}
return value;
}
/**
* Simple wrapper subclass to provide nontrivial type conversions for python properties.
*/
template<class T>
struct OptionsWrapper : public T
{
public:
void setDelay(double delay)
{
this->delay = rclcpp::Duration::from_nanoseconds(
static_cast<rcl_duration_value_t>(RCUTILS_S_TO_NS(delay)));
}
double getPlaybackDuration() const
{
return RCUTILS_NS_TO_S(static_cast<double>(this->playback_duration.nanoseconds()));
}
void setPlaybackDuration(double playback_duration)
{
this->playback_duration = rclcpp::Duration::from_nanoseconds(
static_cast<rcl_duration_value_t>(RCUTILS_S_TO_NS(playback_duration)));
}
double getDelay() const
{
return RCUTILS_NS_TO_S(static_cast<double>(this->delay.nanoseconds()));
}
void setStartOffset(double start_offset)
{
this->start_offset = static_cast<rcutils_time_point_value_t>(RCUTILS_S_TO_NS(start_offset));
}
double getStartOffset() const
{
return RCUTILS_NS_TO_S(static_cast<double>(this->start_offset));
}
void setPlaybackUntilTimestamp(int64_t playback_until_timestamp)
{
this->playback_until_timestamp =
static_cast<rcutils_time_point_value_t>(playback_until_timestamp);
}
int64_t getPlaybackUntilTimestamp() const
{
return this->playback_until_timestamp;
}
void setTopicQoSProfileOverrides(const py::dict & overrides)
{
py_dict = overrides;
this->topic_qos_profile_overrides = qos_map_from_py_dict(overrides);
}
const py::dict & getTopicQoSProfileOverrides() const
{
return py_dict;
}
py::dict py_dict;
};
typedef OptionsWrapper<rosbag2_transport::PlayOptions> PlayOptions;
typedef OptionsWrapper<rosbag2_transport::RecordOptions> RecordOptions;
} // namespace
namespace rosbag2_py
{
class Player
{
public:
Player()
{
rclcpp::init(0, nullptr);
}
virtual ~Player()
{
rclcpp::shutdown();
}
void play(
const rosbag2_storage::StorageOptions & storage_options,
PlayOptions & play_options)
{
auto reader = rosbag2_transport::ReaderWriterFactory::make_reader(storage_options);
auto player = std::make_shared<rosbag2_transport::Player>(
std::move(reader), storage_options, play_options);
rclcpp::executors::SingleThreadedExecutor exec;
exec.add_node(player);
auto spin_thread = std::thread(
[&exec]() {
exec.spin();
});
player->play();
exec.cancel();
spin_thread.join();
}
void burst(
const rosbag2_storage::StorageOptions & storage_options,
PlayOptions & play_options,
size_t num_messages)
{
auto reader = rosbag2_transport::ReaderWriterFactory::make_reader(storage_options);
auto player = std::make_shared<rosbag2_transport::Player>(
std::move(reader), storage_options, play_options);
rclcpp::executors::SingleThreadedExecutor exec;
exec.add_node(player);
auto spin_thread = std::thread(
[&exec]() {
exec.spin();
});
auto play_thread = std::thread(
[&player]() {
player->play();
});
player->burst(num_messages);
exec.cancel();
spin_thread.join();
play_thread.join();
}
};
class Recorder
{
public:
Recorder()
{
auto init_options = rclcpp::InitOptions();
init_options.shutdown_on_signal = false;
rclcpp::init(0, nullptr, init_options, rclcpp::SignalHandlerOptions::None);
std::signal(
SIGTERM, [](int /* signal */) {
rosbag2_py::Recorder::cancel();
});
std::signal(
SIGINT, [](int /* signal */) {
rosbag2_py::Recorder::cancel();
});
}
virtual ~Recorder()
{
rclcpp::shutdown();
}
void record(
const rosbag2_storage::StorageOptions & storage_options,
RecordOptions & record_options,
std::string & node_name)
{
exit_ = false;
auto exec = std::make_unique<rclcpp::executors::SingleThreadedExecutor>();
if (record_options.rmw_serialization_format.empty()) {
record_options.rmw_serialization_format = std::string(rmw_get_serialization_format());
}
auto writer = rosbag2_transport::ReaderWriterFactory::make_writer(record_options);
auto recorder = std::make_shared<rosbag2_transport::Recorder>(
std::move(writer), storage_options, record_options, node_name);
recorder->record();
exec->add_node(recorder);
// Run exec->spin() in a separate thread, because we need to call exec->cancel() after
// recorder->stop() to be able to send notifications about bag split and close.
auto spin_thread = std::thread(
[&exec]() {
exec->spin();
});
{
// Release the GIL for long-running record, so that calling Python code can use other threads
py::gil_scoped_release release;
std::unique_lock<std::mutex> lock(wait_for_exit_mutex_);
wait_for_exit_cv_.wait(lock, [] {return rosbag2_py::Recorder::exit_.load();});
recorder->stop();
}
exec->cancel();
if (spin_thread.joinable()) {
spin_thread.join();
}
exec->remove_node(recorder);
}
static void cancel()
{
exit_ = true;
wait_for_exit_cv_.notify_all();
}
protected:
static std::atomic_bool exit_;
static std::condition_variable wait_for_exit_cv_;
std::mutex wait_for_exit_mutex_;
};
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;
}
// Simple wrapper to read the output config YAML into structs
void bag_rewrite(
const std::vector<rosbag2_storage::StorageOptions> & input_options,
std::string output_config_file)
{
YAML::Node yaml_file = YAML::LoadFile(output_config_file);
auto bag_nodes = yaml_file["output_bags"];
if (!bag_nodes) {
throw std::runtime_error("Output bag config YAML file must have top-level key 'output_bags'");
}
if (!bag_nodes.IsSequence()) {
throw std::runtime_error(
"Top-level key 'output_bags' must contain a list of "
"StorageOptions/RecordOptions dicts.");
}
std::vector<
std::pair<rosbag2_storage::StorageOptions, rosbag2_transport::RecordOptions>> output_options;
for (const auto & bag_node : bag_nodes) {
rosbag2_storage::StorageOptions storage_options{};
YAML::convert<rosbag2_storage::StorageOptions>::decode(bag_node, storage_options);
rosbag2_transport::RecordOptions record_options = bag_rewrite_default_record_options();
YAML::convert<rosbag2_transport::RecordOptions>::decode(bag_node, record_options);
output_options.push_back(std::make_pair(storage_options, record_options));
}
rosbag2_transport::bag_rewrite(input_options, output_options);
}
} // namespace rosbag2_py
PYBIND11_MODULE(_transport, m) {
m.doc() = "Python wrapper of the rosbag2_transport API";
// NOTE: it is non-trivial to add a constructor for PlayOptions and RecordOptions
// because the rclcpp::QoS <-> rclpy.qos.QoS Profile conversion cannot be done by builtins.
// It is possible, but the code is much longer and harder to maintain, requiring duplicating
// the names of the members multiple times, as well as the default values from the struct
// definitions.
py::class_<PlayOptions>(m, "PlayOptions")
.def(py::init<>())
.def_readwrite("read_ahead_queue_size", &PlayOptions::read_ahead_queue_size)
.def_readwrite("node_prefix", &PlayOptions::node_prefix)
.def_readwrite("rate", &PlayOptions::rate)
.def_readwrite("topics_to_filter", &PlayOptions::topics_to_filter)
.def_readwrite("topics_regex_to_filter", &PlayOptions::topics_regex_to_filter)
.def_readwrite("topics_regex_to_exclude", &PlayOptions::topics_regex_to_exclude)
.def_property(
"topic_qos_profile_overrides",
&PlayOptions::getTopicQoSProfileOverrides,
&PlayOptions::setTopicQoSProfileOverrides)
.def_readwrite("loop", &PlayOptions::loop)
.def_readwrite("topic_remapping_options", &PlayOptions::topic_remapping_options)
.def_readwrite("clock_publish_frequency", &PlayOptions::clock_publish_frequency)
.def_readwrite("clock_publish_on_topic_publish", &PlayOptions::clock_publish_on_topic_publish)
.def_readwrite("clock_topics", &PlayOptions::clock_trigger_topics)
.def_property(
"delay",
&PlayOptions::getDelay,
&PlayOptions::setDelay)
.def_property(
"playback_duration",
&PlayOptions::getPlaybackDuration,
&PlayOptions::setPlaybackDuration)
.def_readwrite("disable_keyboard_controls", &PlayOptions::disable_keyboard_controls)
.def_readwrite("start_paused", &PlayOptions::start_paused)
.def_property(
"start_offset",
&PlayOptions::getStartOffset,
&PlayOptions::setStartOffset)
.def_property(
"playback_until_timestamp",
&PlayOptions::getPlaybackUntilTimestamp,
&PlayOptions::setPlaybackUntilTimestamp)
.def_readwrite("wait_acked_timeout", &PlayOptions::wait_acked_timeout)
.def_readwrite("disable_loan_message", &PlayOptions::disable_loan_message)
;
py::class_<RecordOptions>(m, "RecordOptions")
.def(py::init<>())
.def_readwrite("all", &RecordOptions::all)
.def_readwrite("is_discovery_disabled", &RecordOptions::is_discovery_disabled)
.def_readwrite("topics", &RecordOptions::topics)
.def_readwrite("rmw_serialization_format", &RecordOptions::rmw_serialization_format)
.def_readwrite("topic_polling_interval", &RecordOptions::topic_polling_interval)
.def_readwrite("regex", &RecordOptions::regex)
.def_readwrite("exclude", &RecordOptions::exclude)
.def_readwrite("node_prefix", &RecordOptions::node_prefix)
.def_readwrite("compression_mode", &RecordOptions::compression_mode)
.def_readwrite("compression_format", &RecordOptions::compression_format)
.def_readwrite("compression_queue_size", &RecordOptions::compression_queue_size)
.def_readwrite("compression_threads", &RecordOptions::compression_threads)
.def_property(
"topic_qos_profile_overrides",
&RecordOptions::getTopicQoSProfileOverrides,
&RecordOptions::setTopicQoSProfileOverrides)
.def_readwrite("include_hidden_topics", &RecordOptions::include_hidden_topics)
.def_readwrite("include_unpublished_topics", &RecordOptions::include_unpublished_topics)
.def_readwrite("start_paused", &RecordOptions::start_paused)
.def_readwrite("ignore_leaf_topics", &RecordOptions::ignore_leaf_topics)
.def_readwrite("use_sim_time", &RecordOptions::use_sim_time)
;
py::class_<rosbag2_py::Player>(m, "Player")
.def(py::init())
.def("play", &rosbag2_py::Player::play, py::arg("storage_options"), py::arg("play_options"))
.def("burst", &rosbag2_py::Player::burst)
;
py::class_<rosbag2_py::Recorder>(m, "Recorder")
.def(py::init())
.def(
"record", &rosbag2_py::Recorder::record, py::arg("storage_options"), py::arg("record_options"),
py::arg("node_name") = "rosbag2_recorder")
.def_static("cancel", &rosbag2_py::Recorder::cancel)
;
m.def(
"bag_rewrite",
&rosbag2_py::bag_rewrite,
"Given one or more input bags, output one or more bags with new settings.");
}