-
Notifications
You must be signed in to change notification settings - Fork 910
/
bag.py
2998 lines (2395 loc) · 115 KB
/
bag.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
# Software License Agreement (BSD License)
#
# Copyright (c) 2010, Willow Garage, Inc.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above
# copyright notice, this list of conditions and the following
# disclaimer in the documentation and/or other materials provided
# with the distribution.
# * Neither the name of Willow Garage, Inc. nor the names of its
# contributors may be used to endorse or promote products derived
# from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
"""
The rosbag Python API.
Provides serialization of bag files.
"""
from __future__ import print_function
import bisect
import bz2
import collections
import heapq
import os
import re
import struct
import sys
import threading
import time
import yaml
from Cryptodome.Cipher import AES
from Cryptodome.Random import random
import gnupg
try:
from cStringIO import StringIO # Python 2.x
except ImportError:
from io import BytesIO as StringIO # Python 3.x
import genmsg
import genpy
import genpy.dynamic
import genpy.message
import roslib.names # still needed for roslib.names.canonicalize_name()
import rospy
try:
import roslz4
found_lz4 = True
except ImportError:
rospy.logwarn(
'Failed to load Python extension for LZ4 support. '
'LZ4 compression will not be available.')
found_lz4 = False
class ROSBagException(Exception):
"""
Base class for exceptions in rosbag.
"""
def __init__(self, value=None):
self.value = value
#fix for #1209. needed in Python 2.7.
# For details: https://stackoverflow.com/questions/41808912/cannot-unpickle-exception-subclass
self.args = (value,)
def __str__(self):
return self.value
class ROSBagFormatException(ROSBagException):
"""
Exceptions for errors relating to the bag file format.
"""
def __init__(self, value):
ROSBagException.__init__(self, value)
class ROSBagUnindexedException(ROSBagException):
"""
Exception for unindexed bags.
"""
def __init__(self, *args):
#*args needed for #1209
ROSBagException.__init__(self, 'Unindexed bag')
class ROSBagEncryptNotSupportedException(ROSBagException):
"""
Exception raised when encryption is not supported.
"""
def __init__(self, value):
ROSBagException.__init__(self, value)
class ROSBagEncryptException(ROSBagException):
"""
Exception raised when encryption or decryption failed.
"""
def __init__(self, value):
ROSBagException.__init__(self, value)
class Compression:
"""
Allowable compression types
"""
NONE = 'none'
BZ2 = 'bz2'
LZ4 = 'lz4'
BagMessage = collections.namedtuple('BagMessage', 'topic message timestamp')
BagMessageWithConnectionHeader = collections.namedtuple('BagMessageWithConnectionHeader', 'topic message timestamp connection_header')
class _ROSBagEncryptor(object):
"""
Base class for bag encryptor.
"""
_ENCRYPTOR_FIELD_NAME = 'encryptor'
def __init__(self):
pass
class _ROSBagNoEncryptor(_ROSBagEncryptor):
"""
Class for unencrypted bags.
"""
def __init__(self):
super(_ROSBagNoEncryptor, self).__init__()
def initialize(self, _, __):
pass
def encrypt_chunk(self, chunk_size, _, __):
return chunk_size
def decrypt_chunk(self, chunk):
return chunk
def add_fields_to_file_header(self, _):
pass
def read_fields_from_file_header(self, _):
pass
def write_encrypted_header(self, write_header, f, header):
return write_header(f, header)
def read_encrypted_header(self, read_header, f, req_op=None):
return read_header(f, req_op)
def add_info_rows(self, rows):
pass
def get_info_str(self):
return ''
class _ROSBagAesCbcEncryptor(_ROSBagEncryptor):
"""
Class for AES-CBC-encrypted bags.
"""
NAME = 'rosbag/AesCbcEncryptor'
_GPG_USER_FIELD_NAME = 'gpg_user'
_ENCRYPTED_KEY_FIELD_NAME = 'encrypted_key'
def __init__(self):
"""
Create AES encryptor.
"""
super(_ROSBagAesCbcEncryptor, self).__init__()
# User name of GPG key used for symmetric key encryption
self._gpg_key_user = None
# Symmetric key for encryption/decryption
self._symmetric_key = None
# Encrypted symmetric key
self._encrypted_symmetric_key = None
def initialize(self, bag, gpg_key_user):
"""
Initialize encryptor by composing AES symmetric key.
@param bag: bag to be encrypted/decrypted
@type bag: Bag
@param gpg_key_user: user name of GPG key used for symmetric key encryption
@type gpg_key_user: str
@raise ROSBagException: if GPG key user has already been set
"""
if bag._mode != 'w':
return
if self._gpg_key_user == gpg_key_user:
return
if not self._gpg_key_user:
self._gpg_key_user = gpg_key_user
self._build_symmetric_key()
else:
raise ROSBagException('Encryption user has already been set to {}'.format(self._gpg_key_user))
def encrypt_chunk(self, chunk_size, chunk_data_pos, f):
"""
Read chunk from file, encrypt it, and write back to file.
@param chunk_size: size of chunk
@type chunk_size: int
@param chunk_data_pos: position of chunk data portion
@type chunk_data_pos: int
@param f: file stream
@type f: file
@return: size of initialization vector and encrypted chunk
@rtype: int
"""
f.seek(chunk_data_pos)
chunk = _read(f, chunk_size)
# Encrypt chunk
iv = random.getrandbits(AES.block_size)
f.seek(chunk_data_pos)
f.write(iv)
cipher = AES.new(self._symmetric_key, AES.MODE_CBC, iv)
encrypted_chunk = cipher.encrypt(_add_padding(chunk))
# Write encrypted chunk
f.write(encrypted_chunk)
f.truncate(f.tell())
return AES.block_size + len(encrypted_chunk)
def decrypt_chunk(self, encrypted_chunk):
"""
Decrypt chunk.
@param encrypted_chunk: chunk to decrypt
@type encrypted_chunk: str
@return: decrypted chunk
@rtype: str
@raise ROSBagFormatException: if size of input chunk is not multiple of AES block size
"""
if len(encrypted_chunk) % AES.block_size != 0:
raise ROSBagFormatException('Error in encrypted chunk size: {}'.format(len(encrypted_chunk)))
if len(encrypted_chunk) < AES.block_size:
raise ROSBagFormatException('No initialization vector in encrypted chunk: {}'.format(len(encrypted_chunk)))
iv = encrypted_chunk[:AES.block_size]
cipher = AES.new(self._symmetric_key, AES.MODE_CBC, iv)
decrypted_chunk = cipher.decrypt(encrypted_chunk[AES.block_size:])
return _remove_padding(decrypted_chunk)
def add_fields_to_file_header(self, header):
"""
Add encryptor information to bag file header.
@param header: bag file header
@type header: dict
"""
header[self._ENCRYPTOR_FIELD_NAME] = self.NAME
header[self._GPG_USER_FIELD_NAME] = self._gpg_key_user
header[self._ENCRYPTED_KEY_FIELD_NAME] = self._encrypted_symmetric_key
def read_fields_from_file_header(self, header):
"""
Read encryptor information from bag file header.
@param header: bag file header
@type header: dict
@raise ROSBagFormatException: if GPG key user is not found in header
"""
try:
self._encrypted_symmetric_key = _read_bytes_field(header, self._ENCRYPTED_KEY_FIELD_NAME)
except ROSBagFormatException:
raise ROSBagFormatException('Encrypted symmetric key is not found in header')
try:
self._gpg_key_user = _read_str_field(header, self._GPG_USER_FIELD_NAME)
except ROSBagFormatException:
raise ROSBagFormatException('GPG key user is not found in header')
try:
self._symmetric_key = _decrypt_string_gpg(self._encrypted_symmetric_key)
except ROSBagFormatException:
raise
def write_encrypted_header(self, _, f, header):
"""
Write encrypted header to bag file.
@param f: file stream
@type f: file
@param header: unencrypted header
@type header: dict
@return: encrypted string representing header
@rtype: str
"""
header_str = b''
equal = b'='
for k, v in header.items():
if not isinstance(k, bytes):
k = k.encode()
if not isinstance(v, bytes):
v = v.encode()
header_str += _pack_uint32(len(k) + 1 + len(v)) + k + equal + v
iv = random.getrandbits(AES.block_size)
enc_str = iv
cipher = AES.new(self._symmetric_key, AES.MODE_CBC, iv)
enc_str += cipher.encrypt(_add_padding(header_str))
_write_sized(f, enc_str)
return enc_str
def read_encrypted_header(self, _, f, req_op=None):
"""
Read encrypted header from bag file.
@param f: file stream
@type f: file
@param req_op: expected header op code
@type req_op: int
@return: decrypted header
@rtype: dict
@raise ROSBagFormatException: if error occurs while decrypting/reading header
"""
# Read header
try:
header = self._decrypt_encrypted_header(f)
except ROSBagException as ex:
raise ROSBagFormatException('Error reading header: %s' % str(ex))
return _build_header_from_str(header, req_op)
def add_info_rows(self, rows):
"""
Add rows for rosbag info.
@param rows: information on bag encryption
@type rows: list of tuples
"""
rows.append(('encryption', self.NAME))
rows.append(('GPG key user', self._gpg_key_user))
def get_info_str(self):
"""
Return string for rosbag info.
@return: information on bag encryption
@rtype: str
"""
return 'encryption: %s\nGPG key user: %s\n' % (self.NAME, self._gpg_key_user)
def _build_symmetric_key(self):
if not self._gpg_key_user:
return
self._symmetric_key = random.getrandbits(AES.block_size)
self._encrypted_symmetric_key = _encrypt_string_gpg(self._gpg_key_user, self._symmetric_key)
def _decrypt_encrypted_header(self, f):
try:
size = _read_uint32(f)
except struct.error as ex:
raise ROSBagFormatException('error unpacking uint32: %s' % str(ex))
if size % AES.block_size != 0:
raise ROSBagFormatException('Error in encrypted header size: {}'.format(size))
if size < AES.block_size:
raise ROSBagFormatException('No initialization vector in encrypted header: {}'.format(size))
iv = _read(f, AES.block_size)
size -= AES.block_size
encrypted_header = _read(f, size)
cipher = AES.new(self._symmetric_key, AES.MODE_CBC, iv)
header = cipher.decrypt(encrypted_header)
return _remove_padding(header)
def _add_padding(input_str):
# Add PKCS#7 padding to input string
return input_str + (AES.block_size - len(input_str) % AES.block_size) * chr(AES.block_size - len(input_str) % AES.block_size)
def _remove_padding(input_str):
# Remove PKCS#7 padding from input string
return input_str[:-ord(input_str[len(input_str) - 1:])]
def _encrypt_string_gpg(key_user, input):
gpg = gnupg.GPG()
enc_data = gpg.encrypt(input, [key_user], always_trust=True)
if not enc_data.ok:
raise ROSBagEncryptException('Failed to encrypt bag: {}. Have you installed a required public key?'.format(enc_data.status))
return str(enc_data)
def _decrypt_string_gpg(input):
gpg = gnupg.GPG()
dec_data = gpg.decrypt(input, passphrase='clearpath')
if not dec_data.ok:
raise ROSBagEncryptException('Failed to decrypt bag: {}. Have you installed a required private key?'.format(dec_data.status))
return dec_data.data
class Bag(object):
"""
Bag serialize messages to and from a single file on disk using the bag format.
"""
def __init__(self, f, mode='r', compression=Compression.NONE, chunk_threshold=768 * 1024, allow_unindexed=False, options=None, skip_index=False):
"""
Open a bag file. The mode can be 'r', 'w', or 'a' for reading (default),
writing or appending. The file will be created if it doesn't exist
when opened for writing or appending; it will be truncated when opened
for writing. Simultaneous reading and writing is allowed when in writing
or appending mode.
@param f: filename of bag to open or a stream to read from
@type f: str or file
@param mode: mode, either 'r', 'w', or 'a'
@type mode: str
@param compression: compression mode, see U{rosbag.Compression} for valid modes
@type compression: str
@param chunk_threshold: minimum number of uncompressed bytes per chunk
@type chunk_threshold: int
@param allow_unindexed: if True, allow opening unindexed bags
@type allow_unindexed: bool
@param options: the bag options (currently: compression and chunk_threshold)
@type options: dict
@param skip_index: if True, don't read the connection index records on open [2.0+]
@type skip_index: bool
@raise ValueError: if any argument is invalid
@raise ROSBagException: if an error occurs opening file
@raise ROSBagFormatException: if bag format is corrupted
"""
if options is not None:
if type(options) is not dict:
raise ValueError('options must be of type dict')
if 'compression' in options:
compression = options['compression']
if 'chunk_threshold' in options:
chunk_threshold = options['chunk_threshold']
self._file = None
self._filename = None
self._version = None
allowed_compressions = [Compression.NONE, Compression.BZ2]
if found_lz4:
allowed_compressions.append(Compression.LZ4)
if compression not in allowed_compressions:
raise ValueError('compression must be one of: %s' % ', '.join(allowed_compressions))
self._compression = compression
if chunk_threshold < 0:
raise ValueError('chunk_threshold must be greater than or equal to zero')
self._chunk_threshold = chunk_threshold
self._skip_index = skip_index
self._reader = None
self._file_header_pos = None
self._index_data_pos = 0 # (1.2+)
self._clear_index()
self._buffer = StringIO()
self._curr_compression = Compression.NONE
self._encryptor = _ROSBagNoEncryptor()
self._open(f, mode, allow_unindexed)
self._output_file = self._file
def __iter__(self):
return self.read_messages()
def __enter__(self):
return self
def __exit__(self, exc_type, exc_value, traceback):
self.close()
@property
def options(self):
"""Get the options."""
return { 'compression' : self._compression, 'chunk_threshold' : self._chunk_threshold }
@property
def filename(self):
"""Get the filename."""
return self._filename
@property
def version(self):
"""Get the version."""
return self._version
@property
def mode(self):
"""Get the mode."""
return self._mode
@property
def size(self):
"""Get the size in bytes."""
if not self._file:
raise ValueError('I/O operation on closed bag')
pos = self._file.tell()
self._file.seek(0, os.SEEK_END)
size = self._file.tell()
self._file.seek(pos)
return size
# compression
def _get_compression(self):
"""Get the compression method to use for writing."""
return self._compression
def _set_compression(self, compression):
"""Set the compression method to use for writing."""
allowed_compressions = [Compression.NONE, Compression.BZ2]
if found_lz4:
allowed_compressions.append(Compression.LZ4)
if compression not in allowed_compressions:
raise ValueError('compression must be one of: %s' % ', '.join(allowed_compressions))
self.flush()
self._compression = compression
compression = property(_get_compression, _set_compression)
# chunk_threshold
def _get_chunk_threshold(self):
"""Get the chunk threshold to use for writing."""
return self._chunk_threshold
def _set_chunk_threshold(self, chunk_threshold):
"""Set the chunk threshold to use for writing."""
if chunk_threshold < 0:
raise ValueError('chunk_threshold must be greater than or equal to zero')
self.flush()
self._chunk_threshold = chunk_threshold
chunk_threshold = property(_get_chunk_threshold, _set_chunk_threshold)
def read_messages(self, topics=None, start_time=None, end_time=None, connection_filter=None, raw=False, return_connection_header=False):
"""
Read messages from the bag, optionally filtered by topic, timestamp and connection details.
@param topics: list of topics or a single topic. if an empty list is given all topics will be read [optional]
@type topics: list(str) or str
@param start_time: earliest timestamp of message to return [optional]
@type start_time: U{genpy.Time}
@param end_time: latest timestamp of message to return [optional]
@type end_time: U{genpy.Time}
@param connection_filter: function to filter connections to include [optional]
@type connection_filter: function taking (topic, datatype, md5sum, msg_def, header) and returning bool
@param raw: if True, then generate tuples of (datatype, (data, md5sum, position), pytype)
@type raw: bool
@return: generator of BagMessage(topic, message, timestamp) namedtuples for each message in the bag file
@rtype: generator of tuples of (str, U{genpy.Message}, U{genpy.Time}) [not raw] or (str, (str, str, str, tuple, class), U{genpy.Time}) [raw]
"""
self.flush()
if topics and type(topics) is str:
topics = [topics]
return self._reader.read_messages(topics, start_time, end_time, connection_filter, raw, return_connection_header)
def flush(self):
"""
Write the open chunk to disk so subsequent reads will read all messages.
@raise ValueError: if bag is closed
"""
if not self._file:
raise ValueError('I/O operation on closed bag')
if self._chunk_open:
self._stop_writing_chunk()
def write(self, topic, msg, t=None, raw=False, connection_header=None):
"""
Write a message to the bag.
@param topic: name of topic
@type topic: str
@param msg: message to add to bag, or tuple (if raw)
@type msg: Message or tuple of raw message data
@param t: ROS time of message publication, if None specifed, use current time [optional]
@type t: U{genpy.Time}
@param raw: if True, msg is in raw format, i.e. (msg_type, serialized_bytes, md5sum, pytype)
@type raw: bool
@raise ValueError: if arguments are invalid or bag is closed
"""
if not self._file:
raise ValueError('I/O operation on closed bag')
if not topic:
raise ValueError('topic is invalid')
if not msg:
raise ValueError('msg is invalid')
if t is None:
t = genpy.Time.from_sec(time.time())
# Seek to end (in case previous operation was a read)
self._file.seek(0, os.SEEK_END)
# Open a chunk, if needed
if not self._chunk_open:
self._start_writing_chunk(t)
# Unpack raw
if raw:
if len(msg) == 5:
msg_type, serialized_bytes, md5sum, pos, pytype = msg
elif len(msg) == 4:
msg_type, serialized_bytes, md5sum, pytype = msg
else:
raise ValueError('msg must be of length 4 or 5')
# Write connection record, if necessary (currently using a connection per topic; ignoring message connection header)
if topic in self._topic_connections:
connection_info = self._topic_connections[topic]
conn_id = connection_info.id
else:
conn_id = len(self._connections)
if raw:
if pytype is None:
try:
pytype = genpy.message.get_message_class(msg_type)
except Exception:
pytype = None
if pytype is None:
raise ROSBagException('cannot locate message class and no message class provided for [%s]' % msg_type)
if pytype._md5sum != md5sum:
print('WARNING: md5sum of loaded type [%s] does not match that specified' % msg_type, file=sys.stderr)
#raise ROSBagException('md5sum of loaded type does not match that of data being recorded')
header = connection_header if connection_header is not None else {
'topic': topic,
'type': msg_type,
'md5sum': md5sum,
'message_definition': pytype._full_text
}
else:
header = connection_header if connection_header is not None else {
'topic': topic,
'type': msg.__class__._type,
'md5sum': msg.__class__._md5sum,
'message_definition': msg._full_text
}
connection_info = _ConnectionInfo(conn_id, topic, header)
# No need to encrypt connection records in chunk (encrypt=False)
self._write_connection_record(connection_info, False)
self._connections[conn_id] = connection_info
self._topic_connections[topic] = connection_info
# Create an index entry
index_entry = _IndexEntry200(t, self._curr_chunk_info.pos, self._get_chunk_offset())
# Update the indexes and current chunk info
if conn_id not in self._curr_chunk_connection_indexes:
# This is the first message on this connection in the chunk
self._curr_chunk_connection_indexes[conn_id] = [index_entry]
self._curr_chunk_info.connection_counts[conn_id] = 1
else:
curr_chunk_connection_index = self._curr_chunk_connection_indexes[conn_id]
if index_entry >= curr_chunk_connection_index[-1]:
# Test if we're writing chronologically. Can skip binary search if so.
curr_chunk_connection_index.append(index_entry)
else:
bisect.insort_right(curr_chunk_connection_index, index_entry)
self._curr_chunk_info.connection_counts[conn_id] += 1
if conn_id not in self._connection_indexes:
self._connection_indexes[conn_id] = [index_entry]
else:
bisect.insort_right(self._connection_indexes[conn_id], index_entry)
# Update the chunk start/end times
if t > self._curr_chunk_info.end_time:
self._curr_chunk_info.end_time = t
elif t < self._curr_chunk_info.start_time:
self._curr_chunk_info.start_time = t
if not raw:
# Serialize the message to the buffer
self._buffer.seek(0)
self._buffer.truncate(0)
msg.serialize(self._buffer)
serialized_bytes = self._buffer.getvalue()
# Write message data record
self._write_message_data_record(conn_id, t, serialized_bytes)
# Check if we want to stop this chunk
chunk_size = self._get_chunk_offset()
if chunk_size > self._chunk_threshold:
self._stop_writing_chunk()
def reindex(self):
"""
Reindexes the bag file. Yields position of each chunk for progress.
"""
self._clear_index()
return self._reader.reindex()
def close(self):
"""
Close the bag file. Closing an already closed bag does nothing.
"""
if self._file:
if self._mode in 'wa':
self._stop_writing()
self._close_file()
def get_compression_info(self):
"""
Returns information about the compression of the bag
@return: generator of CompressionTuple(compression, uncompressed, compressed) describing the
type of compression used, size of the uncompressed data in Bytes, size of the compressed data in Bytes. If
no compression is used then uncompressed and compressed data will be equal.
@rtype: generator of CompressionTuple of (str, int, int)
"""
compression = self.compression
uncompressed = 0
compressed = 0
if self._chunk_headers:
compression_counts = {}
compression_uncompressed = {}
compression_compressed = {}
# the rest of this is determine which compression algorithm is dominant and
# to add up the uncompressed and compressed Bytes
for chunk_header in self._chunk_headers.values():
if chunk_header.compression not in compression_counts:
compression_counts[chunk_header.compression] = 0
if chunk_header.compression not in compression_uncompressed:
compression_uncompressed[chunk_header.compression] = 0
if chunk_header.compression not in compression_compressed:
compression_compressed[chunk_header.compression] = 0
compression_counts[chunk_header.compression] += 1
compression_uncompressed[chunk_header.compression] += chunk_header.uncompressed_size
uncompressed += chunk_header.uncompressed_size
compression_compressed[chunk_header.compression] += chunk_header.compressed_size
compressed += chunk_header.compressed_size
chunk_count = len(self._chunk_headers)
main_compression_count, main_compression = sorted([(v, k) for k, v in compression_counts.items()], reverse=True)[0]
compression = str(main_compression)
return collections.namedtuple("CompressionTuple", ["compression",
"uncompressed", "compressed"])(compression=compression,
uncompressed=uncompressed, compressed=compressed)
def get_message_count(self, topic_filters=None):
"""
Returns the number of messages in the bag. Can be filtered by Topic
@param topic_filters: One or more topics to filter by
@type topic_filters: Could be either a single str or a list of str.
@return: The number of messages in the bag, optionally filtered by topic
@rtype: int
"""
num_messages = 0
if topic_filters is not None:
info = self.get_type_and_topic_info(topic_filters=topic_filters)
for topic in info.topics.values():
num_messages += topic.message_count
else:
if self._chunks:
for c in self._chunks:
for counts in c.connection_counts.values():
num_messages += counts
else:
num_messages = sum([len(index) for index in self._connection_indexes.values()])
return num_messages
def get_start_time(self):
"""
Returns the start time of the bag.
@return: a timestamp of the start of the bag
@rtype: float, timestamp in seconds, includes fractions of a second
"""
if self._chunks:
start_stamp = self._chunks[0].start_time.to_sec()
else:
if not self._connection_indexes:
raise ROSBagException('Bag contains no message')
start_stamps = [index[0].time.to_sec() for index in self._connection_indexes.values() if index]
start_stamp = min(start_stamps) if start_stamps else 0
return start_stamp
def get_end_time(self):
"""
Returns the end time of the bag.
@return: a timestamp of the end of the bag
@rtype: float, timestamp in seconds, includes fractions of a second
"""
if self._chunks:
end_stamp = self._chunks[-1].end_time.to_sec()
else:
if not self._connection_indexes:
raise ROSBagException('Bag contains no message')
end_stamps = [index[-1].time.to_sec() for index in self._connection_indexes.values() if index]
end_stamp = max(end_stamps) if end_stamps else 0
return end_stamp
def get_type_and_topic_info(self, topic_filters=None):
"""
Coallates info about the type and topics in the bag.
Note, it would be nice to filter by type as well, but there appear to be some limitations in the current architecture
that prevent that from working when more than one message type is written on the same topic.
@param topic_filters: specify one or more topic to filter by.
@type topic_filters: either a single str or a list of str.
@return: generator of TypesAndTopicsTuple(types{key:type name, val: md5hash},
topics{type: msg type (Ex. "std_msgs/String"),
message_count: the number of messages of the particular type,
connections: the number of connections,
frequency: the data frequency,
key: type name,
val: md5hash}) describing the types of messages present
and information about the topics
@rtype: TypesAndTopicsTuple(dict(str, str),
TopicTuple(str, int, int, float, str, str))
"""
datatypes = set()
datatype_infos = []
for connection in self._connections.values():
if connection.datatype in datatypes:
continue
datatype_infos.append((connection.datatype, connection.md5sum, connection.msg_def))
datatypes.add(connection.datatype)
topics = []
# load our list of topics and optionally filter
if topic_filters is not None:
if not isinstance(topic_filters, list):
topic_filters = [topic_filters]
topics = topic_filters
else:
topics = [c.topic for c in self._get_connections()]
topics = sorted(set(topics))
topic_datatypes = {}
topic_conn_counts = {}
topic_msg_counts = {}
topic_freqs_median = {}
for topic in topics:
connections = list(self._get_connections(topic))
if not connections:
continue
topic_datatypes[topic] = connections[0].datatype
topic_conn_counts[topic] = len(connections)
msg_count = 0
for connection in connections:
for chunk in self._chunks:
msg_count += chunk.connection_counts.get(connection.id, 0)
topic_msg_counts[topic] = msg_count
if self._connection_indexes_read:
stamps = [entry.time.to_sec() for entry in self._get_entries(connections)]
if len(stamps) > 1:
periods = [s1 - s0 for s1, s0 in zip(stamps[1:], stamps[:-1])]
med_period = _median(periods)
if med_period > 0.0:
topic_freqs_median[topic] = 1.0 / med_period
# process datatypes
types = {}
for datatype, md5sum, msg_def in sorted(datatype_infos):
types[datatype] = md5sum
# process topics
topics_t = {}
TopicTuple = collections.namedtuple("TopicTuple", ["msg_type", "message_count", "connections", "frequency"])
for topic in sorted(topic_datatypes.keys()):
topic_msg_count = topic_msg_counts[topic]
frequency = topic_freqs_median[topic] if topic in topic_freqs_median else None
topics_t[topic] = TopicTuple(msg_type=topic_datatypes[topic],
message_count=topic_msg_count,
connections=topic_conn_counts[topic],
frequency=frequency)
return collections.namedtuple("TypesAndTopicsTuple", ["msg_types", "topics"])(msg_types=types, topics=topics_t)
def set_encryptor(self, encryptor=None, param=None):
if self._chunks:
raise ROSBagException('Cannot set encryptor after chunks are written')
if encryptor is None:
self._encryptor = _ROSBagNoEncryptor()
elif encryptor == _ROSBagAesCbcEncryptor.NAME:
if sys.platform == 'win32':
raise ROSBagEncryptNotSupportedException('AES CBC encryptor is not supported for Windows')
else:
self._encryptor = _ROSBagAesCbcEncryptor()
else:
self._encryptor = _ROSBagNoEncryptor()
self._encryptor.initialize(self, param)
def __str__(self):
rows = []
try:
if self._filename:
rows.append(('path', self._filename))
if self._version == 102 and type(self._reader) == _BagReader102_Unindexed:
rows.append(('version', '1.2 (unindexed)'))
else:
rows.append(('version', '%d.%d' % (int(self._version / 100), self._version % 100)))
if not self._connection_indexes and not self._chunks:
rows.append(('size', _human_readable_size(self.size)))
else:
if self._chunks:
start_stamp = self._chunks[ 0].start_time.to_sec()
end_stamp = self._chunks[-1].end_time.to_sec()
else:
start_stamps = [index[0].time.to_sec() for index in self._connection_indexes.values() if index]
start_stamp = min(start_stamps) if start_stamps else 0
end_stamps = [index[-1].time.to_sec() for index in self._connection_indexes.values() if index]
end_stamp = max(end_stamps) if end_stamps else 0
# Show duration
duration = end_stamp - start_stamp
dur_secs = duration % 60
dur_mins = int(duration / 60)
dur_hrs = int(dur_mins / 60)
if dur_hrs > 0:
dur_mins = dur_mins % 60
duration_str = '%dhr %d:%02ds (%ds)' % (dur_hrs, dur_mins, dur_secs, duration)
elif dur_mins > 0:
duration_str = '%d:%02ds (%ds)' % (dur_mins, dur_secs, duration)
else:
duration_str = '%.1fs' % duration
rows.append(('duration', duration_str))
# Show start and end times
rows.append(('start', '%s (%.2f)' % (_time_to_str(start_stamp), start_stamp)))
rows.append(('end', '%s (%.2f)' % (_time_to_str(end_stamp), end_stamp)))
rows.append(('size', _human_readable_size(self.size)))
if self._chunks:
num_messages = 0
for c in self._chunks:
for counts in c.connection_counts.values():
num_messages += counts
else:
num_messages = sum([len(index) for index in self._connection_indexes.values()])
rows.append(('messages', str(num_messages)))
# Show compression information
if len(self._chunk_headers) == 0:
rows.append(('compression', 'none'))
else:
compression_counts = {}
compression_uncompressed = {}
compression_compressed = {}
for chunk_header in self._chunk_headers.values():
if chunk_header.compression not in compression_counts:
compression_counts[chunk_header.compression] = 1
compression_uncompressed[chunk_header.compression] = chunk_header.uncompressed_size
compression_compressed[chunk_header.compression] = chunk_header.compressed_size
else:
compression_counts[chunk_header.compression] += 1
compression_uncompressed[chunk_header.compression] += chunk_header.uncompressed_size
compression_compressed[chunk_header.compression] += chunk_header.compressed_size
chunk_count = len(self._chunk_headers)
compressions = []
for count, compression in reversed(sorted([(v, k) for k, v in compression_counts.items()])):
if compression != Compression.NONE: