Public Member Functions | Private Member Functions | Private Attributes | Friends
rosbag::Bag Class Reference

#include <bag.h>

List of all members.

Public Member Functions

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

Private Member Functions

void appendConnectionRecordToBuffer (Buffer &buf, ConnectionInfo const *connection_info)
void appendDataLengthToBuffer (Buffer &buf, uint32_t data_len)
void appendHeaderToBuffer (Buffer &buf, ros::M_string const &fields)
ros::M_string::const_iterator checkField (ros::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 decompressRawChunk (ChunkHeader const &chunk_header) const
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)
uint32_t getChunkOffset () const
template<class T >
boost::shared_ptr< T > instantiateBuffer (IndexEntry const &index_entry) const
 deserializes the message held in record_buffer_
bool isOp (ros::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 (ros::M_string const &fields, std::string const &field_name, bool required, T *data) const
bool readField (ros::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 (ros::M_string const &fields, std::string const &field_name, bool required, std::string &data) const
bool readField (ros::M_string const &fields, std::string const &field_name, bool required, ros::Time &data) const
void readFileHeaderRecord ()
bool readHeader (ros::Header &header) const
void readHeaderFromBuffer (Buffer &buffer, uint32_t offset, ros::Header &header, uint32_t &data_size, uint32_t &bytes_read) const
ros::Header readMessageDataHeader (IndexEntry const &index_entry)
void readMessageDataHeaderFromBuffer (Buffer &buffer, uint32_t offset, ros::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, ros::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 (ros::Time time)
void stopWriting ()
void stopWritingChunk ()
template<typename T >
std::string toHeaderString (T const *field) const
std::string toHeaderString (ros::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 (ros::M_string const &fields)
void writeIndexRecords ()
template<class T >
void writeMessageDataRecord (uint32_t conn_id, ros::Time const &time, T const &msg)
void writeVersion ()

Private Attributes

uint32_t bag_revision_
Buffer chunk_buffer_
 reusable buffer to read chunk into
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
uint64_t decompressed_chunk_
 position of decompressed chunk
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
std::map< ros::M_string, uint32_t > header_connection_ids_
uint64_t index_data_pos_
BagMode mode_
Buffer outgoing_chunk_buffer_
 reusable buffer to read chunk into
Buffer record_buffer_
 reusable buffer in which to assemble the record data before writing to file
std::map< std::string, uint32_t > topic_connection_ids_
int version_

Friends

class MessageInstance
class View

Detailed Description

Definition at line 77 of file bag.h.


Constructor & Destructor Documentation

Definition at line 54 of file bag.cpp.

rosbag::Bag::Bag ( 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 85 of file bag.cpp.


Member Function Documentation

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

Definition at line 632 of file bag.cpp.

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

Definition at line 950 of file bag.cpp.

void rosbag::Bag::appendHeaderToBuffer ( Buffer buf,
ros::M_string const &  fields 
) [private]

Definition at line 936 of file bag.cpp.

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

Definition at line 1027 of file bag.cpp.

Close the bag file.

Definition at line 149 of file bag.cpp.

void rosbag::Bag::closeWrite ( ) [private]

Definition at line 168 of file bag.cpp.

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

Definition at line 786 of file bag.cpp.

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

Definition at line 722 of file bag.cpp.

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

Definition at line 774 of file bag.cpp.

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

Definition at line 468 of file bag.h.

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

Definition at line 379 of file bag.cpp.

uint32_t rosbag::Bag::getChunkThreshold ( ) const

Get the threshold for creating new chunks.

Definition at line 176 of file bag.cpp.

Get the compression method to use for writing chunks.

Definition at line 185 of file bag.cpp.

string rosbag::Bag::getFileName ( ) const

Get the filename of the bag.

Definition at line 172 of file bag.cpp.

uint32_t rosbag::Bag::getMajorVersion ( ) const

Get the major-version of the open bag file.

Definition at line 221 of file bag.cpp.

uint32_t rosbag::Bag::getMinorVersion ( ) const

Get the minor-version of the open bag file.

Definition at line 222 of file bag.cpp.

Get the mode the bag is in.

Definition at line 173 of file bag.cpp.

uint64_t rosbag::Bag::getSize ( ) const

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

Definition at line 174 of file bag.cpp.

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

deserializes the message held in record_buffer_

Definition at line 377 of file bag.h.

bool rosbag::Bag::isOp ( ros::M_string fields,
uint8_t  reqOp 
) const [private]

Definition at line 918 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 89 of file bag.cpp.

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

Definition at line 127 of file bag.cpp.

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

Definition at line 108 of file bag.cpp.

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

Definition at line 121 of file bag.cpp.

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

Definition at line 1081 of file bag.cpp.

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

Definition at line 453 of file bag.cpp.

Definition at line 873 of file bag.cpp.

Definition at line 562 of file bag.cpp.

Definition at line 642 of file bag.cpp.

bool rosbag::Bag::readDataLength ( uint32_t &  data_size) const [private]

Definition at line 1022 of file bag.cpp.

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

Definition at line 340 of file bag.h.

bool rosbag::Bag::readField ( ros::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 ( ros::M_string const &  fields,
std::string const &  field_name,
bool  required,
std::string &  data 
) const [private]
bool rosbag::Bag::readField ( ros::M_string const &  fields,
std::string const &  field_name,
bool  required,
ros::Time data 
) const [private]

Definition at line 349 of file bag.cpp.

bool rosbag::Bag::readHeader ( ros::Header header) const [private]

Definition at line 1004 of file bag.cpp.

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

Definition at line 959 of file bag.cpp.

ros::Header rosbag::Bag::readMessageDataHeader ( IndexEntry const &  index_entry) [private]

Definition at line 802 of file bag.cpp.

void rosbag::Bag::readMessageDataHeaderFromBuffer ( Buffer buffer,
uint32_t  offset,
ros::Header header,
uint32_t &  data_size,
uint32_t &  bytes_read 
) const [private]

Definition at line 985 of file bag.cpp.

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

Definition at line 349 of file bag.h.

void rosbag::Bag::readMessageDataRecord102 ( uint64_t  offset,
ros::Header header 
) const [private]

Definition at line 751 of file bag.cpp.

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

Definition at line 821 of file bag.cpp.

Definition at line 678 of file bag.cpp.

Definition at line 500 of file bag.cpp.

void rosbag::Bag::readVersion ( ) [private]

Definition at line 206 of file bag.cpp.

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

Definition at line 1082 of file bag.cpp.

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

Set the threshold for creating new chunks.

Definition at line 178 of file bag.cpp.

Set the compression method to use for writing chunks.

Definition at line 187 of file bag.cpp.

Definition at line 281 of file bag.cpp.

Definition at line 246 of file bag.cpp.

void rosbag::Bag::startWriting ( ) [private]

Definition at line 226 of file bag.cpp.

void rosbag::Bag::startWritingChunk ( ros::Time  time) [private]

Definition at line 386 of file bag.cpp.

void rosbag::Bag::stopWriting ( ) [private]

Definition at line 232 of file bag.cpp.

void rosbag::Bag::stopWritingChunk ( ) [private]

Definition at line 404 of file bag.cpp.

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

Definition at line 335 of file bag.h.

std::string rosbag::Bag::toHeaderString ( ros::Time const *  field) const [private]

Definition at line 1064 of file bag.cpp.

template<class T >
void rosbag::Bag::write ( std::string const &  topic,
ros::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 315 of file bag.h.

template<class T >
void rosbag::Bag::write ( std::string const &  topic,
ros::Time const &  time,
T const &  msg,
boost::shared_ptr< ros::M_string connection_header = boost::shared_ptr<ros::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 320 of file bag.h.

template<class T >
void rosbag::Bag::write ( std::string const &  topic,
ros::Time const &  time,
boost::shared_ptr< T const > const &  msg,
boost::shared_ptr< ros::M_string connection_header = boost::shared_ptr<ros::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 325 of file bag.h.

template<class T >
void rosbag::Bag::write ( std::string const &  topic,
ros::Time const &  time,
boost::shared_ptr< T > const &  msg,
boost::shared_ptr< ros::M_string connection_header = boost::shared_ptr<ros::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 330 of file bag.h.

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

Definition at line 1079 of file bag.cpp.

void rosbag::Bag::write ( std::string const &  s) [private]
void rosbag::Bag::writeChunkHeader ( CompressionType  compression,
uint32_t  compressed_size,
uint32_t  uncompressed_size 
) [private]

Definition at line 431 of file bag.cpp.

Definition at line 839 of file bag.cpp.

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

Definition at line 619 of file bag.cpp.

Definition at line 612 of file bag.cpp.

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

Definition at line 932 of file bag.cpp.

Definition at line 317 of file bag.cpp.

void rosbag::Bag::writeHeader ( ros::M_string const &  fields) [private]

Definition at line 924 of file bag.cpp.

void rosbag::Bag::writeIndexRecords ( ) [private]

Definition at line 471 of file bag.cpp.

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

Definition at line 579 of file bag.h.

void rosbag::Bag::writeVersion ( ) [private]

Definition at line 196 of file bag.cpp.


Friends And Related Function Documentation

friend class MessageInstance [friend]

Definition at line 79 of file bag.h.

friend class View [friend]

Definition at line 80 of file bag.h.


Member Data Documentation

uint32_t rosbag::Bag::bag_revision_ [private]

Definition at line 271 of file bag.h.

Buffer rosbag::Bag::chunk_buffer_ [mutable, private]

reusable buffer to read chunk into

Definition at line 296 of file bag.h.

uint32_t rosbag::Bag::chunk_count_ [private]

Definition at line 277 of file bag.h.

bool rosbag::Bag::chunk_open_ [private]

Definition at line 280 of file bag.h.

uint32_t rosbag::Bag::chunk_threshold_ [private]

Definition at line 270 of file bag.h.

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

Definition at line 288 of file bag.h.

Definition at line 269 of file bag.h.

uint32_t rosbag::Bag::connection_count_ [private]

Definition at line 276 of file bag.h.

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

Definition at line 290 of file bag.h.

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

Definition at line 286 of file bag.h.

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

Definition at line 291 of file bag.h.

Definition at line 282 of file bag.h.

Definition at line 281 of file bag.h.

Buffer* rosbag::Bag::current_buffer_ [mutable, private]

Definition at line 301 of file bag.h.

reusable buffer to decompress chunks into

Definition at line 297 of file bag.h.

uint64_t rosbag::Bag::decompressed_chunk_ [mutable, private]

position of decompressed chunk

Definition at line 303 of file bag.h.

ChunkedFile rosbag::Bag::file_ [mutable, private]

Definition at line 267 of file bag.h.

uint64_t rosbag::Bag::file_header_pos_ [private]

Definition at line 274 of file bag.h.

uint64_t rosbag::Bag::file_size_ [private]

Definition at line 273 of file bag.h.

Buffer rosbag::Bag::header_buffer_ [mutable, private]

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

Definition at line 293 of file bag.h.

std::map<ros::M_string, uint32_t> rosbag::Bag::header_connection_ids_ [private]

Definition at line 285 of file bag.h.

uint64_t rosbag::Bag::index_data_pos_ [private]

Definition at line 275 of file bag.h.

Definition at line 266 of file bag.h.

reusable buffer to read chunk into

Definition at line 299 of file bag.h.

Buffer rosbag::Bag::record_buffer_ [mutable, private]

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

Definition at line 294 of file bag.h.

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

Definition at line 284 of file bag.h.

int rosbag::Bag::version_ [private]

Definition at line 268 of file bag.h.


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


rosbag
Author(s): Tim Field (tfield@willowgarage.com), Jeremy Leibs (leibs@willowgarage.com), and James Bowman (jamesb@willowgarage.com)
autogenerated on Sat Dec 28 2013 17:43:05