34 Recorder subscribes to ROS messages and writes them to a bag file.
37 from __future__
import print_function
39 from queue
import Queue
41 from Queue
import Queue
56 def __init__(self, filename, bag_lock=None, all=True, topics=[], regex=False, limit=0, master_check_interval=1.0):
58 Subscribe to ROS messages and record them to a bag file.
60 @param filename: filename of bag to write to
62 @param all: all topics are to be recorded [default: True]
64 @param topics: topics (or regexes if regex is True) to record [default: empty list]
65 @type topics: list of str
66 @param regex: topics should be considered as regular expressions [default: False]
68 @param limit: record only this number of messages on each topic (if non-positive, then unlimited) [default: 0]
70 @param master_check_interval: period (in seconds) to check master for new topic publications [default: 1]
71 @type master_check_interval: float
80 self.
_bag_lock = bag_lock
if bag_lock
else threading.Lock()
108 Add a listener which gets called whenever a message is recorded.
109 @param listener: function to call
110 @type listener: function taking (topic, message, time)
116 Start subscribing and recording messages to bag.
147 master = rosgraph.Master(
'rqt_bag_recorder')
152 for topic, datatype
in master.getPublishedTopics(
''):
162 pytype = roslib.message.get_message_class(datatype)
167 except Exception
as ex:
168 print(
'Error subscribing to %s (ignoring): %s' %
169 (topic, str(ex)), file=sys.stderr)
176 except Exception
as ex:
177 print(
'Error recording to bag: %s' % str(ex), file=sys.stderr)
186 except Exception
as ex:
187 print(
'Error closing bag [%s]: %s' % (self.
_bag.filename, str(ex)))
197 if regex.match(topic):
235 self.
_bag.write(topic, m, t)
239 listener(topic, m, t)
241 except Exception
as ex:
242 print(
'Error write to bag: %s' % str(ex), file=sys.stderr)