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/encryptor.h"
44 #include "rosbag/exceptions.h"
45 #include "rosbag/structures.h"
46 
47 #include "ros/header.h"
48 #include "ros/time.h"
49 #include "ros/message_traits.h"
50 #include "ros/message_event.h"
51 #include "ros/serialization.h"
52 
53 //#include "ros/subscription_callback_helper.h"
54 
55 #include <ios>
56 #include <map>
57 #include <queue>
58 #include <set>
59 #include <stdexcept>
60 
61 #include <boost/config.hpp>
62 #include <boost/format.hpp>
63 #include <boost/iterator/iterator_facade.hpp>
64 
66 
67 #include "console_bridge/console.h"
68 #if defined logDebug
69 # undef logDebug
70 #endif
71 #if defined logInform
72 # undef logInform
73 #endif
74 #if defined logWarn
75 # undef logWarn
76 #endif
77 #if defined logError
78 # undef logError
79 #endif
80 
81 namespace rosbag {
82 
83 namespace bagmode
84 {
86  enum BagMode
87  {
88  Write = 1,
89  Read = 2,
90  Append = 4
91  };
92 }
94 
95 class MessageInstance;
96 class View;
97 class Query;
98 
100 {
101  friend class MessageInstance;
102  friend class View;
103 
104 public:
105  Bag();
106 
108 
114  explicit Bag(std::string const& filename, uint32_t mode = bagmode::Read);
115 
116  ~Bag();
117 
118 #ifndef BOOST_NO_CXX11_RVALUE_REFERENCES
119  Bag(Bag&& other);
120 
121  Bag& operator=(Bag&& other);
122 #endif // BOOST_NO_CXX11_RVALUE_REFERENCES
123 
125 
131  void open(std::string const& filename, uint32_t mode = bagmode::Read);
132 
134  void close();
135 
136  std::string getFileName() const;
137  BagMode getMode() const;
138  uint32_t getMajorVersion() const;
139  uint32_t getMinorVersion() const;
140  uint64_t getSize() const;
141 
142  void setCompression(CompressionType compression);
143  CompressionType getCompression() const;
144  void setChunkThreshold(uint32_t chunk_threshold);
145  uint32_t getChunkThreshold() const;
146 
148 
155  void setEncryptorPlugin(const std::string& plugin_name, const std::string& plugin_param = std::string());
156 
158 
164  template<class T>
165  void write(std::string const& topic, ros::MessageEvent<T> const& event);
166 
168 
176  template<class T>
177  void write(std::string const& topic, ros::Time const& time, T const& msg,
179 
181 
189  template<class T>
190  void write(std::string const& topic, ros::Time const& time, boost::shared_ptr<T const> const& msg,
192 
194 
202  template<class T>
203  void write(std::string const& topic, ros::Time const& time, boost::shared_ptr<T> const& msg,
205 
206  void swap(Bag&);
207 
208  bool isOpen() const;
209 
210 private:
211  // disable copying
212  Bag(const Bag&);
213  Bag& operator=(const Bag&);
214 
215  void init();
216 
217  // This helper function actually does the write with an arbitrary serializable message
218  template<class T>
219  void doWrite(std::string const& topic, ros::Time const& time, T const& msg, boost::shared_ptr<ros::M_string> const& connection_header);
220 
221  void openRead (std::string const& filename);
222  void openWrite (std::string const& filename);
223  void openAppend(std::string const& filename);
224 
225  void closeWrite();
226 
227  template<class T>
228  boost::shared_ptr<T> instantiateBuffer(IndexEntry const& index_entry) const;
229 
230  void startWriting();
231  void stopWriting();
232 
233  void startReadingVersion102();
234  void startReadingVersion200();
235 
236  // Writing
237 
238  void writeVersion();
239  void writeFileHeaderRecord();
240  void writeConnectionRecord(ConnectionInfo const* connection_info, const bool encrypt);
241  void appendConnectionRecordToBuffer(Buffer& buf, ConnectionInfo const* connection_info);
242  template<class T>
243  void writeMessageDataRecord(uint32_t conn_id, ros::Time const& time, T const& msg);
244  void writeIndexRecords();
245  void writeConnectionRecords();
246  void writeChunkInfoRecords();
247  void startWritingChunk(ros::Time time);
248  void writeChunkHeader(CompressionType compression, uint32_t compressed_size, uint32_t uncompressed_size);
249  void stopWritingChunk();
250 
251  // Reading
252 
253  void readVersion();
254  void readFileHeaderRecord();
255  void readConnectionRecord();
256  void readChunkHeader(ChunkHeader& chunk_header) const;
257  void readChunkInfoRecord();
258  void readConnectionIndexRecord200();
259 
260  void readTopicIndexRecord102();
261  void readMessageDefinitionRecord102();
262  void readMessageDataRecord102(uint64_t offset, ros::Header& header) const;
263 
264  ros::Header readMessageDataHeader(IndexEntry const& index_entry);
265  uint32_t readMessageDataSize(IndexEntry const& index_entry) const;
266 
267  template<typename Stream>
268  void readMessageDataIntoStream(IndexEntry const& index_entry, Stream& stream) const;
269 
270  void decompressChunk(uint64_t chunk_pos) const;
271  void decompressRawChunk(ChunkHeader const& chunk_header) const;
272  void decompressBz2Chunk(ChunkHeader const& chunk_header) const;
273  void decompressLz4Chunk(ChunkHeader const& chunk_header) const;
274  uint32_t getChunkOffset() const;
275 
276  // Record header I/O
277 
278  void writeHeader(ros::M_string const& fields);
279  void writeDataLength(uint32_t data_len);
280  void appendHeaderToBuffer(Buffer& buf, ros::M_string const& fields);
281  void appendDataLengthToBuffer(Buffer& buf, uint32_t data_len);
282 
283  void readHeaderFromBuffer(Buffer& buffer, uint32_t offset, ros::Header& header, uint32_t& data_size, uint32_t& bytes_read) const;
284  void readMessageDataHeaderFromBuffer(Buffer& buffer, uint32_t offset, ros::Header& header, uint32_t& data_size, uint32_t& bytes_read) const;
285  bool readHeader(ros::Header& header) const;
286  bool readDataLength(uint32_t& data_size) const;
287  bool isOp(ros::M_string& fields, uint8_t reqOp) const;
288 
289  // Header fields
290 
291  template<typename T>
292  std::string toHeaderString(T const* field) const;
293 
294  std::string toHeaderString(ros::Time const* field) const;
295 
296  template<typename T>
297  bool readField(ros::M_string const& fields, std::string const& field_name, bool required, T* data) const;
298 
299  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;
300  bool readField(ros::M_string const& fields, std::string const& field_name, bool required, std::string& data) const;
301 
302  bool readField(ros::M_string const& fields, std::string const& field_name, bool required, ros::Time& data) const;
303 
304  ros::M_string::const_iterator checkField(ros::M_string const& fields, std::string const& field,
305  unsigned int min_len, unsigned int max_len, bool required) const;
306 
307  // Low-level I/O
308 
309  void write(char const* s, std::streamsize n);
310  void write(std::string const& s);
311  void read(char* b, std::streamsize n) const;
312  void seek(uint64_t pos, int origin = std::ios_base::beg) const;
313 
314 private:
315  BagMode mode_;
317  int version_;
320  uint32_t bag_revision_;
321 
322  uint64_t file_size_;
324  uint64_t index_data_pos_;
326  uint32_t chunk_count_;
327 
328  // Current chunk
332 
333  std::map<std::string, uint32_t> topic_connection_ids_;
334  std::map<ros::M_string, uint32_t> header_connection_ids_;
335  std::map<uint32_t, ConnectionInfo*> connections_;
336 
337  std::vector<ChunkInfo> chunks_;
338 
339  std::map<uint32_t, std::multiset<IndexEntry> > connection_indexes_;
340  std::map<uint32_t, std::multiset<IndexEntry> > curr_chunk_connection_indexes_;
341 
344 
347 
349 
351 
352  mutable uint64_t decompressed_chunk_;
353 
354  // Encryptor plugin loader
356  // Active encryptor
358 };
359 
360 } // namespace rosbag
361 
362 #include "rosbag/message_instance.h"
363 
364 namespace rosbag {
365 
366 // Templated method definitions
367 
368 template<class T>
369 void Bag::write(std::string const& topic, ros::MessageEvent<T> const& event) {
370  doWrite(topic, event.getReceiptTime(), *event.getMessage(), event.getConnectionHeaderPtr());
371 }
372 
373 template<class T>
374 void Bag::write(std::string const& topic, ros::Time const& time, T const& msg, boost::shared_ptr<ros::M_string> connection_header) {
375  doWrite(topic, time, msg, connection_header);
376 }
377 
378 template<class T>
379 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) {
380  doWrite(topic, time, *msg, connection_header);
381 }
382 
383 template<class T>
384 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) {
385  doWrite(topic, time, *msg, connection_header);
386 }
387 
388 template<typename T>
389 std::string Bag::toHeaderString(T const* field) const {
390  return std::string((char*) field, sizeof(T));
391 }
392 
393 template<typename T>
394 bool Bag::readField(ros::M_string const& fields, std::string const& field_name, bool required, T* data) const {
395  ros::M_string::const_iterator i = checkField(fields, field_name, sizeof(T), sizeof(T), required);
396  if (i == fields.end())
397  return false;
398  memcpy(data, i->second.data(), sizeof(T));
399  return true;
400 }
401 
402 template<typename Stream>
403 void Bag::readMessageDataIntoStream(IndexEntry const& index_entry, Stream& stream) const {
405  uint32_t data_size;
406  uint32_t bytes_read;
407  switch (version_)
408  {
409  case 200:
410  {
411  decompressChunk(index_entry.chunk_pos);
412  readMessageDataHeaderFromBuffer(*current_buffer_, index_entry.offset, header, data_size, bytes_read);
413  if (data_size > 0)
414  memcpy(stream.advance(data_size), current_buffer_->getData() + index_entry.offset + bytes_read, data_size);
415  break;
416  }
417  case 102:
418  {
419  readMessageDataRecord102(index_entry.chunk_pos, header);
420  data_size = record_buffer_.getSize();
421  if (data_size > 0)
422  memcpy(stream.advance(data_size), record_buffer_.getData(), data_size);
423  break;
424  }
425  default:
426  throw BagFormatException((boost::format("Unhandled version: %1%") % version_).str());
427  }
428 }
429 
430 template<class T>
432  switch (version_)
433  {
434  case 200:
435  {
436  decompressChunk(index_entry.chunk_pos);
437 
438  // Read the message header
440  uint32_t data_size;
441  uint32_t bytes_read;
442  readMessageDataHeaderFromBuffer(*current_buffer_, index_entry.offset, header, data_size, bytes_read);
443 
444  // Read the connection id from the header
445  uint32_t connection_id;
446  readField(*header.getValues(), CONNECTION_FIELD_NAME, true, &connection_id);
447 
448  std::map<uint32_t, ConnectionInfo*>::const_iterator connection_iter = connections_.find(connection_id);
449  if (connection_iter == connections_.end())
450  throw BagFormatException((boost::format("Unknown connection ID: %1%") % connection_id).str());
451  ConnectionInfo* connection_info = connection_iter->second;
452 
453  boost::shared_ptr<T> p = boost::make_shared<T>();
454 
456  predes_params.message = p;
457  predes_params.connection_header = connection_info->header;
459 
460  // Deserialize the message
461  ros::serialization::IStream s(current_buffer_->getData() + index_entry.offset + bytes_read, data_size);
463 
464  return p;
465  }
466  case 102:
467  {
468  // Read the message record
470  readMessageDataRecord102(index_entry.chunk_pos, header);
471 
472  ros::M_string& fields = *header.getValues();
473 
474  // Read the connection id from the header
475  std::string topic, latching("0"), callerid;
476  readField(fields, TOPIC_FIELD_NAME, true, topic);
477  readField(fields, LATCHING_FIELD_NAME, false, latching);
478  readField(fields, CALLERID_FIELD_NAME, false, callerid);
479 
480  std::map<std::string, uint32_t>::const_iterator topic_conn_id_iter = topic_connection_ids_.find(topic);
481  if (topic_conn_id_iter == topic_connection_ids_.end())
482  throw BagFormatException((boost::format("Unknown topic: %1%") % topic).str());
483  uint32_t connection_id = topic_conn_id_iter->second;
484 
485  std::map<uint32_t, ConnectionInfo*>::const_iterator connection_iter = connections_.find(connection_id);
486  if (connection_iter == connections_.end())
487  throw BagFormatException((boost::format("Unknown connection ID: %1%") % connection_id).str());
488  ConnectionInfo* connection_info = connection_iter->second;
489 
490  boost::shared_ptr<T> p = boost::make_shared<T>();
491 
492  // Create a new connection header, updated with the latching and callerid values
493  boost::shared_ptr<ros::M_string> message_header(boost::make_shared<ros::M_string>());
494  for (ros::M_string::const_iterator i = connection_info->header->begin(); i != connection_info->header->end(); i++)
495  (*message_header)[i->first] = i->second;
496  (*message_header)["latching"] = latching;
497  (*message_header)["callerid"] = callerid;
498 
500  predes_params.message = p;
501  predes_params.connection_header = message_header;
503 
504  // Deserialize the message
505  ros::serialization::IStream s(record_buffer_.getData(), record_buffer_.getSize());
507 
508  return p;
509  }
510  default:
511  throw BagFormatException((boost::format("Unhandled version: %1%") % version_).str());
512  }
513 }
514 
515 template<class T>
516 void Bag::doWrite(std::string const& topic, ros::Time const& time, T const& msg, boost::shared_ptr<ros::M_string> const& connection_header) {
517 
518  if (time < ros::TIME_MIN)
519  {
520  throw BagException("Tried to insert a message with time less than ros::TIME_MIN");
521  }
522 
523  // Whenever we write we increment our revision
524  bag_revision_++;
525 
526  // Get ID for connection header
527  ConnectionInfo* connection_info = NULL;
528  uint32_t conn_id = 0;
529  if (!connection_header) {
530  // No connection header: we'll manufacture one, and store by topic
531 
532  std::map<std::string, uint32_t>::iterator topic_connection_ids_iter = topic_connection_ids_.find(topic);
533  if (topic_connection_ids_iter == topic_connection_ids_.end()) {
534  conn_id = connections_.size();
535  topic_connection_ids_[topic] = conn_id;
536  }
537  else {
538  conn_id = topic_connection_ids_iter->second;
539  connection_info = connections_[conn_id];
540  }
541  }
542  else {
543  // Store the connection info by the address of the connection header
544 
545  // Add the topic name to the connection header, so that when we later search by
546  // connection header, we can disambiguate connections that differ only by topic name (i.e.,
547  // same callerid, same message type), #3755. This modified connection header is only used
548  // for our bookkeeping, and will not appear in the resulting .bag.
549  ros::M_string connection_header_copy(*connection_header);
550  connection_header_copy["topic"] = topic;
551 
552  std::map<ros::M_string, uint32_t>::iterator header_connection_ids_iter = header_connection_ids_.find(connection_header_copy);
553  if (header_connection_ids_iter == header_connection_ids_.end()) {
554  conn_id = connections_.size();
555  header_connection_ids_[connection_header_copy] = conn_id;
556  }
557  else {
558  conn_id = header_connection_ids_iter->second;
559  connection_info = connections_[conn_id];
560  }
561  }
562 
563  {
564  // Seek to the end of the file (needed in case previous operation was a read)
565  seek(0, std::ios::end);
566  file_size_ = file_.getOffset();
567 
568  // Write the chunk header if we're starting a new chunk
569  if (!chunk_open_)
570  startWritingChunk(time);
571 
572  // Write connection info record, if necessary
573  if (connection_info == NULL) {
574  connection_info = new ConnectionInfo();
575  connection_info->id = conn_id;
576  connection_info->topic = topic;
577  connection_info->datatype = std::string(ros::message_traits::datatype(msg));
578  connection_info->md5sum = std::string(ros::message_traits::md5sum(msg));
579  connection_info->msg_def = std::string(ros::message_traits::definition(msg));
580  if (connection_header != NULL) {
581  connection_info->header = connection_header;
582  }
583  else {
584  connection_info->header = boost::make_shared<ros::M_string>();
585  (*connection_info->header)["type"] = connection_info->datatype;
586  (*connection_info->header)["md5sum"] = connection_info->md5sum;
587  (*connection_info->header)["message_definition"] = connection_info->msg_def;
588  }
589  connections_[conn_id] = connection_info;
590  // No need to encrypt connection records in chunks
591  writeConnectionRecord(connection_info, false);
592  appendConnectionRecordToBuffer(outgoing_chunk_buffer_, connection_info);
593  }
594 
595  // Add to topic indexes
596  IndexEntry index_entry;
597  index_entry.time = time;
598  index_entry.chunk_pos = curr_chunk_info_.pos;
599  index_entry.offset = getChunkOffset();
600 
601  std::multiset<IndexEntry>& chunk_connection_index = curr_chunk_connection_indexes_[connection_info->id];
602  chunk_connection_index.insert(chunk_connection_index.end(), index_entry);
603 
604  if (mode_ != BagMode::Write) {
605  std::multiset<IndexEntry>& connection_index = connection_indexes_[connection_info->id];
606  connection_index.insert(connection_index.end(), index_entry);
607  }
608 
609  // Increment the connection count
610  curr_chunk_info_.connection_counts[connection_info->id]++;
611 
612  // Write the message data
613  writeMessageDataRecord(conn_id, time, msg);
614 
615  // Check if we want to stop this chunk
616  uint32_t chunk_size = getChunkOffset();
617  CONSOLE_BRIDGE_logDebug(" curr_chunk_size=%d (threshold=%d)", chunk_size, chunk_threshold_);
618  if (chunk_size > chunk_threshold_) {
619  // Empty the outgoing chunk
620  stopWritingChunk();
621  outgoing_chunk_buffer_.setSize(0);
622 
623  // We no longer have a valid curr_chunk_info
624  curr_chunk_info_.pos = -1;
625  }
626  }
627 }
628 
629 template<class T>
630 void Bag::writeMessageDataRecord(uint32_t conn_id, ros::Time const& time, T const& msg) {
632  header[OP_FIELD_NAME] = toHeaderString(&OP_MSG_DATA);
633  header[CONNECTION_FIELD_NAME] = toHeaderString(&conn_id);
634  header[TIME_FIELD_NAME] = toHeaderString(&time);
635 
636  // Assemble message in memory first, because we need to write its length
637  uint32_t msg_ser_len = ros::serialization::serializationLength(msg);
638 
639  record_buffer_.setSize(msg_ser_len);
640 
641  ros::serialization::OStream s(record_buffer_.getData(), msg_ser_len);
642 
643  // todo: serialize into the outgoing_chunk_buffer & remove record_buffer_
645 
646  // We do an extra seek here since writing our data record may
647  // have indirectly moved our file-pointer if it was a
648  // MessageInstance for our own bag
649  seek(0, std::ios::end);
650  file_size_ = file_.getOffset();
651 
652  CONSOLE_BRIDGE_logDebug("Writing MSG_DATA [%llu:%d]: conn=%d sec=%d nsec=%d data_len=%d",
653  (unsigned long long) file_.getOffset(), getChunkOffset(), conn_id, time.sec, time.nsec, msg_ser_len);
654 
655  writeHeader(header);
656  writeDataLength(msg_ser_len);
657  write((char*) record_buffer_.getData(), msg_ser_len);
658 
659  // todo: use better abstraction than appendHeaderToBuffer
660  appendHeaderToBuffer(outgoing_chunk_buffer_, header);
661  appendDataLengthToBuffer(outgoing_chunk_buffer_, msg_ser_len);
662 
663  uint32_t offset = outgoing_chunk_buffer_.getSize();
664  outgoing_chunk_buffer_.setSize(outgoing_chunk_buffer_.getSize() + msg_ser_len);
665  memcpy(outgoing_chunk_buffer_.getData() + offset, record_buffer_.getData(), msg_ser_len);
666 
667  // Update the current chunk time range
668  if (time > curr_chunk_info_.end_time)
669  curr_chunk_info_.end_time = time;
670  else if (time < curr_chunk_info_.start_time)
671  curr_chunk_info_.start_time = time;
672 }
673 
674 inline void swap(Bag& a, Bag& b) {
675  a.swap(b);
676 }
677 
678 } // namespace rosbag
679 
680 #endif
static void notify(const PreDeserializeParams< M > &)
BagMode mode_
Definition: bag.h:315
#define ROSBAG_STORAGE_DECL
Definition: macros.h:50
std::map< std::string, uint32_t > topic_connection_ids_
Definition: bag.h:333
static const std::string LATCHING_FIELD_NAME
Definition: constants.h:72
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:335
bool readField(ros::M_string const &fields, std::string const &field_name, bool required, T *data) const
Definition: bag.h:394
int version_
Definition: bag.h:317
std::string toHeaderString(T const *field) const
Definition: bag.h:389
void swap(Bag &)
Definition: bag.cpp:1148
void init(const M_string &remappings)
static const std::string CONNECTION_FIELD_NAME
Definition: constants.h:57
const Time TIME_MIN(0, 1)
uint64_t file_size_
Definition: bag.h:322
std::map< ros::M_string, uint32_t > header_connection_ids_
Definition: bag.h:334
ros::Time time
timestamp of the message
Definition: structures.h:78
XmlRpcServer s
int writeHeader(roslz4_stream *str)
Buffer header_buffer_
reusable buffer in which to assemble the record header before writing to file
Definition: bag.h:342
boost::shared_ptr< T > instantiateBuffer(IndexEntry const &index_entry) const
deserializes the message held in record_buffer_
Definition: bag.h:431
Base class for rosbag exceptions.
Definition: exceptions.h:43
void swap(Bag &a, Bag &b)
Definition: bag.h:674
Exception thrown on problems reading the bag format.
Definition: exceptions.h:57
BagMode
The possible modes to open a bag in.
Definition: bag.h:86
std::string md5sum
Definition: structures.h:54
static const unsigned char OP_MSG_DATA
Definition: constants.h:76
Buffer decompress_buffer_
reusable buffer to decompress chunks into
Definition: bag.h:346
std::map< std::string, std::string > M_string
uint64_t decompressed_chunk_
position of decompressed chunk
Definition: bag.h:352
const char * datatype()
uint64_t index_data_pos_
Definition: bag.h:324
A class pointing into a bag file.
void serialize(Stream &stream, const T &t)
void writeMessageDataRecord(uint32_t conn_id, ros::Time const &time, T const &msg)
Definition: bag.h:630
boost::shared_ptr< rosbag::EncryptorBase > encryptor_
Definition: bag.h:357
Buffer * current_buffer_
Definition: bag.h:350
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:323
uint32_t bag_revision_
Definition: bag.h:320
Buffer record_buffer_
reusable buffer in which to assemble the record data before writing to file
Definition: bag.h:343
Buffer chunk_buffer_
reusable buffer to read chunk into
Definition: bag.h:345
ChunkInfo curr_chunk_info_
Definition: bag.h:330
std::map< uint32_t, std::multiset< IndexEntry > > connection_indexes_
Definition: bag.h:339
uint64_t chunk_pos
absolute byte offset of the chunk record containing the message
Definition: structures.h:79
uint32_t connection_count_
Definition: bag.h:325
M_stringPtr getValues()
uint32_t offset
relative byte offset of the message record (either definition or data) in the chunk ...
Definition: structures.h:80
uint32_t chunk_threshold_
Definition: bag.h:319
std::vector< ChunkInfo > chunks_
Definition: bag.h:337
std::string datatype
Definition: structures.h:53
ros::Time getReceiptTime() const
boost::shared_ptr< ros::M_string > header
Definition: structures.h:57
uint32_t chunk_count_
Definition: bag.h:326
uint32_t serializationLength(const T &t)
static const std::string TIME_FIELD_NAME
Definition: constants.h:60
CompressionType compression_
Definition: bag.h:318
std::map< uint32_t, std::multiset< IndexEntry > > curr_chunk_connection_indexes_
Definition: bag.h:340
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:516
uint64_t curr_chunk_data_pos_
Definition: bag.h:331
Buffer outgoing_chunk_buffer_
reusable buffer to read chunk into
Definition: bag.h:348
pluginlib::ClassLoader< rosbag::EncryptorBase > encryptor_loader_
Definition: bag.h:355
const char * md5sum()
const std::string header
boost::shared_ptr< std::map< std::string, std::string > > connection_header
ChunkedFile file_
Definition: bag.h:316
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:73
void write(std::string const &topic, ros::MessageEvent< T > const &event)
Write a message into the bag file.
Definition: bag.h:369
bool chunk_open_
Definition: bag.h:329
void readMessageDataIntoStream(IndexEntry const &index_entry, Stream &stream) const
Definition: bag.h:403


rosbag_storage
Author(s): Dirk Thomas
autogenerated on Mon Feb 28 2022 23:33:55