Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
rosbag::Bag Class Reference

#include <bag.h>

Public Member Functions

 Bag ()
 
 Bag (std::string const &filename, uint32_t mode=bagmode::Read)
 Open a bag file. More...
 
void close ()
 Close the bag file. More...
 
uint32_t getChunkThreshold () const
 Get the threshold for creating new chunks. More...
 
CompressionType getCompression () const
 Get the compression method to use for writing chunks. More...
 
std::tuple< std::string, uint64_t, uint64_tgetCompressionInfo () const
 
std::string getFileName () const
 Get the filename of the bag. More...
 
uint32_t getMajorVersion () const
 Get the major-version of the open bag file. More...
 
uint32_t getMinorVersion () const
 Get the minor-version of the open bag file. More...
 
BagMode getMode () const
 Get the mode the bag is in. More...
 
uint64_t getSize () const
 Get the current size of the bag file (a lower bound) More...
 
void open (std::string const &filename, uint32_t mode=bagmode::Read)
 Open a bag file. More...
 
void setChunkThreshold (uint32_t chunk_threshold)
 Set the threshold for creating new chunks. More...
 
void setCompression (CompressionType compression)
 Set the compression method to use for writing chunks. More...
 
template<class T >
void write (std::string const &topic, rs2rosinternal::MessageEvent< T > const &event)
 Write a message into the bag file. More...
 
template<class T >
void write (std::string const &topic, rs2rosinternal::Time const &time, T const &msg, std::shared_ptr< rs2rosinternal::M_string > connection_header=std::shared_ptr< rs2rosinternal::M_string >())
 Write a message into the bag file. More...
 
template<class T >
void write (std::string const &topic, rs2rosinternal::Time const &time, std::shared_ptr< T const > const &msg, std::shared_ptr< rs2rosinternal::M_string > connection_header=std::shared_ptr< rs2rosinternal::M_string >())
 Write a message into the bag file. More...
 
template<class T >
void write (std::string const &topic, rs2rosinternal::Time const &time, std::shared_ptr< T > const &msg, std::shared_ptr< rs2rosinternal::M_string > connection_header=std::shared_ptr< rs2rosinternal::M_string >())
 Write a message into the bag file. More...
 
 ~Bag ()
 

Private Member Functions

void appendConnectionRecordToBuffer (Buffer &buf, ConnectionInfo const *connection_info)
 
void appendDataLengthToBuffer (Buffer &buf, uint32_t data_len)
 
void appendHeaderToBuffer (Buffer &buf, rs2rosinternal::M_string const &fields)
 
rs2rosinternal::M_string::const_iterator checkField (rs2rosinternal::M_string const &fields, std::string const &field, unsigned int min_len, unsigned int max_len, bool required) const
 
void closeWrite ()
 
void decompressBz2Chunk (ChunkHeader const &chunk_header) const
 
void decompressChunk (uint64_t chunk_pos) const
 
void decompressLz4Chunk (ChunkHeader const &chunk_header) const
 
void decompressRawChunk (ChunkHeader const &chunk_header) const
 
template<class T >
void doWrite (std::string const &topic, rs2rosinternal::Time const &time, T const &msg, std::shared_ptr< rs2rosinternal::M_string > const &connection_header)
 
uint32_t getChunkOffset () const
 
template<class T >
std::shared_ptr< T > instantiateBuffer (IndexEntry const &index_entry) const
 deserializes the message held in record_buffer_ More...
 
bool isOp (rs2rosinternal::M_string &fields, uint8_t reqOp) const
 
void openAppend (std::string const &filename)
 
void openRead (std::string const &filename)
 
void openWrite (std::string const &filename)
 
void read (char *b, std::streamsize n) const
 
void readChunkHeader (ChunkHeader &chunk_header) const
 
void readChunkInfoRecord ()
 
void readConnectionIndexRecord200 ()
 
void readConnectionRecord ()
 
bool readDataLength (uint32_t &data_size) const
 
template<typename T >
bool readField (rs2rosinternal::M_string const &fields, std::string const &field_name, bool required, T *data) const
 
