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

Enabled rosbag::Bag move operations if compiler support is available #1189

Merged
merged 2 commits into from
Oct 20, 2017
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
10 changes: 10 additions & 0 deletions tools/rosbag_storage/include/rosbag/bag.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@
#include <set>
#include <stdexcept>

#include <boost/config.hpp>
#include <boost/format.hpp>
#include <boost/iterator/iterator_facade.hpp>

Expand Down Expand Up @@ -111,6 +112,12 @@ class ROSBAG_DECL Bag

~Bag();

#ifndef BOOST_NO_CXX11_RVALUE_REFERENCES
Bag(Bag&& other);

Bag& operator=(Bag&& other);
#endif // BOOST_NO_CXX11_RVALUE_REFERENCES

//! Open a bag file.
/*!
* \param filename The bag file to open
Expand Down Expand Up @@ -186,9 +193,12 @@ class ROSBAG_DECL Bag
void swap(Bag&);

private:
// disable copying
Bag(const Bag&);
Bag& operator=(const Bag&);

void init();

// This helper function actually does the write with an arbitrary serializable message
template<class T>
void doWrite(std::string const& topic, ros::Time const& time, T const& msg, boost::shared_ptr<ros::M_string> const& connection_header);
Expand Down
63 changes: 35 additions & 28 deletions tools/rosbag_storage/src/bag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,45 +57,52 @@ using ros::Time;

namespace rosbag {

Bag::Bag() :
mode_(bagmode::Write),
version_(0),
compression_(compression::Uncompressed),
chunk_threshold_(768 * 1024), // 768KB chunks
bag_revision_(0),
file_size_(0),
file_header_pos_(0),
index_data_pos_(0),
connection_count_(0),
chunk_count_(0),
chunk_open_(false),
curr_chunk_data_pos_(0),
current_buffer_(0),
decompressed_chunk_(0)
Bag::Bag()
{
init();
}

Bag::Bag(string const& filename, uint32_t mode) :
compression_(compression::Uncompressed),
chunk_threshold_(768 * 1024), // 768KB chunks
bag_revision_(0),
file_size_(0),
file_header_pos_(0),
index_data_pos_(0),
connection_count_(0),
chunk_count_(0),
chunk_open_(false),
curr_chunk_data_pos_(0),
current_buffer_(0),
decompressed_chunk_(0)
Bag::Bag(string const& filename, uint32_t mode)
{
init();
open(filename, mode);
}

#ifndef BOOST_NO_CXX11_RVALUE_REFERENCES

Bag::Bag(Bag&& other) {
init();
swap(other);
}

Bag& Bag::operator=(Bag&& other) {
swap(other);
return *this;
}

#endif // BOOST_NO_CXX11_RVALUE_REFERENCES

Bag::~Bag() {
close();
}

void Bag::init() {
mode_ = bagmode::Write;
version_ = 0;
compression_ = compression::Uncompressed;
chunk_threshold_ = 768 * 1024; // 768KB chunks
bag_revision_ = 0;
file_size_ = 0;
file_header_pos_ = 0;
index_data_pos_ = 0;
connection_count_ = 0;
chunk_count_ = 0;
chunk_open_ = false;
curr_chunk_data_pos_ = 0;
current_buffer_ = 0;
decompressed_chunk_ = 0;
}

void Bag::open(string const& filename, uint32_t mode) {
mode_ = (BagMode) mode;

Expand Down