5------------------------------------------------------------------------------
6This file is part of grepros - grep for ROS bag files and live topics.
7Released under the BSD License.
12------------------------------------------------------------------------------
14## @namespace grepros.ros1
35from . api import TypeMeta, calculate_definition_hash, parse_definition_subtypes
36from . common import ConsolePrinter, memoize
39## Bagfile extensions to seek
40BAG_EXTENSIONS = (".bag",
".bag.active")
43SKIP_EXTENSIONS = (
".bag.orig.active", )
46ROS_TIME_TYPES = [
"time",
"duration"]
49ROS_TIME_CLASSES = {rospy.Time:
"time", rospy.Duration:
"duration"}
52ROS_ALIAS_TYPES = {
"byte":
"int8",
"char":
"uint8"}
64genpy_mtx = threading.RLock()
69 ROS1 bag reader and writer.
71 Extends `rosbag.Bag`
with more conveniences, smooths over the rosbag bug of ignoring
72 topic
and time filters
in format v1.2,
and smooths over the rosbag bug
73 of yielding messages of wrong type,
if message types
in different topics
74 have different packages but identical fields
and hashes.
76 Does **
not** smooth over the rosbag bug of writing different types to one topic.
78 rosbag does allow writing messages of different types to one topic,
79 just like live ROS topics can have multiple message types published
80 to one topic. And their serialized bytes will actually be
in the bag,
81 but rosbag will only register the first type
for this topic (unless it
is
82 explicitly given another connection header
with metadata on the other type).
84 All messages yielded will be deserialized by rosbag
as that first type,
85 and whether reading will
raise an exception
or not depends on whether
86 the other type has enough bytes to be deserialized
as that first type.
101 @param f bag file path,
or a stream object
102 @param mode mode to open bag
in, defaults to
"r" (read mode)
103 @param reindex
if true
and bag
is unindexed, make a copy
104 of the file (unless unindexed format)
and reindex original
105 @param progress show progress bar
with reindexing status
106 @param kwargs additional keyword arguments
for `rosbag.Bag`, like `compression`
110 f, args = (args[0]
if args
else kwargs.pop(
"f")), args[1:]
111 mode, args = (args[0]
if args
else kwargs.pop(
"mode",
"r")), args[1:]
112 if mode
not in self.
MODES:
raise ValueError(
"invalid mode %r" % mode)
114 kwargs.setdefault(
"skip_index",
True)
115 reindex, progress = (kwargs.pop(k,
False)
for k
in (
"reindex",
"progress"))
116 getargspec = getattr(inspect,
"getfullargspec", getattr(inspect,
"getargspec",
None))
117 for n
in set(kwargs) - set(getargspec(rosbag.Bag.__init__).args): kwargs.pop(n)
119 if common.is_stream(f):
120 if not common.verify_io(f, mode):
121 raise io.UnsupportedOperation({
"r":
"read",
"w":
"write",
"a":
"append"}[mode])
122 super(ROS1Bag, self).
__init__(f, mode, *args, **kwargs)
127 if "a" == mode
and (
not os.path.exists(f)
or not os.path.getsize(f)):
129 os.path.exists(f)
and os.remove(f)
132 super(ROS1Bag, self).
__init__(f, mode, *args, **kwargs)
133 except rosbag.ROSBagUnindexedException:
134 if not reindex:
raise
135 Bag.reindex_file(f, progress, *args, **kwargs)
136 super(ROS1Bag, self).
__init__(f, mode, *args, **kwargs)
141 """Returns ROS1 message type definition full text from bag, including subtype definitions."""
143 return self.
__TYPEDEFS.get((msg_or_type._type, msg_or_type._md5sum))
144 typename = msg_or_type
145 return next((d
for (n, h), d
in self.
__TYPEDEFS.items()
if n == typename),
None)
150 Returns rospy message class for typename, or None if unknown type.
152 Generates
class dynamically if not already generated.
154 @param typehash message type definition hash,
if any
157 typehash = typehash
or next((h
for n, h
in self.
__TYPEDEFS if n == typename),
None)
158 typekey = (typename, typehash)
161 self.
__TYPES[(n, c._md5sum)] = c
162 return self.
__TYPES.get(typekey)
166 """Returns ROS1 message type MD5 hash, or None if unknown type."""
168 typename = msg_or_type
169 typehash =
next((h
for n, h
in self.
__TYPEDEFS if n == typename),
None)
172 typehash =
next((h
for n, h
in self.
__TYPEDEFS if n == typename),
None)
177 """Returns the start time of the bag, as UNIX timestamp, or None if bag empty."""
179 except Exception:
return None
183 """Returns the end time of the bag, as UNIX timestamp, or None if bag empty."""
185 except Exception:
return None
189 """Returns topic and message type metainfo as {(topic, typename, typehash): count}."""
193 def read_messages(self, topics=None, start_time=None, end_time=None,
194 raw=False, connection_filter=None, **__):
196 Yields messages from the bag, optionally filtered by topic, timestamp
and connection details.
198 @param topics list of topics
or a single topic.
199 If an empty list
is given, all topics will be read.
200 @param start_time earliest timestamp of messages to
return,
201 as ROS time
or convertible (int/float/duration/datetime/decimal)
202 @param end_time latest timestamp of messages to
return,
203 as ROS time
or convertible (int/float/duration/datetime/decimal)
204 @param connection_filter function to filter connections to include
205 @param raw
if true, then returned messages are tuples of
206 (typename, bytes, typehash, typeclass)
207 or (typename, bytes, typehash, position, typeclass),
208 depending on file format
209 @return BagMessage namedtuples of
210 (topic, message, timestamp
as rospy.Time)
213 if "w" == self._mode:
raise io.UnsupportedOperation(
"read")
216 for n, h
in self.
__TYPEDEFS: hashtypes.setdefault(h, []).append(n)
217 read_topics = topics
if isinstance(topics, (dict, list, set, tuple))
else \
218 [topics]
if topics
else None
219 dupes = {t: (n, h)
for t, n, h
in self.
__topics
220 if (read_topics
is None or t
in read_topics)
and len(hashtypes.get(h, [])) > 1}
223 if self.version != 102
or (
not topics
and start_time
is None and end_time
is None):
224 in_range =
lambda *_:
True
225 else: in_range =
lambda t, s: ((
not read_topics
or t
in read_topics)
and
226 (start_time
is None or s >= start_time)
and
227 (end_time
is None or s <= end_time))
229 start_time, end_time = map(to_time, (start_time, end_time))
230 kwargs = dict(topics=topics, start_time=start_time, end_time=end_time,
231 connection_filter=connection_filter, raw=raw)
233 for topic, msg, stamp
in super(ROS1Bag, self).
read_messages(**kwargs):
234 if in_range(topic, stamp):
235 TypeMeta.make(msg, topic, self)
240 for topic, msg, stamp
in super(ROS1Bag, self).
read_messages(**kwargs):
241 if not in_range(topic, stamp):
continue
245 typename, typehash = (msg[0], msg[2])
if raw
else (msg._type, msg._md5sum)
246 if dupes[topic] != (typename, typehash):
251 TypeMeta.make(msg, topic, self)
256 def write(self, topic, msg, t=None, raw=False, connection_header=None, **__):
258 Writes a message to the bag.
260 Populates connection header if topic already
in bag but
with a different message type.
262 @param topic name of topic
263 @param msg ROS1 message
264 @param t message timestamp
if not using current wall time,
265 as ROS time
or convertible (int/float/duration/datetime/decimal)
266 @param raw
if true, `msg`
is in raw format,
267 (typename, bytes, typehash, typeclass)
268 @param connection_header custom connection record
for topic,
269 as {
"topic",
"type",
"md5sum",
"message_definition"}
272 if "r" == self._mode:
raise io.UnsupportedOperation(
"write")
274 return super(ROS1Bag, self).
write(topic, msg,
to_time(t), raw, connection_header)
278 """Opens the bag file if not already open."""
284 """Closes the bag file."""
286 super(ROS1Bag, self).
close()
292 """Returns whether bag contains given topic."""
293 return any(key == t
for t, _, _
in self.
__topics)
297 """Retrieves next message from bag as (topic, message, timestamp)."""
305 """Returns the list of topics in bag, in alphabetic order."""
306 return sorted((t
for t, _, _
in self.
__topics), key=str.lower)
311 """Returns whether file is closed."""
312 return not self._file
315 def _convert_message(self, msg, typename2, typehash2=None):
316 """Returns message converted to given type; fields must match."""
320 v1 = v2 = getattr(msg, fname)
321 if ftypename != fields2.get(fname, ftypename):
323 setattr(msg2, fname, v2)
327 def _populate_meta(self):
328 """Populates topics and message type definitions and hashes."""
329 result = collections.Counter()
330 counts = collections.Counter()
331 for c
in self._chunks:
332 for c_id, count
in c.connection_counts.items():
333 counts[c_id] += count
334 for c
in self._connections.values():
335 result[(c.topic, c.datatype, c.md5sum)] += counts[c.id]
336 self.
__TYPEDEFS[(c.datatype, c.md5sum)] = c.msg_def
340 def _register_write(self, topic, msg, raw=False, connection_header=None):
341 """Registers message in local metadata, writes connection header if new type for topic."""
342 if raw: typename, typehash, typeclass = msg[0], msg[2], msg[3]
343 else: typename, typehash, typeclass = msg._type, msg._md5sum, type(msg)
344 topickey, typekey = (topic, typename, typehash), (typename, typehash)
347 and any(topic == t
and typekey != (n, h)
for t, n, h
in self.
__topics):
349 if not connection_header:
350 connection_header = {
"topic": topic,
"type": typename,
"md5sum": typehash,
351 "message_definition": typeclass._full_text}
352 conn_id = len(self._connections)
353 connection_info = rosbag.bag._ConnectionInfo(conn_id, topic, connection_header)
354 self._write_connection_record(connection_info, encrypt=
False)
355 self._connections[conn_id] = self._topic_connections[topic] = connection_info
357 self.
__TYPES.setdefault(typekey, typeclass)
358 self.
__TYPEDEFS.setdefault(typekey, typeclass._full_text)
362 def _ensure_typedef(self, typename, typehash=None):
363 """Parses subtype definition from any full definition where available, if not loaded."""
364 typehash = typehash
or next((h
for n, h
in self.
__TYPEDEFS if n == typename),
None)
365 typekey = (typename, typehash)
367 for (roottype, roothash), rootdef
in list(self.
__TYPEDEFS.items()):
368 rootkey = (roottype, roothash)
371 subdefs = tuple(parse_definition_subtypes(rootdef).items())
372 subhashes = {n: calculate_definition_hash(n, d, subdefs)
for n, d
in subdefs}
373 self.
__TYPEDEFS.update(((n, subhashes[n]), d)
for n, d
in subdefs)
374 self.
__PARSEDS.update(((n, h),
True)
for n, h
in subhashes.items())
384 Reindexes bag, making a backup copy in file directory.
386 @param progress show progress bar
for reindexing status
388 KWS = ["mode",
"compression",
"chunk_threshold",
389 "allow_unindexed",
"options",
"skip_index"]
390 kwargs.update(zip(KWS, args), allow_unindexed=
True)
391 copied, bar, f2 =
False,
None,
None
393 fmt =
lambda s: common.format_bytes(s, strip=
False)
394 name, size = os.path.basename(f), os.path.getsize(f)
395 aftertemplate =
" Reindexing %s (%s): {afterword}" % (name, fmt(size))
398 ConsolePrinter.warn(
"Unindexed bag %s, reindexing.", f)
399 bar
and bar.update(0).start()
401 with rosbag.Bag(f, **kwargs)
as inbag:
402 inplace = (inbag.version > 102)
404 f2 =
"%s.orig%s" % os.path.splitext(f)
408 inbag, outbag =
None,
None
409 outkwargs = dict(kwargs, mode=
"a" if inplace
else "w", allow_unindexed=
True)
411 inbag = rosbag.Bag(f2, **dict(kwargs, mode=
"r"))
412 outbag = rosbag.Bag(f, **outkwargs)
413 Bag._run_reindex(inbag, outbag, bar)
414 bar
and bar.update(bar.max)
415 except BaseException:
416 inbag
and inbag.close()
417 outbag
and outbag.close()
418 copied
and shutil.move(f2, f)
420 finally: bar
and bar.update(bar.value, flush=
True).stop()
426 def _run_reindex(inbag, outbag, bar=None):
427 """Runs reindexing, showing optional progress bar."""
428 update_bar = noop =
lambda s:
None
429 indexbag, writebag = (inbag, outbag)
if inbag.version == 102
else (outbag,
None)
431 fmt =
lambda s: common.format_bytes(s, strip=
False)
432 update_bar =
lambda s: (setattr(bar,
"afterword", fmt(s)),
433 setattr(bar,
"pulse",
False), bar.update(s).stop())
436 progress = update_bar
if not writebag
else noop
437 for offset
in indexbag.reindex():
442 progress = update_bar
if bar
else noop
443 for (topic, msg, t, header)
in indexbag.read_messages(return_connection_header=
True):
444 writebag.write(topic, msg, t, connection_header=header)
445 progress(indexbag._file.tell())
452 Initializes a ROS1 node if not already initialized.
454 Blocks until ROS master available.
461 master = rospy.client.get_master()
464 try: uri = master.getUri()[-1]
466 if available
is None:
467 ConsolePrinter.log(logging.ERROR,
468 "Unable to register with master. Will keep trying.")
470 time.sleep(SLEEP_INTERVAL)
472 ConsolePrinter.debug(
"Connected to ROS master at %s.", uri)
474 try: rospy.get_rostime()
476 rospy.init_node(name, anonymous=
True, disable_signals=
True)
480 """Shuts down live ROS1 node."""
484 rospy.signal_shutdown(
"Close grepros")
489 Returns whether ROS1 environment is set, prints error
if not.
491 @param live whether environment must support launching a ROS node
493 VARS = ["ROS_MASTER_URI",
"ROS_ROOT",
"ROS_VERSION"]
if live
else [
"ROS_VERSION"]
494 missing = [k
for k
in VARS
if not os.getenv(k)]
496 ConsolePrinter.error(
"ROS environment not sourced: missing %s.",
497 ", ".join(sorted(missing)))
498 if "1" != os.getenv(
"ROS_VERSION",
"1"):
499 ConsolePrinter.error(
"ROS environment not supported: need ROS_VERSION=1.")
507 Returns "pkg/Type" for "pkg/subdir/Type".
509 @param unbounded drop array bounds, e.g. returning
"uint8[]" for "uint8[10]"
511 if typename
and typename.count(
"/") > 1:
512 typename =
"%s/%s" % tuple((x[0], x[-1])
for x
in [typename.split(
"/")])[0]
513 if unbounded
and typename
and "[" in typename:
514 typename = typename[:typename.index(
"[")] +
"[]"
519 """Returns a rospy.Publisher."""
520 def pub_unregister():
522 if not pub.get_num_connections(): super(rospy.Publisher, pub).unregister()
524 cls = cls_or_typename
526 pub = rospy.Publisher(topic, cls, queue_size=queue_size)
527 pub.unregister = pub_unregister
533 Returns a rospy.Subscriber.
535 Local message packages are not required. Subscribes
as AnyMsg,
536 creates message
class dynamically from connection info,
537 and deserializes message before providing to handler.
542 The supplementary .get_message_xyz() methods should only be invoked after at least one message
543 has been received
from the topic,
as they get populated
from live connection metadata.
546 if msg._connection_header[
"type"] != typename:
548 typekey = (typename, msg._connection_header[
"md5sum"])
549 if typekey
not in TYPECLASSES:
550 typedef = msg._connection_header[
"message_definition"]
552 TYPECLASSES.setdefault((name, cls._md5sum), cls)
553 if isinstance(msg, rospy.AnyMsg):
554 try: msg = TYPECLASSES[typekey]().deserialize(msg._buff)
555 except Exception
as e:
556 ConsolePrinter.error(
"Error deserializing message in topic %r (%s): %s",
561 sub = rospy.Subscriber(topic, rospy.AnyMsg, myhandler, queue_size=queue_size)
562 sub.get_message_class =
lambda: next(c
for (n, h), c
in TYPECLASSES.items()
565 for (n, h), c
in TYPECLASSES.items()
if n == typename)
566 sub.get_message_type_hash =
lambda: next(h
for n, h
in TYPECLASSES
if n == typename)
567 sub.get_qoses =
lambda:
None
573 Returns a message attribute value as string.
575 Result
is at least 10 chars wide
if message
is a ROS time/duration
576 (aligning seconds
and nanoseconds).
578 LENS = {"secs": 10,
"nsecs": 9}
580 if not isinstance(msg, genpy.TVal)
or name
not in LENS:
583 EXTRA = sum(v.count(x) * len(x)
for x
in (common.MatchMarkers.START, common.MatchMarkers.END))
584 return (
"%%%ds" % (LENS[name] + EXTRA)) % v
590 Generates ROS message classes dynamically from given name
and definition.
592 Modifies `sys.path` to include the generated Python module.
594 @param typename message type name like
"std_msgs/String"
595 @param typedef message type definition full text, including all subtype definitions
596 @return dictionary of {typename: typeclass}
for message type
and all subtypes
598 with genpy_mtx:
return genpy.dynamic.generate_dynamic(typename, typedef)
603 """Returns ROS1 message class."""
604 if typename
in ROS_TIME_TYPES:
605 return next(k
for k, v
in ROS_TIME_CLASSES.items()
if v == typename)
606 if typename
in (
"genpy/Time",
"rospy/Time"):
608 if typename
in (
"genpy/Duration",
"rospy/Duration"):
609 return rospy.Duration
610 try:
return roslib.message.get_message_class(typename)
611 except Exception:
return None
616 Returns ROS1 message type definition full text, including subtype definitions.
618 Returns None if unknown type.
621 return getattr(msg_or_cls,
"_full_text",
None)
625 """Returns ROS message type MD5 hash, or "" if unknown type."""
627 return getattr(msg_or_cls,
"_md5sum",
"")
632 Returns OrderedDict({field name: field type name}) if ROS1 message,
else {}.
634 @param val ROS1 message
class or instance
636 names, types = (getattr(val, k, []) for k
in (
"__slots__",
"_slot_types"))
638 if isinstance(val, genpy.TVal): names, types = genpy.TVal.__slots__, [
"uint32",
"uint32"]
639 return collections.OrderedDict(zip(names, types))
643 """Returns ROS1 message type name, like "std_msgs/Header"."""
645 cls = msg_or_cls
if inspect.isclass(msg_or_cls)
else type(msg_or_cls)
646 return "duration" if "duration" in cls.__name__.lower()
else "time"
647 return msg_or_cls._type
652 Returns object attribute value, with numeric arrays converted to lists.
654 @param name message attribute name
655 @param typename value ROS type name,
for identifying byte arrays
656 @param default value to
return if attribute does
not exist; raises exception otherwise
658 if default
is not Ellipsis
and not hasattr(msg, name):
return default
659 v = getattr(msg, name)
660 listifiable = typename
and typename.startswith((
"uint8[",
"char["))
and isinstance(v, bytes)
661 if six.PY2
and listifiable:
662 listifiable = v[:1] !=
"[" or v[-1:] !=
"]" or common.MatchMarkers.START
not in v
663 return list(bytearray(v))
if listifiable
else v
664 return list(v)
if listifiable
or isinstance(v, tuple)
else v
669 Returns current ROS1 time, as rospy.Time.
671 @param fallback use wall time
if node
not initialized
673 try:
return rospy.get_rostime()
675 if fallback:
return make_time(time.time())
681 Returns currently available ROS1 topics, as [(topicname, typename)].
683 Omits topics that the current ROS1 node itself has published.
685 result, myname = [], rospy.get_name()
686 pubs, _, _ = master.getSystemState()[-1]
687 mypubs = [t for t, nn
in pubs
if myname
in nn
and t
not in (
"/rosout",
"/rosout_agg")]
688 for topic, typename
in master.getTopicTypes()[-1]:
689 if topic
not in mypubs:
690 result.append((topic, typename))
696 Returns whether value is a ROS1 message
or special like ROS1 time/duration
class or instance.
698 @param ignore_time whether to ignore ROS1 time/duration types
700 isfunc = issubclass if inspect.isclass(val)
else isinstance
701 return isfunc(val, genpy.Message
if ignore_time
else (genpy.Message, genpy.TVal))
705 """Returns whether value is a ROS1 time/duration class or instance."""
706 return issubclass(val, genpy.TVal)
if inspect.isclass(val)
else isinstance(val, genpy.TVal)
710 """Returns a ROS1 duration, as rospy.Duration."""
711 return rospy.Duration(secs=secs, nsecs=nsecs)
715 """Returns a ROS1 time, as rospy.Time."""
716 return rospy.Time(secs=secs, nsecs=nsecs)
720 """Returns ROS1 message as a serialized binary."""
721 with TypeMeta.make(msg)
as m:
722 if m.data
is not None:
return m.data
725 return buf.getvalue()
729 """Returns ROS1 message or service request/response instantiated from serialized binary."""
730 cls = cls_or_typename
732 return cls().deserialize(raw)
738 Returns scalar type from ROS message data type, like
"uint8" from "uint8[100]".
740 Returns type unchanged
if already a scalar.
742 return typename[:typename.index(
"[")]
if typename
and "[" in typename
else typename
746 """Sets message or object attribute value."""
747 setattr(obj, name, value)
751 """Returns value as ROS1 duration if convertible (int/float/time/datetime/decimal), else value."""
753 if isinstance(val, decimal.Decimal):
754 result = rospy.Duration(int(val), float(val % 1) * 10**9)
755 elif isinstance(val, datetime.datetime):
756 result = rospy.Duration(int(val.timestamp()), 1000 * val.microsecond)
757 elif isinstance(val, (float, int)):
758 result = rospy.Duration(val)
759 elif isinstance(val, rospy.Time):
760 result = rospy.Duration(val.secs, val.nsecs)
765 """Returns value in nanoseconds if value is ROS time/duration, else value."""
766 return val.to_nsec()
if isinstance(val, genpy.TVal)
else val
770 """Returns value in seconds if value is ROS1 time/duration, else value."""
771 return val.to_sec()
if isinstance(val, genpy.TVal)
else val
775 """Returns value as (seconds, nanoseconds) if value is ROS1 time/duration, else value."""
776 return (val.secs, val.nsecs)
if isinstance(val, genpy.TVal)
else val
780 """Returns value as ROS1 time if convertible (int/float/duration/datetime/decimal), else value."""
782 if isinstance(val, decimal.Decimal):
783 result = rospy.Time(int(val), float(val % 1) * 10**9)
784 elif isinstance(val, datetime.datetime):
785 result = rospy.Time(int(val.timestamp()), 1000 * val.microsecond)
786 elif isinstance(val, six.integer_types + (float, )):
787 result = rospy.Time(val)
788 elif isinstance(val, genpy.Duration):
789 result = rospy.Time(val.secs, val.nsecs)
794 "BAG_EXTENSIONS",
"ROS_ALIAS_TYPES",
"ROS_TIME_CLASSES",
"ROS_TIME_TYPES",
"SKIP_EXTENSIONS",
795 "SLEEP_INTERVAL",
"TYPECLASSES",
"Bag",
"ROS1Bag",
"master",
796 "canonical",
"create_publisher",
"create_subscriber",
"deserialize_message",
797 "format_message_value",
"generate_message_classes",
"get_message_class",
798 "get_message_definition",
"get_message_fields",
"get_message_type",
"get_message_type_hash",
799 "get_message_value",
"get_rostime",
"get_topic_types",
"init_node",
"is_ros_message",
800 "is_ros_time",
"make_duration",
"make_time",
"scalar",
"serialize_message",
"set_message_value",
801 "shutdown_node",
"to_duration",
"to_nsec",
"to_sec",
"to_sec_nsec",
"to_time",
"validate",
tuple MODES
Supported opening modes, overridden in subclasses.
BagMessage
Returned from read_messages() as (topic name, ROS message, ROS timestamp object).
mode
Returns file open mode.
filename
Returns bag file path.
get_message_class(self, typename, typehash=None)
Returns ROS message type class, or None if unknown message type for bag.
read_messages(self, topics=None, start_time=None, end_time=None, raw=False, **__)
Yields messages from the bag, optionally filtered by topic and timestamp.
closed
Returns whether file is closed.
A simple ASCII progress bar with a ticker thread.
ROS1 bag reader and writer.
open(self)
Opens the bag file if not already open.
__init__(self, *args, **kwargs)
get_start_time(self)
Returns the start time of the bag, as UNIX timestamp, or None if bag empty.
get_end_time(self)
Returns the end time of the bag, as UNIX timestamp, or None if bag empty.
get_message_class(self, typename, typehash=None)
Returns rospy message class for typename, or None if unknown type.
get_message_type_hash(self, msg_or_type)
Returns ROS1 message type MD5 hash, or None if unknown type.
get_topic_info(self, *_, **__)
Returns topic and message type metainfo as {(topic, typename, typehash): count}.
close(self)
Closes the bag file.
reindex_file(f, progress, *args, **kwargs)
Reindexes bag, making a backup copy in file directory.
__contains__(self, key)
Returns whether bag contains given topic.
closed
Returns whether file is closed.
topics
Returns the list of topics in bag, in alphabetic order.
__next__(self)
Retrieves next message from bag as (topic, message, timestamp).
get_message_definition(self, msg_or_type)
Returns ROS1 message type definition full text from bag, including subtype definitions.
read_messages(self, topics=None, start_time=None, end_time=None, raw=False, connection_filter=None, **__)
Yields messages from the bag, optionally filtered by topic, timestamp and connection details.
write(self, topic, msg, t=None, raw=False, connection_header=None, **__)
Writes a message to the bag.
canonical(typename, unbounded=False)
Returns "pkg/Type" for "pkg/subdir/Type".
create_publisher(topic, cls_or_typename, queue_size)
Returns a rospy.Publisher.
serialize_message(msg)
Returns ROS1 message as a serialized binary.
to_sec(val)
Returns value in seconds if value is ROS1 time/duration, else value.
get_topic_types()
Returns currently available ROS1 topics, as [(topicname, typename)].
format_message_value(msg, name, value)
Returns a message attribute value as string.
get_message_value(msg, name, typename=None, default=Ellipsis)
Returns object attribute value, with numeric arrays converted to lists.
get_message_class(typename)
Returns ROS1 message class.
to_duration(val)
Returns value as ROS1 duration if convertible (int/float/time/datetime/decimal), else value.
make_time(secs=0, nsecs=0)
Returns a ROS1 time, as rospy.Time.
deserialize_message(raw, cls_or_typename)
Returns ROS1 message or service request/response instantiated from serialized binary.
get_message_type(msg_or_cls)
Returns ROS1 message type name, like "std_msgs/Header".
get_message_definition(msg_or_type)
Returns ROS1 message type definition full text, including subtype definitions.
validate(live=False)
Returns whether ROS1 environment is set, prints error if not.
scalar(typename)
Returns scalar type from ROS message data type, like "uint8" from "uint8[100]".
make_duration(secs=0, nsecs=0)
Returns a ROS1 duration, as rospy.Duration.
create_subscriber(topic, typename, handler, queue_size)
Returns a rospy.Subscriber.
get_rostime(fallback=False)
Returns current ROS1 time, as rospy.Time.
to_nsec(val)
Returns value in nanoseconds if value is ROS time/duration, else value.
to_time(val)
Returns value as ROS1 time if convertible (int/float/duration/datetime/decimal), else value.
shutdown_node()
Shuts down live ROS1 node.
set_message_value(obj, name, value)
Sets message or object attribute value.
is_ros_time(val)
Returns whether value is a ROS1 time/duration class or instance.
get_message_type_hash(msg_or_type)
Returns ROS message type MD5 hash, or "" if unknown type.
to_sec_nsec(val)
Returns value as (seconds, nanoseconds) if value is ROS1 time/duration, else value.
init_node(name)
Initializes a ROS1 node if not already initialized.
is_ros_message(val, ignore_time=False)
Returns whether value is a ROS1 message or special like ROS1 time/duration class or instance.
get_message_fields(val)
Returns OrderedDict({field name: field type name}) if ROS1 message, else {}.
generate_message_classes(typename, typedef)
Generates ROS message classes dynamically from given name and definition.