bool readField (rs2rosinternal::M_string const &fields, std::string const &field_name, unsigned int min_len, unsigned int max_len, bool required, std::string &data) const
 
bool readField (rs2rosinternal::M_string const &fields, std::string const &field_name, bool required, std::string &data) const
 
bool readField (rs2rosinternal::M_string const &fields, std::string const &field_name, bool required, rs2rosinternal::Time &data) const
 
void readFileHeaderRecord ()
 
bool readHeader (rs2rosinternal::Header &header) const
 
void readHeaderFromBuffer (Buffer &buffer, uint32_t offset, rs2rosinternal::Header &header, uint32_t &data_size, uint32_t &bytes_read) const
 
rs2rosinternal::Header readMessageDataHeader (IndexEntry const &index_entry)
 
void readMessageDataHeaderFromBuffer (Buffer &buffer, uint32_t offset, rs2rosinternal::Header &header, uint32_t &data_size, uint32_t &bytes_read) const
 
template<typename Stream >
void readMessageDataIntoStream (IndexEntry const &index_entry, Stream &stream) const
 
void readMessageDataRecord102 (uint64_t offset, rs2rosinternal::Header &header) const
 
uint32_t readMessageDataSize (IndexEntry const &index_entry) const
 
void readMessageDefinitionRecord102 ()
 
void readTopicIndexRecord102 ()
 
void readVersion ()
 
void seek (uint64_t pos, int origin=std::ios_base::beg) const
 
void startReadingVersion102 ()
 
void startReadingVersion200 ()
 
void startWriting ()
 
void startWritingChunk (rs2rosinternal::Time time)
 
void stopWriting ()
 
void stopWritingChunk ()
 
template<typename T >
std::string toHeaderString (T const *field) const
 
std::string toHeaderString (rs2rosinternal::Time const *field) const
 
void write (char const *s, std::streamsize n)
 
void write (std::string const &s)
 
void writeChunkHeader (CompressionType compression, uint32_t compressed_size, uint32_t uncompressed_size)
 
void writeChunkInfoRecords ()
 
void writeConnectionRecord (ConnectionInfo const *connection_info)
 
void writeConnectionRecords ()
 
void writeDataLength (uint32_t data_len)
 
void writeFileHeaderRecord ()
 
void writeHeader (rs2rosinternal::M_string const &fields)
 
void writeIndexRecords ()
 
template<class T >
void writeMessageDataRecord (uint32_t conn_id, rs2rosinternal::Time const &time, T const &msg)
 
void writeVersion ()
 

Private Attributes

uint32_t bag_revision_
 
Buffer chunk_buffer_
 reusable buffer to read chunk into More...
 
uint32_t chunk_count_
 
bool chunk_open_
 
uint32_t chunk_threshold_
 
std::vector< ChunkInfochunks_
 
CompressionType compression_
 
uint32_t connection_count_
 
std::map< uint32_t, std::multiset< IndexEntry > > connection_indexes_
 
std::map< uint32_t, ConnectionInfo * > connections_
 
std::map< uint32_t, std::multiset< IndexEntry > > curr_chunk_connection_indexes_
 
uint64_t curr_chunk_data_pos_
 
ChunkInfo curr_chunk_info_
 
Buffercurrent_buffer_
 
Buffer decompress_buffer_
 reusable buffer to decompress chunks into More...
 
uint64_t decompressed_chunk_
 position of decompressed chunk More...
 
ChunkedFile file_
 
uint64_t file_header_pos_
 
uint64_t file_size_
 
Buffer header_buffer_
 reusable buffer in which to assemble the record header before writing to file More...
 
std::map< rs2rosinternal::M_string, uint32_theader_connection_ids_
 
uint64_t index_data_pos_
 
BagMode mode_
 
Buffer outgoing_chunk_buffer_
 reusable buffer to read chunk into More...
 
Buffer record_buffer_
 reusable buffer in which to assemble the record data before writing to file More...
 
std::map< std::string, uint32_ttopic_connection_ids_
 
int version_
 

Friends

class MessageInstance
 
class View
 

