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


rosbag_storage
Author(s): Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:19