Repository Summary
Checkout URI | https://github.com/osrf/rosbag_direct_write.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2018-02-16 |
Dev Status | UNMAINTAINED |
CI status | No Continuous Integration |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Packages
Name | Version |
---|---|
rosbag_direct_write | 0.0.0 |
README
rosbag_direct_write
This repository contains one package, rosbag_direct_write
, which provides a similar interface to the rosbag::Bag
interface, but only for writing rosbag files.
The purpose of this package is to allow for high performance rosbag file creation by:
- avoiding seeking during writing
- using
O_DIRECT
and writing in 4KB aligned memory segments - by allowing the user to write directly to the rosbag file in special cases to prevent
memcpy
’s
Basic API usage
This package depends on the rosbag_storage
package and provieds the DirectBag
class.
The DirectBag
class provides a few important functions:
-
open
: opens a rosbag, overwriting any existing rosbag -
filename
: path to the rosbag to open -
chunk_threshold
: size at which to break up rosbag chunks, default 768KB -
write
: writes a given message, to a given topic, with a given received time -
topic
: ROS topic to associate the message with -
time
: ros::Time when the message was received -
msg
: message or structure to be written to the bag -
close
: closes the rosbag, immediately finishing any open chunks
These are the most important functions, but there are a few others.
See the header at include/rosbag_direct_write/direct_bag.h
for more details.
Features
rosbag_direct_write
will always open rosbag files with O_DIRECT
, or F_NOCACHE
where needed, to make use of the more efficient writing.
In the default case, messages are serialized and stored in an in-memory buffer until the chunk threshold is met.
When the chunk threshold is met, the chunk is “finished” and written to the disk, taking advantage of O_DIRECT
.
This will be faster out-of-the-box than the rosbag::Bag
API in most cases, even if the Zero-copy direct write mechanism is not used.
Zero-copy Direct Writing
If the user of the API so chooses, they may make use of the zero-copy direct writing of messages to the rosbag file.
This is most useful when the user has a large segment of data, like in an image or in a point cloud, and they do not wish to copy that data into an intermediate in-memory buffer.
This can help avoid necessary memcpy
’s and it can also allow the kernel to make use of DMA optimizations, especially if the data to be recorded does not start in main memory.
In order to take advantage of this feature, the user must define three function template specializations for their message type.
Here is an example for sensor_msgs/PointCloud2
:
```c++ #include <sensor_msgs/PointCloud2.h>
#include <rosbag_direct_write/direct_bag.h>
namespace rosbag_direct_write {
template <> bool has_direct_data(const sensor_msgs::PointCloud2 &point_cloud) { ROSBAG_DIRECT_WRITE_UNUSED(point_cloud); // Prevents unused argument warning return true; }
template <> size_t alignment_adjustment(const sensor_msgs::PointCloud2 &point_cloud) { ROSBAG_DIRECT_WRITE_UNUSED(point_cloud); return 1; // To account for the trailing is_dense boolean. }
template <> SerializationReturnCode serialize_to_buffer(VectorBuffer& buffer, const sensor_msgs::PointCloud2& msg, size_t step) { size_t ser_len = 0; size_t start_offset = 0; shared_ptr<ros::serialization::OStream> s; switch (step) { case 0: // First stage of the serialization // Calculate how much additional buffer we will need for the message ser_len = ros::serialization::serializationLength(msg); ser_len -= msg.data.size(); // Subtract for the size of size of image data (an int32) ser_len -= 4; // Subtract the size of the fields which come after the “data” field ser_len -= ros::serialization::serializationLength(msg.is_dense); // Save correct buffer position and resize start_offset = buffer.size(); buffer.resize(buffer.size() + ser_len); // Create a OStream s.reset(new ros::serialization::OStream(buffer.data() + start_offset, ser_len)); // Write out everything but image data ros::serialization::serialize(s, msg.header); ros::serialization::serialize(s, msg.height); ros::serialization::serialize(s, msg.width); ros::serialization::serialize(s, msg.fields); ros::serialization::serialize(s, msg.is_bigendian); ros::serialization::serialize(s, msg.point_step); ros::serialization::serialize(*s, msg.row_step); // Write the size of the data which comes next in serialize_to_file impl::write_to_buffer(buffer, msg.data.size(), 4); return SerializationReturnCode::SERIALIZE_TO_FILE_NEXT; case 2: // Second call, after file writing // Calculate the size needed
File truncated at 100 lines see the full file