Detailed Description

Definition at line 84 of file bag.h.

Constructor & Destructor Documentation

rosbag::Bag::Bag ( )

Definition at line 62 of file bag.cpp.

rosbag::Bag::Bag ( std::string const &  filename,
uint32_t  mode = bagmode::Read 
)
explicit

Open a bag file.

Parameters
filenameThe bag file to open
modeThe mode to use (either read, write or append)

Can throw BagException

Definition at line 80 of file bag.cpp.

rosbag::Bag::~Bag ( )

Definition at line 97 of file bag.cpp.

Member Function Documentation

void rosbag::Bag::appendConnectionRecordToBuffer ( Buffer buf,
ConnectionInfo const *  connection_info 
)
private

Definition at line 698 of file bag.cpp.

void rosbag::Bag::appendDataLengthToBuffer ( Buffer buf,
uint32_t  data_len 
)
private

Definition at line 1034 of file bag.cpp.

void rosbag::Bag::appendHeaderToBuffer ( Buffer buf,
rs2rosinternal::M_string const &  fields 
)
private

Definition at line 1020 of file bag.cpp.

M_string::const_iterator rosbag::Bag::checkField ( rs2rosinternal::M_string const &  fields,
std::string const &  field,
unsigned int  min_len,
unsigned int  max_len,
bool  required 
) const
private

Definition at line 1112 of file bag.cpp.

void rosbag::Bag::close ( )

Close the bag file.

Definition at line 161 of file bag.cpp.

void rosbag::Bag::closeWrite ( )
private

Definition at line 180 of file bag.cpp.

void rosbag::Bag::decompressBz2Chunk ( ChunkHeader const &  chunk_header) const
private

Definition at line 854 of file bag.cpp.

void rosbag::Bag::decompressChunk ( uint64_t  chunk_pos) const
private

Definition at line 788 of file bag.cpp.

void rosbag::Bag::decompressLz4Chunk ( ChunkHeader const &  chunk_header) const
private

Definition at line 870 of file bag.cpp.

void rosbag::Bag::decompressRawChunk ( ChunkHeader const &  chunk_header) const
private

Definition at line 842 of file bag.cpp.

template<class T >
void rosbag::Bag::doWrite ( std::string const &  topic,
rs2rosinternal::Time const &  time,
T const &  msg,
std::shared_ptr< rs2rosinternal::M_string > const &  connection_header 
)
private

Definition at line 471 of file bag.h.

uint32_t rosbag::Bag::getChunkOffset ( ) const
private

Definition at line 444 of file bag.cpp.

uint32_t rosbag::Bag::getChunkThreshold ( ) const

Get the threshold for creating new chunks.

Definition at line 188 of file bag.cpp.

CompressionType rosbag::Bag::getCompression ( ) const

Get the compression method to use for writing chunks.

Definition at line 197 of file bag.cpp.

std::tuple< std::string, uint64_t, uint64_t > rosbag::Bag::getCompressionInfo ( ) const

Definition at line 199 of file bag.cpp.

string rosbag::Bag::getFileName ( ) const

Get the filename of the bag.

Definition at line 184 of file bag.cpp.

uint32_t rosbag::Bag::getMajorVersion ( ) const

Get the major-version of the open bag file.

Definition at line 286 of file bag.cpp.

uint32_t rosbag::Bag::getMinorVersion ( ) const

Get the minor-version of the open bag file.

Definition at line 287 of file bag.cpp.

BagMode rosbag::Bag::getMode ( ) const

Get the mode the bag is in.

Definition at line 185 of file bag.cpp.

uint64_t rosbag::Bag::getSize ( ) const

Get the current size of the bag file (a lower bound)

Definition at line 186 of file bag.cpp.

template<class T >
std::shared_ptr< T > rosbag::Bag::instantiateBuffer ( IndexEntry const &  index_entry) const
private

deserializes the message held in record_buffer_

Definition at line 386 of file bag.h.

bool rosbag::Bag::isOp ( rs2rosinternal::M_string fields,
uint8_t  reqOp 
) const
private

Definition at line 1002 of file bag.cpp.

