bag.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage, Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #ifndef ROSBAG_BAG_H
36 #define ROSBAG_BAG_H
37 
38 #include "rosbag/macros.h"
39 
40 #include "rosbag/buffer.h"
41 #include "rosbag/chunked_file.h"
42 #include "rosbag/constants.h"
43 #include "rosbag/exceptions.h"
44 #include "rosbag/structures.h"
45 
46 #include "ros/header.h"
47 #include "ros/time.h"
48 #include "ros/message_traits.h"
49 #include "ros/message_event.h"
50 #include "ros/serialization.h"
51 
52 //#include "ros/subscription_callback_helper.h"
53 
54 #include <ios>
55 #include <map>
56 #include <queue>
57 #include <set>
58 #include <stdexcept>
59 
60 #include <boost/config.hpp>
61 #include <boost/format.hpp>
62 #include <boost/iterator/iterator_facade.hpp>
63 
64 #include "console_bridge/console.h"
65 #if defined logDebug
66 # undef logDebug
67 #endif
68 #if defined logInform
69 # undef logInform
70 #endif
71 #if defined logWarn
72 # undef logWarn
73 #endif
74 #if defined logError
75 # undef logError
76 #endif
77 
78 namespace rosbag {
79 
80 namespace bagmode
81 {
83  enum BagMode
84  {
85  Write = 1,
86  Read = 2,
87  Append = 4
88  };
89 }
91 
92 class MessageInstance;
93 class View;
94 class Query;
95 
97 {
98  friend class MessageInstance;
99  friend class View;
100 
101 public:
102  Bag();
103 
105 
111  explicit Bag(std::string const& filename, uint32_t mode = bagmode::Read);
112 
113  ~Bag();
114 
115 #ifndef BOOST_NO_CXX11_RVALUE_REFERENCES
116  Bag(Bag&& other);
117 
118  Bag& operator=(Bag&& other);
119 #endif // BOOST_NO_CXX11_RVALUE_REFERENCES
120 
122 
128  void open(std::string const& filename, uint32_t mode = bagmode::Read);
129 
131  void close();
132 
133  std::string getFileName() const;
134  BagMode getMode() const;
135  uint32_t getMajorVersion() const;
136  uint32_t getMinorVersion() const;
137  uint64_t getSize() const;
138 
139  void setCompression(CompressionType compression);
140  CompressionType getCompression() const;
141  void setChunkThreshold(uint32_t chunk_threshold);
142  uint32_t getChunkThreshold() const;
143 
145 
151  template<class T>
152  void write(std::string const& topic, ros::MessageEvent<T> const& event);
153 
155 
163  template<class T>
164  void write(std::string const& topic, ros::Time const& time, T const& msg,
166 
168 
176  template<class T>
177  void write(std::string const& topic, ros::Time const& time, boost::shared_ptr<T const> const& msg,
179 
181 
189  template<class T>
190  void write(std::string const& topic, ros::Time const& time, boost::shared_ptr<T> const& msg,
192 
193  void swap(Bag&);
194 
195  bool isOpen() const;
196 
197 private:
198  // disable copying
199  Bag(const Bag&);
200  Bag& operator=(const Bag&);
201 
202  void init();
203 
204  // This helper function actually does the write with an arbitrary serializable message
205  template<class T>
206  void doWrite(std::string const& topic, ros::Time const& time, T const& msg, boost::shared_ptr<ros::M_string> const& connection_header);
207 
208  void openRead (std::string const& filename);
209  void openWrite (std::string const& filename);
210  void openAppend(std::string const& filename);
211 
212  void closeWrite();
213 
214  template<class T>
215  boost::shared_ptr<T> instantiateBuffer(IndexEntry const& index_entry) const;
216 
217  void startWriting();
218  void stopWriting();
219 
220  void startReadingVersion102();
221  void startReadingVersion200();
222 
223  // Writing
224 
225  void writeVersion();
226  void writeFileHeaderRecord();
227  void writeConnectionRecord(ConnectionInfo const* connection_info);
228  void appendConnectionRecordToBuffer(Buffer& buf, ConnectionInfo const* connection_info);
229  template<class T>
230  void writeMessageDataRecord(uint32_t conn_id, ros::Time const& time, T const& msg);
231  void writeIndexRecords();
232  void writeConnectionRecords();
233  void writeChunkInfoRecords();
234  void startWritingChunk(ros::Time time);
235  void writeChunkHeader(CompressionType compression, uint32_t compressed_size, uint32_t uncompressed_size);
236  void stopWritingChunk();
237 
238  // Reading
239 
240  void readVersion();
241  void readFileHeaderRecord();
242  void readConnectionRecord();
243  void readChunkHeader(ChunkHeader& chunk_header) const;
244  void readChunkInfoRecord();
245  void readConnectionIndexRecord200();
246 
247  void readTopicIndexRecord102();
248  void readMessageDefinitionRecord102();
249  void readMessageDataRecord102(uint64_t offset, ros::Header& header) const;
250 
251  ros::Header readMessageDataHeader(IndexEntry const& index_entry);
252  uint32_t readMessageDataSize(IndexEntry const& index_entry) const;
253 
254  template<typename Stream>
255  void readMessageDataIntoStream(IndexEntry const& index_entry, Stream& stream) const;
256 
257  void decompressChunk(uint64_t chunk_pos) const;
258  void decompressRawChunk(ChunkHeader const& chunk_header) const;
259  void decompressBz2Chunk(ChunkHeader const& chunk_header) const;
260  void decompressLz4Chunk(ChunkHeader const& chunk_header) const;
261  uint32_t getChunkOffset() const;
262 
263  // Record header I/O
264 
265  void writeHeader(ros::M_string const& fields);
266  void writeDataLength(uint32_t data_len);
267  void appendHeaderToBuffer(Buffer& buf, ros::M_string const& fields);
268  void appendDataLengthToBuffer(Buffer& buf, uint32_t data_len);
269 
270  void readHeaderFromBuffer(Buffer& buffer, uint32_t offset, ros::Header& header, uint32_t& data_size, uint32_t& bytes_read) const;
271  void readMessageDataHeaderFromBuffer(Buffer& buffer, uint32_t offset, ros::Header& header, uint32_t& data_size, uint32_t& bytes_read) const;
272  bool readHeader(ros::Header& header) const;
273  bool readDataLength(uint32_t& data_size) const;
274  bool isOp(ros::M_string& fields, uint8_t reqOp) const;
275 
276  // Header fields
277 
278  template<typename T>
279  std::string toHeaderString(T const* field) const;
280 
281  std::string toHeaderString(ros::Time const* field) const;
282 
283  template<typename T>
284  bool readField(ros::M_string const& fields, std::string const& field_name, bool required, T* data) const;
285 
286  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;
287  bool readField(ros::M_string const& fields, std::string const& field_name, bool required, std::string& data) const;
288 
289  bool readField(ros::M_string const& fields, std::string const& field_name, bool required, ros::Time& data) const;
290 
291  ros::M_string::const_iterator checkField(ros::M_string const& fields, std::string const& field,
292  unsigned int min_len, unsigned int max_len, bool required) const;
293 
294  // Low-level I/O
295 
296  void write(char const* s, std::streamsize n);
297  void write(std::string const& s);
298  void read(char* b, std::streamsize n) const;
299  void seek(uint64_t pos, int origin = std::ios_base::beg) const;
300 
301 private:
302  BagMode mode_;
304  int version_;
307  uint32_t bag_revision_;
308 
309  uint64_t file_size_;
311  uint64_t index_data_pos_;
313  uint32_t chunk_count_;
314 
315  // Current chunk
319 
320  std::map<std::string, uint32_t> topic_connection_ids_;
321  std::map<ros::M_string, uint32_t> header_connection_ids_;
322  std::map<uint32_t, ConnectionInfo*> connections_;
323 
324  std::vector<ChunkInfo> chunks_;
325 
326  std::map<uint32_t, std::multiset<IndexEntry> > connection_indexes_;
327  std::map<uint32_t, std::multiset<IndexEntry> > curr_chunk_connection_indexes_;
328 
331 
334 
336 
338 
339  mutable uint64_t decompressed_chunk_;
340 };
341 
342 } // namespace rosbag
343 
344 #include "rosbag/message_instance.h"
345 
346 namespace rosbag {
347 
348 // Templated method definitions
349 
350 template<class T>
351 void Bag::write(std::string const& topic, ros::MessageEvent<T> const& event) {
352  doWrite(topic, event.getReceiptTime(), *event.getMessage(), event.getConnectionHeaderPtr());
353 }
354 
355 template<class T>
356 void Bag::write(std::string const& topic, ros::Time const& time, T const& msg, boost::shared_ptr<ros::M_string> connection_header) {
357  doWrite(topic, time, msg, connection_header);
358 }
359 
360 template<class T>
361 void 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) {
362  doWrite(topic, time, *msg, connection_header);
363 }
364 
365 template<class T>
366 void Bag::write(std::string const& topic, ros::Time const& time, boost::shared_ptr<T> const& msg, boost::shared_ptr<ros::M_string> connection_header) {
367  doWrite(topic, time, *msg, connection_header);
368 }
369 
370 template<typename T>
371 std::string Bag::toHeaderString(T const* field) const {
372  return std::string((char*) field, sizeof(T));
373 }
374 
375 template<typename T>
376 bool Bag::readField(ros::M_string const& fields, std::string const& field_name, bool required, T* data) const {
377  ros::M_string::const_iterator i = checkField(fields, field_name, sizeof(T), sizeof(T), required);
378  if (i == fields.end())
379  return false;
380  memcpy(data, i->second.data(), sizeof(T));
381  return true;
382 }
383 
384 template<typename Stream>
385 void Bag::readMessageDataIntoStream(IndexEntry const& index_entry, Stream& stream) const {
387  uint32_t data_size;
388  uint32_t bytes_read;
389  switch (version_)
390  {
391  case 200:
392  {
393  decompressChunk(index_entry.chunk_pos);
394  readMessageDataHeaderFromBuffer(*current_buffer_, index_entry.offset, header, data_size, bytes_read);
395  if (data_size > 0)
396  memcpy(stream.advance(data_size), current_buffer_->getData() + index_entry.offset + bytes_read, data_size);
397  break;
398  }
399  case 102:
400  {
401  readMessageDataRecord102(index_entry.chunk_pos, header);
402  data_size = record_buffer_.getSize();
403  if (data_size > 0)
404  memcpy(stream.advance(data_size), record_buffer_.getData(), data_size);
405  break;
406  }
407  default:
408  throw BagFormatException((boost::format("Unhandled version: %1%") % version_).str());
409  }
410 }
411 
412 template<class T>
414  switch (version_)
415  {
416  case 200:
417  {
418  decompressChunk(index_entry.chunk_pos);
419 
420  // Read the message header
422  uint32_t data_size;
423  uint32_t bytes_read;
424  readMessageDataHeaderFromBuffer(*current_buffer_, index_entry.offset, header, data_size, bytes_read);
425 
426  // Read the connection id from the header
427  uint32_t connection_id;
428  readField(*header.getValues(), CONNECTION_FIELD_NAME, true, &connection_id);
429 
430  std::map<uint32_t, ConnectionInfo*>::const_iterator connection_iter = connections_.find(connection_id);
431  if (connection_iter == connections_.end())
432  throw BagFormatException((boost::format("Unknown connection ID: %1%") % connection_id).str());
433  ConnectionInfo* connection_info = connection_iter->second;
434 
435  boost::shared_ptr<T> p = boost::make_shared<T>();
436 
438  predes_params.message = p;
439  predes_params.connection_header = connection_info->header;
441 
442  // Deserialize the message
443  ros::serialization::IStream s(current_buffer_->getData() + index_entry.offset + bytes_read, data_size);
445 
446  return p;
447  }
448  case 102:
449  {
450  // Read the message record
452  readMessageDataRecord102(index_entry.chunk_pos, header);
453 
454  ros::M_string& fields = *header.getValues();
455 
456  // Read the connection id from the header
457  std::string topic, latching("0"), callerid;
458  readField(fields, TOPIC_FIELD_NAME, true, topic);
459  readField(fields, LATCHING_FIELD_NAME, false, latching);
460  readField(fields, CALLERID_FIELD_NAME, false, callerid);
461 
462  std::map<std::string, uint32_t>::const_iterator topic_conn_id_iter = topic_connection_ids_.find(topic);
463  if (topic_conn_id_iter == topic_connection_ids_.end())
464  throw BagFormatException((boost::format("Unknown topic: %1%") % topic).str());
465  uint32_t connection_id = topic_conn_id_iter->second;
466 
467  std::map<uint32_t, ConnectionInfo*>::const_iterator connection_iter = connections_.find(connection_id);
468  if (connection_iter == connections_.end())
469  throw BagFormatException((boost::format("Unknown connection ID: %1%") % connection_id).str());
470  ConnectionInfo* connection_info = connection_iter->second;
471 
472  boost::shared_ptr<T> p = boost::make_shared<T>();
473 
474  // Create a new connection header, updated with the latching and callerid values
475  boost::shared_ptr<ros::M_string> message_header(boost::make_shared<ros::M_string>());
476  for (ros::M_string::const_iterator i = connection_info->header->begin(); i != connection_info->header->end(); i++)
477  (*message_header)[i->first] = i->second;
478  (*message_header)["latching"] = latching;
479  (*message_header)["callerid"] = callerid;
480 
482  predes_params.message = p;
483  predes_params.connection_header = message_header;
485 
486  // Deserialize the message
487  ros::serialization::IStream s(record_buffer_.getData(), record_buffer_.getSize());
489 
490  return p;
491  }
492  default:
493  throw BagFormatException((boost::format("Unhandled version: %1%") % version_).str());
494  }
495 }
496 
497 template<class T>
498 void Bag::doWrite(std::string const& topic, ros::Time const& time, T const& msg, boost::shared_ptr<ros::M_string> const& connection_header) {
499 
500  if (time < ros::TIME_MIN)
501  {
502  throw BagException("Tried to insert a message with time less than ros::TIME_MIN");
503  }
504 
505  // Whenever we write we increment our revision
506  bag_revision_++;
507 
508  // Get ID for connection header
509  ConnectionInfo* connection_info = NULL;
510  uint32_t conn_id = 0;
511  if (!connection_header) {
512  // No connection header: we'll manufacture one, and store by topic
513 
514  std::map<std::string, uint32_t>::iterator topic_connection_ids_iter = topic_connection_ids_.find(topic);
515  if (topic_connection_ids_iter == topic_connection_ids_.end()) {
516  conn_id = connections_.size();
517  topic_connection_ids_[topic] = conn_id;
518  }
519  else {
520  conn_id = topic_connection_ids_iter->second;
521  connection_info = connections_[conn_id];
522  }
523  }
524  else {
525  // Store the connection info by the address of the connection header
526 
527  // Add the topic name to the connection header, so that when we later search by
528  // connection header, we can disambiguate connections that differ only by topic name (i.e.,
529  // same callerid, same message type), #3755. This modified connection header is only used
530  // for our bookkeeping, and will not appear in the resulting .bag.
531  ros::M_string connection_header_copy(*connection_header);
532  connection_header_copy["topic"] = topic;
533 
534  std::map<ros::M_string, uint32_t>::iterator header_connection_ids_iter = header_connection_ids_.find(connection_header_copy);
535  if (header_connection_ids_iter == header_connection_ids_.end()) {
536  conn_id = connections_.size();
537  header_connection_ids_[connection_header_copy] = conn_id;
538  }
539  else {
540  conn_id = header_connection_ids_iter->second;
541  connection_info = connections_[conn_id];
542  }
543  }
544 
545  {
546  // Seek to the end of the file (needed in case previous operation was a read)
547  seek(0, std::ios::end);
548  file_size_ = file_.getOffset();
549 
550  // Write the chunk header if we're starting a new chunk
551  if (!chunk_open_)
552  startWritingChunk(time);
553 
554  // Write connection info record, if necessary
555  if (connection_info == NULL) {
556  connection_info = new ConnectionInfo();
557  connection_info->id = conn_id;
558  connection_info->topic = topic;
559  connection_info->datatype = std::string(ros::message_traits::datatype(msg));
560  connection_info->md5sum = std::string(ros::message_traits::md5sum(msg));
561  connection_info->msg_def = std::string(ros::message_traits::definition(msg));
562  if (connection_header != NULL) {
563  connection_info->header = connection_header;
564  }
565  else {
566  connection_info->header = boost::make_shared<ros::M_string>();
567  (*connection_info->header)["type"] = connection_info->datatype;
568  (*connection_info->header)["md5sum"] = connection_info->md5sum;
569  (*connection_info->header)["message_definition"] = connection_info->msg_def;
570  }
571  connections_[conn_id] = connection_info;
572 
573  writeConnectionRecord(connection_info);
574  appendConnectionRecordToBuffer(outgoing_chunk_buffer_, connection_info);
575  }
576 
577  // Add to topic indexes
578  IndexEntry index_entry;
579  index_entry.time = time;
580  index_entry.chunk_pos = curr_chunk_info_.pos;
581  index_entry.offset = getChunkOffset();
582 
583  std::multiset<IndexEntry>& chunk_connection_index = curr_chunk_connection_indexes_[connection_info->id];
584  chunk_connection_index.insert(chunk_connection_index.end(), index_entry);
585  std::multiset<IndexEntry>& connection_index = connection_indexes_[connection_info->id];
586  connection_index.insert(connection_index.end(), index_entry);
587 
588  // Increment the connection count
589  curr_chunk_info_.connection_counts[connection_info->id]++;
590 
591  // Write the message data
592  writeMessageDataRecord(conn_id, time, msg);
593 
594  // Check if we want to stop this chunk
595  uint32_t chunk_size = getChunkOffset();
596  CONSOLE_BRIDGE_logDebug(" curr_chunk_size=%d (threshold=%d)", chunk_size, chunk_threshold_);
597  if (chunk_size > chunk_threshold_) {
598  // Empty the outgoing chunk
599  stopWritingChunk();
600  outgoing_chunk_buffer_.setSize(0);
601 
602  // We no longer have a valid curr_chunk_info
603  curr_chunk_info_.pos = -1;
604  }
605  }
606 }
607 
608 template<class T>
609 void Bag::writeMessageDataRecord(uint32_t conn_id, ros::Time const& time, T const& msg) {
611  header[OP_FIELD_NAME] = toHeaderString(&OP_MSG_DATA);
612  header[CONNECTION_FIELD_NAME] = toHeaderString(&conn_id);
613  header[TIME_FIELD_NAME] = toHeaderString(&time);
614 
615  // Assemble message in memory first, because we need to write its length
616  uint32_t msg_ser_len = ros::serialization::serializationLength(msg);
617 
618  record_buffer_.setSize(msg_ser_len);
619 
620  ros::serialization::OStream s(record_buffer_.getData(), msg_ser_len);
621 
622  // todo: serialize into the outgoing_chunk_buffer & remove record_buffer_
624 
625  // We do an extra seek here since writing our data record may
626  // have indirectly moved our file-pointer if it was a
627  // MessageInstance for our own bag
628  seek(0, std::ios::end);
629  file_size_ = file_.getOffset();
630 
631  CONSOLE_BRIDGE_logDebug("Writing MSG_DATA [%llu:%d]: conn=%d sec=%d nsec=%d data_len=%d",
632  (unsigned long long) file_.getOffset(), getChunkOffset(), conn_id, time.sec, time.nsec, msg_ser_len);
633 
634  writeHeader(header);
635  writeDataLength(msg_ser_len);
636  write((char*) record_buffer_.getData(), msg_ser_len);
637 
638  // todo: use better abstraction than appendHeaderToBuffer
639  appendHeaderToBuffer(outgoing_chunk_buffer_, header);
640  appendDataLengthToBuffer(outgoing_chunk_buffer_, msg_ser_len);
641 
642  uint32_t offset = outgoing_chunk_buffer_.getSize();
643  outgoing_chunk_buffer_.setSize(outgoing_chunk_buffer_.getSize() + msg_ser_len);
644  memcpy(outgoing_chunk_buffer_.getData() + offset, record_buffer_.getData(), msg_ser_len);
645 
646  // Update the current chunk time range
647  if (time > curr_chunk_info_.end_time)
648  curr_chunk_info_.end_time = time;
649  else if (time < curr_chunk_info_.start_time)
650  curr_chunk_info_.start_time = time;
651 }
652 
653 inline void swap(Bag& a, Bag& b) {
654  a.swap(b);
655 }
656 
657 } // namespace rosbag
658 
659 #endif
static void notify(const PreDeserializeParams< M > &)
BagMode mode_
Definition: bag.h:302
std::map< std::string, uint32_t > topic_connection_ids_
Definition: bag.h:320
static const std::string LATCHING_FIELD_NAME
Definition: constants.h:71
ros::Time getReceiptTime() const
ChunkedFile reads and writes files which contain interleaved chunks of compressed and uncompressed da...
Definition: chunked_file.h:51
std::map< uint32_t, ConnectionInfo * > connections_
Definition: bag.h:322
int version_
Definition: bag.h:304
void swap(Bag &)
Definition: bag.cpp:1129
static const std::string CONNECTION_FIELD_NAME
Definition: constants.h:57
uint64_t file_size_
Definition: bag.h:309
std::map< ros::M_string, uint32_t > header_connection_ids_
Definition: bag.h:321
ros::Time time
Definition: structures.h:78
int writeHeader(roslz4_stream *str)
Buffer header_buffer_
reusable buffer in which to assemble the record header before writing to file
Definition: bag.h:329
Base class for rosbag exceptions.
Definition: exceptions.h:43
std_msgs::Header * header(M &m)
void swap(Bag &a, Bag &b)
Definition: bag.h:653
Exception thrown on problems reading the bag format.
Definition: exceptions.h:57
BagMode
The possible modes to open a bag in.
Definition: bag.h:83
std::string md5sum
Definition: structures.h:54
static const unsigned char OP_MSG_DATA
Definition: constants.h:75
boost::shared_ptr< T > instantiateBuffer(IndexEntry const &index_entry) const
deserializes the message held in record_buffer_
Definition: bag.h:413
bool readField(ros::M_string const &fields, std::string const &field_name, bool required, T *data) const
Definition: bag.h:376
Buffer decompress_buffer_
reusable buffer to decompress chunks into
Definition: bag.h:333
std::map< std::string, std::string > M_string
std::string toHeaderString(T const *field) const
Definition: bag.h:371
uint64_t decompressed_chunk_
position of decompressed chunk
Definition: bag.h:339
const char * datatype()
uint64_t index_data_pos_
Definition: bag.h:311
A class pointing into a bag file.
void serialize(Stream &stream, const T &t)
void readMessageDataIntoStream(IndexEntry const &index_entry, Stream &stream) const
Definition: bag.h:385
#define ROSBAG_DECL
Definition: macros.h:42
void writeMessageDataRecord(uint32_t conn_id, ros::Time const &time, T const &msg)
Definition: bag.h:609
Buffer * current_buffer_
Definition: bag.h:337
std::string msg_def
Definition: structures.h:55
static const std::string OP_FIELD_NAME
Definition: constants.h:50
uint64_t file_header_pos_
Definition: bag.h:310
uint32_t bag_revision_
Definition: bag.h:307
Buffer record_buffer_
reusable buffer in which to assemble the record data before writing to file
Definition: bag.h:330
Buffer chunk_buffer_
reusable buffer to read chunk into
Definition: bag.h:332
ChunkInfo curr_chunk_info_
Definition: bag.h:317
std::map< uint32_t, std::multiset< IndexEntry > > connection_indexes_
Definition: bag.h:326
uint64_t chunk_pos
timestamp of the message
Definition: structures.h:79
uint32_t connection_count_
Definition: bag.h:312
M_stringPtr getValues()
uint32_t offset
absolute byte offset of the chunk record containing the message
Definition: structures.h:80
uint32_t chunk_threshold_
Definition: bag.h:306
std::vector< ChunkInfo > chunks_
Definition: bag.h:324
std::string datatype
Definition: structures.h:53
ROSTIME_DECL const Time TIME_MIN
boost::shared_ptr< ros::M_string > header
Definition: structures.h:57
uint32_t chunk_count_
Definition: bag.h:313
uint32_t serializationLength(const T &t)
static const std::string TIME_FIELD_NAME
Definition: constants.h:60
Definition: bag.h:78
CompressionType compression_
Definition: bag.h:305
std::map< uint32_t, std::multiset< IndexEntry > > curr_chunk_connection_indexes_
Definition: bag.h:327
void doWrite(std::string const &topic, ros::Time const &time, T const &msg, boost::shared_ptr< ros::M_string > const &connection_header)
Definition: bag.h:498
uint64_t curr_chunk_data_pos_
Definition: bag.h:318
Buffer outgoing_chunk_buffer_
reusable buffer to read chunk into
Definition: bag.h:335
const char * md5sum()
boost::shared_ptr< std::map< std::string, std::string > > connection_header
ChunkedFile file_
Definition: bag.h:303
static const std::string TOPIC_FIELD_NAME
Definition: constants.h:51
const char * definition()
void deserialize(Stream &stream, T &t)
static const std::string CALLERID_FIELD_NAME
Definition: constants.h:72
void write(std::string const &topic, ros::MessageEvent< T > const &event)
Write a message into the bag file.
Definition: bag.h:351
bool chunk_open_
Definition: bag.h:316


rosbag_storage
Author(s):
autogenerated on Sun Feb 3 2019 03:29:47