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


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