void rosbag::Bag::open ( std::string const &  filename,
uint32_t  mode = bagmode::Read 
)

Open a bag file.

Parameters
filenameThe bag file to open
modeThe mode to use (either read, write or append)

Can throw BagException

Definition at line 101 of file bag.cpp.

void rosbag::Bag::openAppend ( std::string const &  filename)
private

Definition at line 139 of file bag.cpp.

void rosbag::Bag::openRead ( std::string const &  filename)
private

Definition at line 120 of file bag.cpp.

void rosbag::Bag::openWrite ( std::string const &  filename)
private

Definition at line 133 of file bag.cpp.

void rosbag::Bag::read ( char *  b,
std::streamsize  n 
) const
private

Definition at line 1160 of file bag.cpp.

void rosbag::Bag::readChunkHeader ( ChunkHeader chunk_header) const
private

Definition at line 519 of file bag.cpp.

void rosbag::Bag::readChunkInfoRecord ( )
private

Definition at line 957 of file bag.cpp.

void rosbag::Bag::readConnectionIndexRecord200 ( )
private

Definition at line 628 of file bag.cpp.

void rosbag::Bag::readConnectionRecord ( )
private

Definition at line 708 of file bag.cpp.

bool rosbag::Bag::readDataLength ( uint32_t data_size) const
private

Definition at line 1107 of file bag.cpp.

template<typename T >
bool rosbag::Bag::readField ( rs2rosinternal::M_string const &  fields,
std::string const &  field_name,
bool  required,
T *  data 
) const
private

Definition at line 349 of file bag.h.

bool rosbag::Bag::readField ( rs2rosinternal::M_string const &  fields,
std::string const &  field_name,
unsigned int  min_len,
unsigned int  max_len,
bool  required,
std::string data 
) const
private
bool rosbag::Bag::readField ( rs2rosinternal::M_string const &  fields,
std::string const &  field_name,
bool  required,
std::string data 
) const
private
bool rosbag::Bag::readField ( rs2rosinternal::M_string const &  fields,
std::string const &  field_name,
bool  required,
rs2rosinternal::Time data 
) const
private
void rosbag::Bag::readFileHeaderRecord ( )
private

Definition at line 414 of file bag.cpp.

bool rosbag::Bag::readHeader ( rs2rosinternal::Header header) const
private

Definition at line 1089 of file bag.cpp.

void rosbag::Bag::readHeaderFromBuffer ( Buffer buffer,
uint32_t  offset,
rs2rosinternal::Header header,
uint32_t data_size,
uint32_t bytes_read 
) const
private
Todo:
clean this up

Definition at line 1043 of file bag.cpp.

rs2rosinternal::Header rosbag::Bag::readMessageDataHeader ( IndexEntry const &  index_entry)
private

Definition at line 887 of file bag.cpp.

void rosbag::Bag::readMessageDataHeaderFromBuffer ( Buffer buffer,
uint32_t  offset,
rs2rosinternal::Header header,
uint32_t data_size,
uint32_t bytes_read 
) const
private

Definition at line 1069 of file bag.cpp.

template<typename Stream >
void rosbag::Bag::readMessageDataIntoStream ( IndexEntry const &  index_entry,
Stream stream 
) const
private

Definition at line 358 of file bag.h.

void rosbag::Bag::readMessageDataRecord102 ( uint64_t  offset,
rs2rosinternal::Header header 
) const
private

Definition at line 819 of file bag.cpp.

uint32_t rosbag::Bag::readMessageDataSize ( IndexEntry const &  index_entry) const
private

Definition at line 906 of file bag.cpp.

void rosbag::Bag::readMessageDefinitionRecord102 ( )
private

Definition at line 744 of file bag.cpp.

void rosbag::Bag::readTopicIndexRecord102 ( )
private

Definition at line 566 of file bag.cpp.

void rosbag::Bag::readVersion ( )
private

Definition at line 267 of file bag.cpp.

void rosbag::Bag::seek ( uint64_t  pos,
int  origin = std::ios_base::beg 
) const
private

Definition at line 1161 of file bag.cpp.

void rosbag::Bag::setChunkThreshold ( uint32_t  chunk_threshold)

Set the threshold for creating new chunks.

Definition at line 190 of file bag.cpp.

void rosbag::Bag::setCompression ( CompressionType  compression)

Set the compression method to use for writing chunks.

Definition at line 241 of file bag.cpp.

void rosbag::Bag::startReadingVersion102 ( )
private

Definition at line 346 of file bag.cpp.

void rosbag::Bag::startReadingVersion200 ( )
private

Definition at line 311 of file bag.cpp.

void rosbag::Bag::startWriting ( )
private

Definition at line 291 of file bag.cpp.

void rosbag::Bag::startWritingChunk ( rs2rosinternal::Time  time)
private

Definition at line 451 of file bag.cpp.

void rosbag::Bag::stopWriting ( )
private

Definition at line 297 of file bag.cpp.

void rosbag::Bag::stopWritingChunk ( )
private

Definition at line 469 of file bag.cpp.

template<typename T >
std::string rosbag::Bag::toHeaderString ( T const *  field) const
private

Definition at line 344 of file bag.h.

std::string rosbag::Bag::toHeaderString ( rs2rosinternal::Time const *  field) const
private

Definition at line 1149 of file bag.cpp.

template<class T >
void rosbag::Bag::write ( std::string const &  topic,
rs2rosinternal::MessageEvent< T > const &  event 
)

Write a message into the bag file.

Parameters
topicThe topic name
eventThe message event to be added

Can throw BagIOException

Definition at line 324 of file bag.h.

template<class T >
void rosbag::Bag::write ( std::string const &  topic,
rs2rosinternal::Time const &  time,
T const &  msg,
std::shared_ptr< rs2rosinternal::M_string connection_header = std::shared_ptr<rs2rosinternal::M_string>() 
)

Write a message into the bag file.

Parameters
topicThe topic name
timeTimestamp of the message
msgThe message to be added
connection_headerA connection header.

Can throw BagIOException

Definition at line 329 of file bag.h.

template<class T >
void rosbag::Bag::write ( std::string const &  topic,
rs2rosinternal::Time const &  time,
std::shared_ptr< T const > const &  msg,
std::shared_ptr< rs2rosinternal::M_string connection_header = std::shared_ptr<rs2rosinternal::M_string>() 
)

Write a message into the bag file.

Parameters
topicThe topic name
timeTimestamp of the message
msgThe message to be added
connection_headerA connection header.

Can throw BagIOException

Definition at line 334 of file bag.h.

template<class T >
void rosbag::Bag::write ( std::string const &  topic,
rs2rosinternal::Time const &  time,
std::shared_ptr< T > const &  msg,
std::shared_ptr< rs2rosinternal::M_string connection_header = std::shared_ptr<rs2rosinternal::M_string>() 
)

Write a message into the bag file.

Parameters
topicThe topic name
timeTimestamp of the message
msgThe message to be added
connection_headerA connection header.

Can throw BagIOException

Definition at line 339 of file bag.h.

void rosbag::Bag::write ( char const *  s,
std::streamsize  n 
)
private

Definition at line 1158 of file bag.cpp.

void rosbag::Bag::write ( std::string const &  s)
private

Definition at line 1157 of file bag.cpp.

void rosbag::Bag::writeChunkHeader ( CompressionType  compression,
uint32_t  compressed_size,
uint32_t  uncompressed_size 
)
private

Definition at line 496 of file bag.cpp.

void rosbag::Bag::writeChunkInfoRecords ( )
private

Definition at line 924 of file bag.cpp.

void rosbag::Bag::writeConnectionRecord ( ConnectionInfo const *  connection_info)
private

Definition at line 685 of file bag.cpp.

void rosbag::Bag::writeConnectionRecords ( )
private

Definition at line 678 of file bag.cpp.

void rosbag::Bag::writeDataLength ( uint32_t  data_len)
private

Definition at line 1016 of file bag.cpp.

void rosbag::Bag::writeFileHeaderRecord ( )
private

Definition at line 382 of file bag.cpp.

void rosbag::Bag::writeHeader ( rs2rosinternal::M_string const &  fields)
private

Definition at line 1008 of file bag.cpp.

void rosbag::Bag::writeIndexRecords ( )
private

Definition at line 537 of file bag.cpp.

template<class T >
void rosbag::Bag::writeMessageDataRecord ( uint32_t  conn_id,
rs2rosinternal::Time const &  time,
T const &  msg 
)
private

Definition at line 582 of file bag.h.

void rosbag::Bag::writeVersion ( )
private

Definition at line 257 of file bag.cpp.

Friends And Related Function Documentation

friend class MessageInstance
friend

Definition at line 86 of file bag.h.

friend class View
friend

Definition at line 87 of file bag.h.

Member Data Documentation

uint32_t rosbag::Bag::bag_revision_
private

Definition at line 280 of file bag.h.

Buffer rosbag::Bag::chunk_buffer_
mutableprivate

reusable buffer to read chunk into

Definition at line 305 of file bag.h.

uint32_t rosbag::Bag::chunk_count_
private

Definition at line 286 of file bag.h.

bool rosbag::Bag::chunk_open_
private

Definition at line 289 of file bag.h.

uint32_t rosbag::Bag::chunk_threshold_
private

Definition at line 279 of file bag.h.

std::vector<ChunkInfo> rosbag::Bag::chunks_
private

Definition at line 297 of file bag.h.

CompressionType rosbag::Bag::compression_
private

Definition at line 278 of file bag.h.

uint32_t rosbag::Bag::connection_count_
private

Definition at line 285 of file bag.h.

std::map<uint32_t, std::multiset<IndexEntry> > rosbag::Bag::connection_indexes_
private

Definition at line 299 of file bag.h.

std::map<uint32_t, ConnectionInfo*> rosbag::Bag::connections_
private

Definition at line 295 of file bag.h.

std::map<uint32_t, std::multiset<IndexEntry> > rosbag::Bag::curr_chunk_connection_indexes_
private

Definition at line 300 of file bag.h.

uint64_t rosbag::Bag::curr_chunk_data_pos_
private

Definition at line 291 of file bag.h.

ChunkInfo rosbag::Bag::curr_chunk_info_
private

Definition at line 290 of file bag.h.

Buffer* rosbag::Bag::current_buffer_
mutableprivate

Definition at line 310 of file bag.h.

Buffer rosbag::Bag::decompress_buffer_
mutableprivate

reusable buffer to decompress chunks into

Definition at line 306 of file bag.h.

uint64_t rosbag::Bag::decompressed_chunk_
mutableprivate

position of decompressed chunk

Definition at line 312 of file bag.h.

ChunkedFile rosbag::Bag::file_
mutableprivate

Definition at line 276 of file bag.h.

uint64_t rosbag::Bag::file_header_pos_
private

Definition at line 283 of file bag.h.

uint64_t rosbag::Bag::file_size_
private

Definition at line 282 of file bag.h.

Buffer rosbag::Bag::header_buffer_
mutableprivate

reusable buffer in which to assemble the record header before writing to file

Definition at line 302 of file bag.h.

std::map<rs2rosinternal::M_string, uint32_t> rosbag::Bag::header_connection_ids_
private

Definition at line 294 of file bag.h.

uint64_t rosbag::Bag::index_data_pos_
private

Definition at line 284 of file bag.h.

BagMode rosbag::Bag::mode_
private

Definition at line 275 of file bag.h.

Buffer rosbag::Bag::outgoing_chunk_buffer_
mutableprivate

reusable buffer to read chunk into

Definition at line 308 of file bag.h.

Buffer rosbag::Bag::record_buffer_
mutableprivate

reusable buffer in which to assemble the record data before writing to file

Definition at line 303 of file bag.h.

std::map<std::string, uint32_t> rosbag::Bag::topic_connection_ids_
private

Definition at line 293 of file bag.h.

int rosbag::Bag::version_
private

Definition at line 277 of file bag.h.


The documentation for this class was generated from the following files:


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:50:40