api.py
Go to the documentation of this file.
1 # -*- coding: utf-8 -*-
2 """
3 ROS interface, shared facade for ROS1 and ROS2.
4 
5 ------------------------------------------------------------------------------
6 This file is part of grepros - grep for ROS1 bag files and live topics.
7 Released under the BSD License.
8 
9 @author Erki Suurjaak
10 @created 01.11.2021
11 @modified 29.12.2023
12 ------------------------------------------------------------------------------
13 """
14 
15 import abc
16 import collections
17 import datetime
18 import decimal
19 import hashlib
20 import inspect
21 import os
22 import re
23 import sys
24 import time
25 
26 import six
27 
28 from . common import ConsolePrinter, LenIterable, format_bytes, memoize
29 #from . import ros1, ros2 # Imported conditionally
30 
31 
32 
33 NODE_NAME = "grepros"
34 
35 
36 BAG_EXTENSIONS = ()
37 
38 
39 SKIP_EXTENSIONS = ()
40 
41 
42 ROS1 = None
43 
44 
45 ROS2 = None
46 
47 
48 ROS_VERSION = None
49 
50 
51 ROS_FAMILY = None
52 
53 
54 ROS_NUMERIC_TYPES = ["byte", "char", "int8", "int16", "int32", "int64", "uint8",
55  "uint16", "uint32", "uint64", "float32", "float64", "bool"]
56 
57 
58 ROS_STRING_TYPES = ["string", "wstring"]
59 
60 
61 ROS_BUILTIN_TYPES = ROS_NUMERIC_TYPES + ROS_STRING_TYPES
62 
63 
64 ROS_BUILTIN_CTORS = {"byte": int, "char": int, "int8": int, "int16": int,
65  "int32": int, "int64": int, "uint8": int, "uint16": int,
66  "uint32": int, "uint64": int, "float32": float, "float64": float,
67  "bool": bool, "string": str, "wstring": str}
68 
69 
70 ROS_TIME_TYPES = []
71 
72 
73 ROS_TIME_CLASSES = {}
74 
75 
76 ROS_COMMON_TYPES = []
77 
78 
79 ROS_ALIAS_TYPES = {}
80 
81 
82 realapi = None
83 
84 
85 class BaseBag(object):
86  """
87  ROS bag interface.
88 
89  %Bag can be used a context manager, is an iterable providing (topic, message, timestamp) tuples
90  and supporting `len(bag)`; and supports topic-based membership
91  (`if mytopic in bag`, `for t, m, s in bag[mytopic]`, `len(bag[mytopic])`).
92 
93  Extra methods and properties compared with rosbag.Bag: Bag.get_message_class(),
94  Bag.get_message_definition(), Bag.get_message_type_hash(), Bag.get_topic_info();
95  Bag.closed and Bag.topics.
96  """
97 
98 
99  BagMessage = collections.namedtuple("BagMessage", "topic message timestamp")
100 
101 
103  TopicTuple = collections.namedtuple("TopicTuple", ["msg_type", "message_count",
104  "connections", "frequency"])
105 
106 
107  TypesAndTopicsTuple = collections.namedtuple("TypesAndTopicsTuple", ["msg_types", "topics"])
108 
109 
110  MODES = ("r", "w", "a")
111 
112 
113  STREAMABLE = True
114 
115  def __iter__(self):
116  """Iterates over all messages in the bag."""
117  return self.read_messages()
118 
119  def __enter__(self):
120  """Context manager entry, opens bag if not open."""
121  self.open()
122  return self
123 
124  def __exit__(self, exc_type, exc_value, traceback):
125  """Context manager exit, closes bag."""
126  self.close()
127 
128  def __len__(self):
129  """Returns the number of messages in the bag."""
130  return self.get_message_count()
131 
132  def __next__(self):
133  """Retrieves next message from bag as (topic, message, timestamp)."""
134  raise NotImplementedError
135  if sys.version_info < (3, ): next = __next__
136 
137  def __nonzero__(self): return True # Iterables by default use len() for bool() [Py2]
138 
139  def __bool__ (self): return True # Iterables by default use len() for bool() [Py3]
140 
141  def __contains__(self, key):
142  """Returns whether bag contains given topic."""
143  raise NotImplementedError
144 
145  def __copy__(self): return self
146 
147  def __deepcopy__(self, memo=None): return self
148 
149  def __getitem__(self, key):
150  """Returns an iterator yielding messages from the bag in given topic, supporting len()."""
151  if key not in self: return LenIterable([], 0)
152  get_count = lambda: sum(c for (t, _, _), c in self.get_topic_info().items() if t == key)
153  return LenIterable(self.read_messages(key), get_count)
154 
155  def __str__(self):
156  """Returns informative text for bag, with a full overview of topics and types."""
157 
158  indent = lambda s, n: ("\n%s" % (" " * n)).join(s.splitlines())
159  # Returns UNIX timestamp as "Dec 22 2021 23:13:44.44"
160  fmttime = lambda x: datetime.datetime.fromtimestamp(x).strftime("%b %d %Y %H:%M:%S.%f")[:-4]
161  def fmtdur(secs):
162  """Returns duration seconds as text like "1hr 1:12s (3672s)" or "51.8s"."""
163  result = ""
164  hh, rem = divmod(secs, 3600)
165  mm, ss = divmod(rem, 60)
166  if hh: result += "%dhr " % hh
167  if mm: result += "%d:" % mm
168  result += "%ds" % ss
169  if hh or mm: result += " (%ds)" % secs
170  return result
171 
172  entries = {}
173  counts = self.get_topic_info()
174  start, end = self.get_start_time(), self.get_end_time()
175 
176  entries["path"] = self.filename or "<stream>"
177  if None not in (start, end):
178  entries["duration"] = fmtdur(end - start)
179  entries["start"] = "%s (%.2f)" % (fmttime(start), start)
180  entries["end"] = "%s (%.2f)" % (fmttime(end), end)
181  entries["size"] = format_bytes(self.size)
182  if any(counts.values()):
183  entries["messages"] = str(sum(counts.values()))
184  if counts:
185  nhs = sorted(set((n, h) for _, n, h in counts))
186  namew = max(len(n) for n, _ in nhs)
187  # "pkg/Msg <PAD>[typehash]"
188  entries["types"] = "\n".join("%s%s [%s]" % (n, " " * (namew - len(n)), h) for n, h in nhs)
189  if counts:
190  topicw = max(len(t) for t, _, _ in counts)
191  typew = max(len(n) for _, n, _ in counts)
192  countw = max(len(str(c)) for c in counts.values())
193  lines = []
194  for (t, n, _), c in sorted(counts.items()):
195  qq = self.get_qoses(t, n) or []
196  # "/my/topic<PAD>"
197  line = "%s%s" % (t, " " * (topicw - len(t)))
198  # " <PAD>13 msgs" or " <PAD>1 msg "
199  line += " %s%s msg%s" % (" " * (countw - len(str(c))), c, " " if 1 == c else "s")
200  # " : pkg/Msg"
201  line += " : %s" % n
202  # "<PAD> (2 connections)" if >1 connections
203  line += "%s (%s connections)" % (" " * (typew - len(n)), len(qq)) if len(qq) > 1 else ""
204  lines.append(line)
205  entries["topics"] = "\n".join(lines)
206 
207  labelw = max(map(len, entries))
208  return "\n".join("%s:%s %s" % (k, " " * (labelw - len(k)), indent(v, labelw + 2))
209  for k, v in entries.items())
210 
211  def get_message_count(self, topic_filters=None):
212  """
213  Returns the number of messages in the bag.
214 
215  @param topic_filters list of topics or a single topic to filter by, if any
216  """
217  raise NotImplementedError
218 
219  def get_start_time(self):
220  """Returns the start time of the bag, as UNIX timestamp, or None if bag empty."""
221  raise NotImplementedError
222 
223  def get_end_time(self):
224  """Returns the end time of the bag, as UNIX timestamp, or None if bag empty."""
225  raise NotImplementedError
226 
227  def get_topic_info(self, counts=True):
228  """
229  Returns topic and message type metainfo as {(topic, typename, typehash): count}.
230 
231  @param counts if false, counts may be returned as None if lookup is costly
232  """
233  raise NotImplementedError
234 
235  def get_type_and_topic_info(self, topic_filters=None):
236  """
237  Returns thorough metainfo on topic and message types.
238 
239  @param topic_filters list of topics or a single topic to filter returned topics-dict by,
240  if any
241  @return TypesAndTopicsTuple(msg_types, topics) namedtuple,
242  msg_types as dict of {typename: typehash},
243  topics as a dict of {topic: TopicTuple() namedtuple}.
244  """
245  raise NotImplementedError
246 
247  def get_qoses(self, topic, typename):
248  """
249  Returns topic Quality-of-Service profiles as a list of dicts, or None if not available.
250 
251  Functional only in ROS2.
252  """
253  return None
254 
255  def get_message_class(self, typename, typehash=None):
256  """Returns ROS message type class, or None if unknown message type for bag."""
257  return None
258 
259  def get_message_definition(self, msg_or_type):
260  """
261  Returns ROS message type definition full text, including subtype definitions.
262 
263  Returns None if unknown message type for bag.
264  """
265  return None
266 
267  def get_message_type_hash(self, msg_or_type):
268  """Returns ROS message type MD5 hash, or None if unknown message type for bag."""
269  return None
270 
271  def read_messages(self, topics=None, start_time=None, end_time=None, raw=False, **__):
272  """
273  Yields messages from the bag, optionally filtered by topic and timestamp.
274 
275  @param topics list of topics or a single topic to filter by, if any
276  @param start_time earliest timestamp of message to return, as ROS time or convertible
277  (int/float/duration/datetime/decimal)
278  @param end_time latest timestamp of message to return, as ROS time
279  (int/float/duration/datetime/decimal)
280  @param raw if true, then returned messages are tuples of
281  (typename, bytes, typehash, typeclass)
282  or (typename, bytes, typehash, position, typeclass),
283  depending on file format
284  @return BagMessage namedtuples of (topic, message, timestamp as ROS time)
285  """
286  raise NotImplementedError
287 
288  def write(self, topic, msg, t=None, raw=False, **kwargs):
289  """
290  Writes a message to the bag.
291 
292  @param topic name of topic
293  @param msg ROS message
294  @param t message timestamp if not using current wall time, as ROS time
295  or convertible (int/float/duration/datetime/decimal)
296  @param raw if true, `msg` is in raw format, (typename, bytes, typehash, typeclass)
297  @param kwargs ROS version-specific arguments,
298  like `connection_header` for ROS1 or `qoses` for ROS2
299  """
300  raise NotImplementedError
301 
302  def open(self):
303  """Opens the bag file if not already open."""
304  raise NotImplementedError
305 
306  def close(self):
307  """Closes the bag file."""
308  raise NotImplementedError
309 
310  def flush(self):
311  """Ensures all changes are written to bag file."""
312 
313  @property
314  def topics(self):
315  """Returns the list of topics in bag, in alphabetic order."""
316  raise NotImplementedError
317 
318  @property
319  def filename(self):
320  """Returns bag file path."""
321  raise NotImplementedError
322 
323  @property
324  def size(self):
325  """Returns current file size in bytes."""
326  raise NotImplementedError
327 
328  @property
329  def mode(self):
330  """Returns file open mode."""
331  raise NotImplementedError
332 
333  @property
334  def closed(self):
335  """Returns whether file is closed."""
336  raise NotImplementedError
337 
338  @property
339  def stop_on_error(self):
340  """Whether raising read error on unknown message type (ROS2 SQLite .db3 specific)."""
341  return getattr(self, "_stop_on_error", None)
342 
343  @stop_on_error.setter
344  def stop_on_error(self, flag):
345  """Sets whether to raise read error on unknown message type (ROS2 SQLite .db3 specific)."""
346  setattr(self, "_stop_on_error", flag)
347 
348 
349 @six.add_metaclass(abc.ABCMeta)
350 class Bag(BaseBag):
351  """
352  %Bag factory metaclass.
353 
354  Result is a format-specific class instance, auto-detected from file extension or content:
355  an extended rosbag.Bag for ROS1 bags, otherwise an object with a conforming interface.
356 
357  E.g. {@link grepros.plugins.mcap.McapBag McapBag} if {@link grepros.plugins.mcap mcap}
358  plugin loaded and file recognized as MCAP format.
359 
360  User plugins can add their own format support to READER_CLASSES and WRITER_CLASSES.
361  Classes can have a static/class method `autodetect(filename)`
362  returning whether given file is in recognizable format for the plugin class.
363  """
364 
365 
366  READER_CLASSES = set()
367 
368 
369  WRITER_CLASSES = set()
370 
371  def __new__(cls, f, mode="r", reindex=False, progress=False, **kwargs):
372  """
373  Returns an object for reading or writing ROS bags.
374 
375  Suitable Bag class is auto-detected by file extension or content.
376 
377  @param f bag file path, or a stream object
378  (streams not supported for ROS2 .db3 SQLite bags)
379  @param mode return reader if "r" else writer
380  @param reindex reindex unindexed bag (ROS1 only), making a backup if indexed format
381  @param progress show progress bar with reindexing status
382  @param kwargs additional keyword arguments for format-specific Bag constructor,
383  like `compression` for ROS1 bag
384  """
385  classes, errors = set(cls.READER_CLASSES if "r" == mode else cls.WRITER_CLASSES), []
386  for detect, bagcls in ((d, c) for d in (True, False) for c in list(classes)):
387  use, discard = not detect, False # Try auto-detecting suitable class first
388  try:
389  if detect and callable(getattr(bagcls, "autodetect", None)):
390  use, discard = bagcls.autodetect(f), True
391  if use:
392  return bagcls(f, mode, reindex=reindex, progress=progress, **kwargs)
393  except Exception as e:
394  discard = True
395  errors.append("Failed to open %r for %s with %s: %s." %
396  (f, "reading" if "r" == mode else "writing", bagcls, e))
397  discard and classes.discard(bagcls)
398  for err in errors: ConsolePrinter.warn(err)
399  raise Exception("No suitable %s class available" % ("reader" if "r" == mode else "writer"))
400 
401 
402  @classmethod
403  def autodetect(cls, f):
404  """Returns registered bag class auto-detected from file, or None."""
405  for bagcls in cls.READER_CLASSES | cls.WRITER_CLASSES:
406  if callable(vars(bagcls).get("autodetect")) and bagcls.autodetect(f):
407  return bagcls
408  return None
409 
410 
411  @classmethod
412  def __subclasshook__(cls, C):
413  return True if issubclass(C, BaseBag) else NotImplemented
414 
415 
416 class TypeMeta(object):
417  """
418  Container for caching and retrieving message type metadata.
419 
420  All property values are lazy-loaded upon request.
421  """
422 
423 
424  LIFETIME = 2
425 
426 
427  POPULATION = 0
428 
429 
430  _CACHE = {}
431 
432 
433  _CHILDREN = {}
434 
435 
436  _TIMINGS = {}
437 
438 
439  _LASTSWEEP = time.time()
440 
441  def __init__(self, msg, topic=None, source=None, data=None):
442  self._msg = msg
443  self._topic = topic
444  self._source = source
445  self._data = data
446  self._type = None # Message typename as "pkg/MsgType"
447  self._def = None # Message type definition with full subtype definitions
448  self._hash = None # Message type definition MD5 hash
449  self._cls = None # Message class object
450  self._topickey = None # (topic, typename, typehash)
451  self._typekey = None # (typename, typehash)
452 
453  def __enter__(self, *_, **__):
454  """Allows using instance as a context manager (no other effect)."""
455  return self
456 
457  def __exit__(self, *_, **__): pass
458 
459  @property
460  def typename(self):
461  """Returns message typename, as "pkg/MsgType"."""
462  if not self._type:
463  self._type = realapi.get_message_type(self._msg)
464  return self._type
465 
466  @property
467  def typehash(self):
468  """Returns message type definition MD5 hash."""
469  if not self._hash:
470  hash = self._source and self._source.get_message_type_hash(self._msg)
471  self._hash = hash or realapi.get_message_type_hash(self._msg)
472  return self._hash
473 
474  @property
475  def definition(self):
476  """Returns message type definition text with full subtype definitions."""
477  if not self._def:
478  typedef = self._source and self._source.get_message_definition(self._msg)
479  self._def = typedef or realapi.get_message_definition(self._msg)
480  return self._def
481 
482  @property
483  def data(self):
484  """Returns message serialized binary, as bytes(), or None if not cached."""
485  return self._data
486 
487  @property
488  def typeclass(self):
489  """Returns message class object."""
490  if not self._cls:
491  cls = type(self._msg) if realapi.is_ros_message(self._msg) else \
492  self._source and self._source.get_message_class(self.typename, self.typehash)
493  self._cls = cls or realapi.get_message_class(self.typename)
494  return self._cls
495 
496  @property
497  def topickey(self):
498  """Returns (topic, typename, typehash) for message."""
499  if not self._topickey:
500  self._topickey = (self._topic, self.typename, self.typehash)
501  return self._topickey
502 
503  @property
504  def typekey(self):
505  """Returns (typename, typehash) for message."""
506  if not self._typekey:
507  self._typekey = (self.typename, self.typehash)
508  return self._typekey
509 
510  @classmethod
511  def make(cls, msg, topic=None, source=None, root=None, data=None):
512  """
513  Returns TypeMeta instance, registering message in cache if not present.
514 
515  Other parameters are only required for first registration.
516 
517  @param topic topic the message is in if root message
518  @param source message source like TopicSource or Bag,
519  for looking up message type metadata
520  @param root root message that msg is a nested value of, if any
521  @param data message serialized binary, if any
522  """
523  msgid = id(msg)
524  if msgid not in cls._CACHE:
525  cls._CACHE[msgid] = TypeMeta(msg, topic, data)
526  if root and root is not msg:
527  cls._CHILDREN.setdefault(id(root), set()).add(msgid)
528  cls._TIMINGS[msgid] = time.time()
529  result = cls._CACHE[msgid]
530  cls.sweep()
531  return result
532 
533  @classmethod
534  def discard(cls, msg):
535  """Discards message metadata from cache, if any, including nested messages."""
536  msgid = id(msg)
537  cls._CACHE.pop(msgid, None), cls._TIMINGS.pop(msgid, None)
538  for childid in cls._CHILDREN.pop(msgid, []):
539  cls._CACHE.pop(childid, None), cls._TIMINGS.pop(childid, None)
540  cls.sweep()
541 
542  @classmethod
543  def sweep(cls):
544  """Discards stale or surplus messages from cache."""
545  if cls.POPULATION > 0 and len(cls._CACHE) > cls.POPULATION:
546  count = len(cls._CACHE) - cls.POPULATION
547  for msgid, tm in sorted(x[::-1] for x in cls._TIMINGS.items())[:count]:
548  cls._CACHE.pop(msgid, None), cls._TIMINGS.pop(msgid, None)
549  for childid in cls._CHILDREN.pop(msgid, []):
550  cls._CACHE.pop(childid, None), cls._TIMINGS.pop(childid, None)
551 
552  now = time.time()
553  if cls.LIFETIME <= 0 or cls._LASTSWEEP < now - cls.LIFETIME: return
554 
555  for msgid, tm in list(cls._TIMINGS.items()):
556  drop = (tm > now) or (tm < now - cls.LIFETIME)
557  drop and (cls._CACHE.pop(msgid, None), cls._TIMINGS.pop(msgid, None))
558  for childid in cls._CHILDREN.pop(msgid, []) if drop else ():
559  cls._CACHE.pop(childid, None), cls._TIMINGS.pop(childid, None)
560  cls._LASTSWEEP = now
561 
562  @classmethod
563  def clear(cls):
564  """Clears entire cache."""
565  cls._CACHE.clear()
566  cls._CHILDREN.clear()
567  cls._TIMINGS.clear()
568 
569 
570 
571 def init_node(name=None):
572  """
573  Initializes a ROS1 or ROS2 node if not already initialized.
574 
575  In ROS1, blocks until ROS master available.
576  """
577  validate() and realapi.init_node(name or NODE_NAME)
578 
579 
581  """Shuts down live ROS node."""
582  realapi and realapi.shutdown_node()
583 
584 
585 def validate(live=False):
586  """
587  Initializes ROS bindings, returns whether ROS environment set, prints or raises error if not.
588 
589  @param live whether environment must support launching a ROS node
590  """
591  global realapi, BAG_EXTENSIONS, SKIP_EXTENSIONS, ROS1, ROS2, ROS_VERSION, ROS_FAMILY, \
592  ROS_COMMON_TYPES, ROS_TIME_TYPES, ROS_TIME_CLASSES, ROS_ALIAS_TYPES
593  if realapi:
594  return True
595 
596  success, version = False, os.getenv("ROS_VERSION")
597  if "1" == version:
598  from . import ros1
599  realapi = ros1
600  success = realapi.validate()
601  ROS1, ROS2, ROS_VERSION, ROS_FAMILY = True, False, 1, "rospy"
602  elif "2" == version:
603  from . import ros2
604  realapi = ros2
605  success = realapi.validate(live)
606  ROS1, ROS2, ROS_VERSION, ROS_FAMILY = False, True, 2, "rclpy"
607  elif not version:
608  ConsolePrinter.error("ROS environment not set: missing ROS_VERSION.")
609  else:
610  ConsolePrinter.error("ROS environment not supported: unknown ROS_VERSION %r.", version)
611  if success:
612  BAG_EXTENSIONS, SKIP_EXTENSIONS = realapi.BAG_EXTENSIONS, realapi.SKIP_EXTENSIONS
613  ROS_COMMON_TYPES = ROS_BUILTIN_TYPES + realapi.ROS_TIME_TYPES
614  ROS_TIME_TYPES = realapi.ROS_TIME_TYPES
615  ROS_TIME_CLASSES = realapi.ROS_TIME_CLASSES
616  ROS_ALIAS_TYPES = realapi.ROS_ALIAS_TYPES
617  Bag.READER_CLASSES.add(realapi.Bag)
618  Bag.WRITER_CLASSES.add(realapi.Bag)
619  return success
620 
621 
622 @memoize
623 def calculate_definition_hash(typename, msgdef, extradefs=()):
624  """
625  Returns MD5 hash for message type definition.
626 
627  @param extradefs additional subtype definitions as ((typename, msgdef), )
628  """
629  # "type name (= constvalue)?" or "type name (defaultvalue)?" (ROS2 format)
630  FIELD_RGX = re.compile(r"^([a-z][^\s:]+)\s+([^\s=]+)(\s*=\s*([^\n]+))?(\s+([^\n]+))?", re.I)
631  STR_CONST_RGX = re.compile(r"^w?string\s+([^\s=#]+)\s*=")
632  lines, pkg = [], typename.rsplit("/", 1)[0]
633  subtypedefs = dict(extradefs, **parse_definition_subtypes(msgdef))
634  extradefs = tuple(subtypedefs.items())
635 
636  # First pass: write constants
637  for line in msgdef.splitlines():
638  if set(line) == set("="): # Subtype separator
639  break # for line
640  # String constants cannot have line comments
641  if "#" in line and not STR_CONST_RGX.match(line): line = line[:line.index("#")]
642  match = FIELD_RGX.match(line)
643  if match and match.group(3):
644  lines.append("%s %s=%s" % (match.group(1), match.group(2), match.group(4).strip()))
645  # Second pass: write fields and subtype hashes
646  for line in msgdef.splitlines():
647  if set(line) == set("="): # Subtype separator
648  break # for line
649  if "#" in line and not STR_CONST_RGX.match(line): line = line[:line.index("#")]
650  match = FIELD_RGX.match(line)
651  if match and not match.group(3): # Not constant
652  scalartype, namestr = scalar(match.group(1)), match.group(2)
653  if scalartype in ROS_COMMON_TYPES:
654  typestr = match.group(1)
655  if match.group(5): namestr = (namestr + " " + match.group(6)).strip()
656  else:
657  subtype = scalartype if "/" in scalartype else "std_msgs/Header" \
658  if "Header" == scalartype else "%s/%s" % (pkg, scalartype)
659  typestr = calculate_definition_hash(subtype, subtypedefs[subtype], extradefs)
660  lines.append("%s %s" % (typestr, namestr))
661  return hashlib.md5("\n".join(lines).encode()).hexdigest()
662 
663 
664 def canonical(typename, unbounded=False):
665  """
666  Returns "pkg/Type" for "pkg/subdir/Type", standardizes various ROS2 formats.
667 
668  Converts ROS2 DDS types like "octet" to "byte", and "sequence<uint8, 100>" to "uint8[100]".
669 
670  @param unbounded drop constraints like array bounds, and string bounds in ROS2,
671  e.g. returning "uint8[]" for "uint8[10]"
672  """
673  return realapi.canonical(typename, unbounded)
674 
675 
676 def create_publisher(topic, cls_or_typename, queue_size):
677  """Returns a ROS publisher instance, with .get_num_connections() and .unregister()."""
678  return realapi.create_publisher(topic, cls_or_typename, queue_size)
679 
680 
681 def create_subscriber(topic, cls_or_typename, handler, queue_size):
682  """
683  Returns a ROS subscriber instance.
684 
685  Supplemented with .unregister(), .get_message_class(), .get_message_definition(),
686  .get_message_type_hash(), and .get_qoses().
687  """
688  return realapi.create_subscriber(topic, cls_or_typename, handler, queue_size)
689 
690 
691 def filter_fields(fieldmap, top=(), include=(), exclude=()):
692  """
693  Returns fieldmap filtered by include and exclude patterns.
694 
695  @param fieldmap {field name: field type name}
696  @param top parent path as (rootattr, ..)
697  @param include [((nested, path), re.Pattern())] to require in parent path
698  @param exclude [((nested, path), re.Pattern())] to reject in parent path
699  """
700  NESTED_RGX = re.compile(".+/.+|" + "|".join("^%s$" % re.escape(x) for x in ROS_TIME_TYPES))
701  result = type(fieldmap)() if include or exclude else fieldmap
702  for k, v in fieldmap.items() if not result else ():
703  trailstr = ".".join(map(str, top + (k, )))
704  for is_exclude, patterns in enumerate((include, exclude)):
705  # Nested fields need filtering on deeper level
706  matches = not is_exclude and NESTED_RGX.match(v) \
707  or any(r.match(trailstr) for _, r in patterns)
708  if patterns and (not matches if is_exclude else matches):
709  result[k] = v
710  elif patterns and is_exclude and matches:
711  result.pop(k, None)
712  if include and exclude and k not in result: # Failing to include takes precedence
713  break # for is_exclude
714  return result
715 
716 
717 def format_message_value(msg, name, value):
718  """
719  Returns a message attribute value as string.
720 
721  Result is at least 10 chars wide if message is a ROS time/duration
722  (aligning seconds and nanoseconds).
723  """
724  return realapi.format_message_value(msg, name, value)
725 
726 
727 def get_message_class(typename):
728  """Returns ROS message class, or None if unavailable."""
729  return realapi.get_message_class(typename)
730 
731 
732 def get_message_definition(msg_or_type):
733  """
734  Returns ROS message type definition full text, including subtype definitions.
735 
736  Returns None if unknown type.
737  """
738  return realapi.get_message_definition(msg_or_type)
739 
740 
741 def get_message_type_hash(msg_or_type):
742  """Returns ROS message type MD5 hash, or "" if unknown type."""
743  return realapi.get_message_type_hash(msg_or_type)
744 
745 
747  """
748  Returns OrderedDict({field name: field type name}) if ROS message, else {}.
749 
750  @param val ROS message class or instance
751  """
752  return realapi.get_message_fields(val)
753 
754 
755 def get_message_type(msg_or_cls):
756  """Returns ROS message type name, like "std_msgs/Header"."""
757  return realapi.get_message_type(msg_or_cls)
758 
759 
760 def get_message_value(msg, name, typename):
761  """Returns object attribute value, with numeric arrays converted to lists."""
762  return realapi.get_message_value(msg, name, typename)
763 
764 
765 def get_rostime(fallback=False):
766  """
767  Returns current ROS time, as rospy.Time or rclpy.time.Time.
768 
769  @param fallback use wall time if node not initialized
770  """
771  return realapi.get_rostime(fallback=fallback)
772 
773 
774 def get_ros_time_category(msg_or_type):
775  """Returns "time" or "duration" for time/duration type or instance, else original argument."""
776  cls = msg_or_type if inspect.isclass(msg_or_type) else \
777  type(msg_or_type) if is_ros_time(msg_or_type) else None
778  if cls is None and isinstance(msg_or_type, (six.binary_type, six.text_type)):
779  cls = next((x for x in ROS_TIME_CLASSES if get_message_type(x) == msg_or_type), None)
780  if cls in ROS_TIME_CLASSES:
781  return "duration" if "duration" in ROS_TIME_CLASSES[cls].lower() else "time"
782  return msg_or_type
783 
784 
786  """
787  Returns currently available ROS topics, as [(topicname, typename)].
788 
789  Omits topics that the current ROS node itself has published.
790  """
791  return realapi.get_topic_types()
792 
793 
794 def get_type_alias(typename):
795  """
796  Returns alias like "char" for ROS built-in type, if any; reverse of get_type_alias().
797 
798  In ROS1, byte and char are aliases for int8 and uint8; in ROS2 the reverse.
799  """
800  return next((k for k, v in ROS_ALIAS_TYPES.items() if v == typename), None)
801 
802 
803 def get_alias_type(typename):
804  """
805  Returns ROS built-in type for alias like "char", if any; reverse of get_alias_type().
806 
807  In ROS1, byte and char are aliases for int8 and uint8; in ROS2 the reverse.
808  """
809  return ROS_ALIAS_TYPES.get(typename)
810 
811 
812 def is_ros_message(val, ignore_time=False):
813  """
814  Returns whether value is a ROS message or special like ROS time/duration class or instance.
815 
816  @param ignore_time whether to ignore ROS time/duration types
817  """
818  return realapi.is_ros_message(val, ignore_time)
819 
820 
821 def is_ros_time(val):
822  """Returns whether value is a ROS time/duration class or instance."""
823  return realapi.is_ros_time(val)
824 
825 
826 def iter_message_fields(msg, messages_only=False, flat=False, scalars=(), include=(), exclude=(),
827  top=()):
828  """
829  Yields ((nested, path), value, typename) from ROS message.
830 
831  @param messages_only whether to yield only values that are ROS messages themselves
832  or lists of ROS messages, else will yield scalar and list values
833  @param flat recurse into lists of nested messages, ignored if `messages_only`
834  @param scalars sequence of ROS types to consider as scalars, like ("time", duration")
835  @param include [((nested, path), re.Pattern())] to require in field path, if any
836  @param exclude [((nested, path), re.Pattern())] to reject in field path, if any
837  @param top internal recursion helper
838  """
839  fieldmap = realapi.get_message_fields(msg)
840  if include or exclude: fieldmap = filter_fields(fieldmap, (), include, exclude)
841  if not fieldmap: return
842  if messages_only:
843  for k, t in fieldmap.items():
844  v, scalart = realapi.get_message_value(msg, k, t), realapi.scalar(t)
845  is_sublist = isinstance(v, (list, tuple)) and scalart not in ROS_COMMON_TYPES
846  is_forced_scalar = get_ros_time_category(scalart) in scalars
847  if not is_forced_scalar and realapi.is_ros_message(v):
848  for p2, v2, t2 in iter_message_fields(v, True, scalars=scalars, top=top + (k, )):
849  yield p2, v2, t2
850  if is_forced_scalar or is_sublist or realapi.is_ros_message(v, ignore_time=True):
851  yield top + (k, ), v, t
852  else:
853  for k, t in fieldmap.items():
854  v, scalart = realapi.get_message_value(msg, k, t), realapi.scalar(t)
855  is_forced_scalar = get_ros_time_category(scalart) in scalars
856  if not is_forced_scalar and realapi.is_ros_message(v):
857  for p2, v2, t2 in iter_message_fields(v, False, flat, scalars, top=top + (k, )):
858  yield p2, v2, t2
859  elif flat and v and isinstance(v, (list, tuple)) and scalart not in ROS_BUILTIN_TYPES:
860  for i, m in enumerate(v):
861  for p2, v2, t2 in iter_message_fields(m, False, True, scalars, top=top + (k, i)):
862  yield p2, v2, t2
863  else:
864  yield top + (k, ), v, t
865 
866 
867 def make_full_typename(typename, category="msg"):
868  """
869  Returns "pkg/msg/Type" for "pkg/Type".
870 
871  @param category type category like "msg" or "srv"
872  """
873  INTER, FAMILY = "/%s/" % category, "rospy" if ROS1 else "rclpy"
874  if INTER in typename or "/" not in typename or typename.startswith("%s/" % FAMILY):
875  return typename
876  return INTER.join(next((x[0], x[-1]) for x in [typename.split("/")]))
877 
878 
879 def make_bag_time(stamp, bag):
880  """
881  Returns value as ROS timestamp, conditionally as relative to bag start/end time.
882 
883  Stamp is interpreted as relative offset from bag start/end time
884  if numeric string with sign prefix, or timedelta, or ROS duration.
885 
886  @param stamp converted to ROS timestamp if int/float/str/duration/datetime/timedelta/decimal
887  @param bag an open bag to use for relative start/end time
888  """
889  shift = 0
890  if is_ros_time(stamp):
891  if "duration" != get_ros_time_category(stamp): return stamp
892  shift = bag.get_start_time() if stamp >= 0 else bag.get_end_time()
893  elif isinstance(stamp, datetime.datetime):
894  stamp = time.mktime(stamp.timetuple()) + stamp.microsecond / 1E6
895  elif isinstance(stamp, datetime.timedelta):
896  stamp = stamp.total_seconds()
897  shift = bag.get_start_time() if stamp >= 0 else bag.get_end_time()
898  elif isinstance(stamp, (six.binary_type, six.text_type)):
899  sign = stamp[0] in ("+", b"+") if six.text_type(stamp[0]) in "+-" else None
900  shift = 0 if sign is None else bag.get_start_time() if sign else bag.get_end_time()
901  stamp = float(stamp)
902  return make_time(stamp + shift)
903 
904 
905 def make_live_time(stamp):
906  """
907  Returns value as ROS timestamp, conditionally as relative to system time.
908 
909  Stamp is interpreted as relative offset from system time
910  if numeric string with sign prefix, or timedelta, or ROS duration.
911 
912  @param stamp converted to ROS timestamp if int/float/str/duration/datetime/timedelta/decimal
913  """
914  shift = 0
915  if is_ros_time(stamp):
916  if "duration" != get_ros_time_category(stamp): return stamp
917  shift = time.time()
918  elif isinstance(stamp, datetime.datetime):
919  stamp = time.mktime(stamp.timetuple()) + stamp.microsecond / 1E6
920  elif isinstance(stamp, datetime.timedelta):
921  stamp, shift = stamp.total_seconds(), time.time()
922  elif isinstance(stamp, (six.binary_type, six.text_type)):
923  sign = stamp[0] in ("+", b"+") if six.text_type(stamp[0]) in "+-" else None
924  stamp, shift = float(stamp), (0 if sign is None else time.time())
925  return make_time(stamp + shift)
926 
927 
928 def make_duration(secs=0, nsecs=0):
929  """Returns a ROS duration."""
930  return realapi.make_duration(secs=secs, nsecs=nsecs)
931 
932 
933 def make_time(secs=0, nsecs=0):
934  """Returns a ROS time."""
935  return realapi.make_time(secs=secs, nsecs=nsecs)
936 
937 
938 def make_message_hash(msg, include=(), exclude=()):
939  """
940  Returns hashcode for ROS message, as a hex digest.
941 
942  @param include message fields to include if not all, as [((nested, path), re.Pattern())]
943  @param exclude message fields to exclude, as [((nested, path), re.Pattern())]
944  """
945  hasher = hashlib.md5()
946 
947  def walk_message(obj, top=()):
948  fieldmap = get_message_fields(obj)
949  fieldmap = filter_fields(fieldmap, include=include, exclude=exclude)
950  for k, t in fieldmap.items():
951  v, path = get_message_value(obj, k, t), top + (k, )
952  if is_ros_message(v):
953  walk_message(v, path)
954  elif isinstance(v, (list, tuple)) and scalar(t) not in ROS_BUILTIN_TYPES:
955  for x in v: walk_message(x, path)
956  else:
957  s = "%s=%s" % (path, v)
958  hasher.update(s.encode("utf-8", errors="backslashreplace"))
959  if not hasattr(obj, "__slots__"):
960  s = "%s=%s" % (top, obj)
961  hasher.update(s.encode("utf-8", errors="backslashreplace"))
962 
963  walk_message(msg)
964  return hasher.hexdigest()
965 
966 
967 def message_to_dict(msg, replace=None):
968  """
969  Returns ROS message as nested Python dictionary.
970 
971  @param replace mapping of {value: replaced value},
972  e.g. {math.nan: None, math.inf: None}
973  """
974  result = {} if realapi.is_ros_message(msg) else msg
975  for name, typename in realapi.get_message_fields(msg).items():
976  v = realapi.get_message_value(msg, name, typename)
977  if realapi.is_ros_time(v):
978  v = dict(zip(realapi.get_message_fields(v), realapi.to_sec_nsec(v)))
979  elif realapi.is_ros_message(v):
980  v = message_to_dict(v)
981  elif isinstance(v, (list, tuple)):
982  if realapi.scalar(typename) not in ROS_BUILTIN_TYPES:
983  v = [message_to_dict(x) for x in v]
984  elif replace:
985  v = [replace.get(x, x) for x in v]
986  elif replace:
987  v = replace.get(v, v)
988  result[name] = v
989  return result
990 
991 
992 def dict_to_message(dct, msg):
993  """
994  Returns given ROS message populated from Python dictionary.
995 
996  Raises TypeError on attribute value type mismatch.
997  """
998  for name, typename in realapi.get_message_fields(msg).items():
999  if name not in dct:
1000  continue # for
1001  v, msgv = dct[name], realapi.get_message_value(msg, name, typename)
1002 
1003  if realapi.is_ros_message(msgv):
1004  v = v if is_ros_time(v) and is_ros_time(msgv) else dict_to_message(v, msgv)
1005  elif isinstance(msgv, (list, tuple)):
1006  scalarname = realapi.scalar(typename)
1007  if scalarname in ROS_BUILTIN_TYPES:
1008  cls = ROS_BUILTIN_CTORS[scalarname]
1009  v = [x if isinstance(x, cls) else cls(x) for x in v]
1010  else:
1011  cls = realapi.get_message_class(scalarname)
1012  v = [dict_to_message(x, cls()) for x in v]
1013  else:
1014  v = type(msgv)(v)
1015 
1016  setattr(msg, name, v)
1017  return msg
1018 
1019 
1020 @memoize
1021 def parse_definition_fields(typename, typedef):
1022  """
1023  Returns field names and type names from a message definition text.
1024 
1025  Does not recurse into subtypes.
1026 
1027  @param typename ROS message type name, like "my_pkg/MyCls"
1028  @param typedef ROS message definition, like "Header header\nbool a\nMyCls2 b"
1029  @return ordered {field name: type name},
1030  like {"header": "std_msgs/Header", "a": "bool", "b": "my_pkg/MyCls2"}
1031  """
1032  result = collections.OrderedDict() # {subtypename: subtypedef}
1033 
1034  FIELD_RGX = re.compile(r"^([a-z][^\s:]+)\s+([^\s=]+)(\s*=\s*([^\n]+))?(\s+([^\n]+))?", re.I)
1035  STR_CONST_RGX = re.compile(r"^w?string\s+([^\s=#]+)\s*=")
1036  pkg = typename.rsplit("/", 1)[0]
1037  for line in filter(bool, typedef.splitlines()):
1038  if set(line) == set("="): # Subtype separator
1039  break # for line
1040  if "#" in line and not STR_CONST_RGX.match(line): line = line[:line.index("#")]
1041  match = FIELD_RGX.match(line)
1042  if not match or match.group(3): # Constant or not field
1043  continue # for line
1044 
1045  name, typename, scalartype = match.group(2), match.group(1), scalar(match.group(1))
1046  if scalartype not in ROS_COMMON_TYPES:
1047  pkg2 = "" if "/" in scalartype else "std_msgs" if "Header" == scalartype else pkg
1048  typename = "%s/%s" % (pkg2, typename) if pkg2 else typename
1049  result[name] = typename
1050  return result
1051 
1052 
1053 @memoize
1054 def parse_definition_subtypes(typedef, nesting=False):
1055  """
1056  Returns subtype names and type definitions from a full message definition.
1057 
1058  @param typedef message type definition including all subtype definitions
1059  @param nesting whether to additionally return type nesting information as
1060  {typename: [typename contained in parent]}
1061  @return {"pkg/MsgType": "full definition for MsgType including subtypes"}
1062  or ({typedefs}, {nesting}) if nesting
1063  """
1064  result = collections.OrderedDict() # {subtypename: subtypedef}
1065  nesteds = collections.defaultdict(list) # {subtypename: [subtypename2, ]})
1066 
1067  # Parse individual subtype definitions from full definition
1068  curtype, curlines = "", []
1069  # Separator line, and definition header like 'MSG: std_msgs/MultiArrayLayout'
1070  rgx = re.compile(r"^((=+)|(MSG: (.+)))$") # Group 2: separator, 4: new type
1071  for line in typedef.splitlines():
1072  m = rgx.match(line)
1073  if m and m.group(2) and curtype: # Separator line between nested definitions
1074  result[curtype] = "\n".join(curlines)
1075  curtype, curlines = "", []
1076  elif m and m.group(4): # Start of nested definition "MSG: pkg/MsgType"
1077  curtype, curlines = m.group(4), []
1078  elif not m and curtype: # Definition content
1079  curlines.append(line)
1080  if curtype:
1081  result[curtype] = "\n".join(curlines)
1082 
1083  # "type name (= constvalue)?" or "type name (defaultvalue)?" (ROS2 format)
1084  FIELD_RGX = re.compile(r"^([a-z][^\s]+)\s+([^\s=]+)(\s*=\s*([^\n]+))?(\s+([^\n]+))?", re.I)
1085  # Concatenate nested subtype definitions to parent subtype definitions
1086  for subtype, subdef in list(result.items()):
1087  pkg, seen = subtype.rsplit("/", 1)[0], set()
1088  for line in subdef.splitlines():
1089  m = FIELD_RGX.match(line)
1090  if m and m.group(1):
1091  scalartype, fulltype = realapi.scalar(m.group(1)), None
1092  if scalartype not in ROS_COMMON_TYPES:
1093  fulltype = scalartype if "/" in scalartype else "std_msgs/Header" \
1094  if "Header" == scalartype else "%s/%s" % (pkg, scalartype)
1095  if fulltype in result and fulltype not in seen:
1096  addendum = "%s\nMSG: %s\n%s" % ("=" * 80, fulltype, result[fulltype])
1097  result[subtype] = result[subtype].rstrip() + ("\n\n%s\n" % addendum)
1098  nesteds[subtype].append(fulltype)
1099  seen.add(fulltype)
1100  return (result, nesteds) if nesting else result
1101 
1102 
1104  """Returns ROS message as a serialized binary."""
1105  return realapi.serialize_message(msg)
1106 
1107 
1108 def deserialize_message(msg, cls_or_typename):
1109  """Returns ROS message or service request/response instantiated from serialized binary."""
1110  return realapi.deserialize_message(msg, cls_or_typename)
1111 
1112 
1113 def scalar(typename):
1114  """
1115  Returns scalar type from ROS message data type, like "uint8" from uint8-array.
1116 
1117  Returns type unchanged if an ordinary type. In ROS2, returns unbounded type,
1118  e.g. "string" from "string<=10[<=5]".
1119  """
1120  return realapi.scalar(typename)
1121 
1122 
1123 def set_message_value(obj, name, value):
1124  """Sets message or object attribute value."""
1125  realapi.set_message_value(obj, name, value)
1126 
1127 
1128 def time_message(val, to_message=True, clock_type=None):
1129  """
1130  Converts ROS2 time/duration between `rclpy` and `builtin_interfaces` objects.
1131 
1132  Returns input value as-is in ROS1.
1133 
1134  @param val ROS2 time/duration object from `rclpy` or `builtin_interfaces`
1135  @param to_message whether to convert from `rclpy` to `builtin_interfaces` or vice versa
1136  @param clock_type ClockType for converting to `rclpy.Time`, defaults to `ROS_TIME`
1137  @return value converted to appropriate type, or original value if not convertible
1138  """
1139  if ROS1: return val
1140  return realapi.time_message(val, to_message, clock_type=clock_type)
1141 
1142 
1143 def to_datetime(val):
1144  """Returns value as datetime.datetime if value is ROS time/duration, else value."""
1145  sec = realapi.to_sec(val)
1146  return datetime.datetime.fromtimestamp(sec) if sec is not val else val
1147 
1148 
1149 def to_decimal(val):
1150  """Returns value as decimal.Decimal if value is ROS time/duration, else value."""
1151  if realapi.is_ros_time(val):
1152  return decimal.Decimal("%d.%09d" % realapi.to_sec_nsec(val))
1153  return val
1154 
1155 
1156 def to_duration(val):
1157  """Returns value as ROS duration if convertible (int/float/time/datetime/decimal), else value."""
1158  return realapi.to_duration(val)
1159 
1160 
1161 def to_nsec(val):
1162  """Returns value in nanoseconds if value is ROS time/duration, else value."""
1163  return realapi.to_nsec(val)
1164 
1165 
1166 def to_sec(val):
1167  """Returns value in seconds if value is ROS time/duration, else value."""
1168  return realapi.to_sec(val)
1169 
1170 
1171 def to_sec_nsec(val):
1172  """Returns value as (seconds, nanoseconds) if value is ROS time/duration, else value."""
1173  return realapi.to_sec_nsec(val)
1174 
1175 
1176 def to_time(val):
1177  """Returns value as ROS time if convertible (int/float/duration/datetime/decimal), else value."""
1178  return realapi.to_time(val)
1179 
1180 
1181 __all___ = [
1182  "BAG_EXTENSIONS", "NODE_NAME", "ROS_ALIAS_TYPES", "ROS_BUILTIN_CTORS", "ROS_BUILTIN_TYPES",
1183  "ROS_COMMON_TYPES", "ROS_FAMILY", "ROS_NUMERIC_TYPES", "ROS_STRING_TYPES", "ROS_TIME_CLASSES",
1184  "ROS_TIME_TYPES", "SKIP_EXTENSIONS", "Bag", "BaseBag", "TypeMeta",
1185  "calculate_definition_hash", "canonical", "create_publisher", "create_subscriber",
1186  "deserialize_message", "dict_to_message", "filter_fields", "format_message_value",
1187  "get_alias_type", "get_message_class", "get_message_definition", "get_message_fields",
1188  "get_message_type", "get_message_type_hash", "get_message_value", "get_ros_time_category",
1189  "get_rostime", "get_topic_types", "get_type_alias", "init_node", "is_ros_message",
1190  "is_ros_time", "iter_message_fields", "make_bag_time", "make_duration", "make_live_time",
1191  "make_message_hash", "make_time", "message_to_dict", "parse_definition_fields",
1192  "parse_definition_subtypes", "scalar", "deserialize_message", "set_message_value",
1193  "shutdown_node", "time_message", "to_datetime", "to_decimal", "to_duration", "to_nsec",
1194  "to_sec", "to_sec_nsec", "to_time", "validate",
1195 ]
grepros.api.parse_definition_subtypes
def parse_definition_subtypes(typedef, nesting=False)
Definition: api.py:1054
grepros.api.get_message_class
def get_message_class(typename)
Definition: api.py:727
grepros.api.parse_definition_fields
def parse_definition_fields(typename, typedef)
Definition: api.py:1021
grepros.api.BaseBag.__str__
def __str__(self)
Definition: api.py:155
grepros.api.Bag.READER_CLASSES
READER_CLASSES
Bag reader classes, as {Cls, }.
Definition: api.py:366
grepros.api.TypeMeta.make
def make(cls, msg, topic=None, source=None, root=None, data=None)
Definition: api.py:511
grepros.api.create_subscriber
def create_subscriber(topic, cls_or_typename, handler, queue_size)
Definition: api.py:681
grepros.common.LenIterable
Definition: common.py:463
grepros.api.iter_message_fields
def iter_message_fields(msg, messages_only=False, flat=False, scalars=(), include=(), exclude=(), top=())
Definition: api.py:826
grepros.api.TypeMeta.clear
def clear(cls)
Definition: api.py:563
grepros.api.Bag.autodetect
def autodetect(cls, f)
Definition: api.py:403
grepros.api.TypeMeta.typekey
def typekey(self)
Definition: api.py:504
grepros.api.get_message_type_hash
def get_message_type_hash(msg_or_type)
Definition: api.py:741
grepros.api.make_time
def make_time(secs=0, nsecs=0)
Definition: api.py:933
grepros.api.get_ros_time_category
def get_ros_time_category(msg_or_type)
Definition: api.py:774
grepros.api.BaseBag.get_message_type_hash
def get_message_type_hash(self, msg_or_type)
Definition: api.py:267
grepros.api.to_nsec
def to_nsec(val)
Definition: api.py:1161
grepros.api.BaseBag.__getitem__
def __getitem__(self, key)
Definition: api.py:149
grepros.api.BaseBag.get_qoses
def get_qoses(self, topic, typename)
Definition: api.py:247
grepros.api.time_message
def time_message(val, to_message=True, clock_type=None)
Definition: api.py:1128
grepros.api.get_type_alias
def get_type_alias(typename)
Definition: api.py:794
grepros.api.TypeMeta.sweep
def sweep(cls)
Definition: api.py:543
grepros.api.TypeMeta._data
_data
Definition: api.py:445
grepros.common.format_bytes
def format_bytes(size, precision=2, inter=" ", strip=True)
Definition: common.py:779
grepros.api.BaseBag.__enter__
def __enter__(self)
Definition: api.py:119
grepros.api.BaseBag.get_topic_info
def get_topic_info(self, counts=True)
Definition: api.py:227
grepros.api.TypeMeta._msg
_msg
Definition: api.py:442
grepros.api.deserialize_message
def deserialize_message(msg, cls_or_typename)
Definition: api.py:1108
grepros.api.BaseBag.__len__
def __len__(self)
Definition: api.py:128
grepros.api.calculate_definition_hash
def calculate_definition_hash(typename, msgdef, extradefs=())
Definition: api.py:623
grepros.api.make_full_typename
def make_full_typename(typename, category="msg")
Definition: api.py:867
grepros.api.TypeMeta.POPULATION
int POPULATION
Max size to constrain cache to, <=0 disables.
Definition: api.py:427
grepros.api.TypeMeta.LIFETIME
int LIFETIME
Seconds before auto-clearing message from cache, <=0 disables.
Definition: api.py:424
grepros.api.TypeMeta.discard
def discard(cls, msg)
Definition: api.py:534
grepros.api.BaseBag
Definition: api.py:85
grepros.api.TypeMeta.definition
def definition(self)
Definition: api.py:475
grepros.api.make_live_time
def make_live_time(stamp)
Definition: api.py:905
grepros.api.TypeMeta._typekey
_typekey
Definition: api.py:451
grepros.api.to_duration
def to_duration(val)
Definition: api.py:1156
grepros.api.BaseBag.filename
def filename(self)
Definition: api.py:319
grepros.api.get_message_fields
def get_message_fields(val)
Definition: api.py:746
grepros.api.get_rostime
def get_rostime(fallback=False)
Definition: api.py:765
grepros.api.validate
def validate(live=False)
Definition: api.py:585
grepros.api.BaseBag.flush
def flush(self)
Definition: api.py:310
grepros.api.TypeMeta._TIMINGS
dictionary _TIMINGS
{id(msg): time.time() of registering}
Definition: api.py:436
grepros.api.to_decimal
def to_decimal(val)
Definition: api.py:1149
grepros.api.BaseBag.__contains__
def __contains__(self, key)
Definition: api.py:141
grepros.api.create_publisher
def create_publisher(topic, cls_or_typename, queue_size)
Definition: api.py:676
grepros.api.BaseBag.closed
def closed(self)
Definition: api.py:334
grepros.api.BaseBag.get_type_and_topic_info
def get_type_and_topic_info(self, topic_filters=None)
Definition: api.py:235
grepros.api.get_alias_type
def get_alias_type(typename)
Definition: api.py:803
grepros.api.TypeMeta.typeclass
def typeclass(self)
Definition: api.py:488
grepros.api.is_ros_message
def is_ros_message(val, ignore_time=False)
Definition: api.py:812
grepros.api.canonical
def canonical(typename, unbounded=False)
Definition: api.py:664
grepros.api.init_node
def init_node(name=None)
Definition: api.py:571
grepros.api.to_sec
def to_sec(val)
Definition: api.py:1166
grepros.api.BaseBag.close
def close(self)
Definition: api.py:306
grepros.api.BaseBag.__next__
def __next__(self)
Definition: api.py:132
grepros.api.filter_fields
def filter_fields(fieldmap, top=(), include=(), exclude=())
Definition: api.py:691
grepros.api.BaseBag.size
def size(self)
Definition: api.py:324
grepros.api.is_ros_time
def is_ros_time(val)
Definition: api.py:821
grepros.api.TypeMeta.data
def data(self)
Definition: api.py:483
grepros.api.Bag.WRITER_CLASSES
WRITER_CLASSES
Bag writer classes, as {Cls, }.
Definition: api.py:369
grepros.api.TypeMeta._topic
_topic
Definition: api.py:443
grepros.api.to_sec_nsec
def to_sec_nsec(val)
Definition: api.py:1171
grepros.api.set_message_value
def set_message_value(obj, name, value)
Definition: api.py:1123
grepros.api.TypeMeta.topickey
def topickey(self)
Definition: api.py:497
grepros.api.BaseBag.get_message_class
def get_message_class(self, typename, typehash=None)
Definition: api.py:255
grepros.api.TypeMeta._topickey
_topickey
Definition: api.py:450
grepros.api.BaseBag.topics
def topics(self)
Definition: api.py:314
grepros.api.shutdown_node
def shutdown_node()
Definition: api.py:580
grepros.api.BaseBag.__iter__
def __iter__(self)
Definition: api.py:115
grepros.api.make_bag_time
def make_bag_time(stamp, bag)
Definition: api.py:879
grepros.api.BaseBag.get_end_time
def get_end_time(self)
Definition: api.py:223
grepros.api.TypeMeta.typename
def typename(self)
Definition: api.py:460
grepros.api.Bag.__subclasshook__
def __subclasshook__(cls, C)
Definition: api.py:412
grepros.api.TypeMeta._hash
_hash
Definition: api.py:448
grepros.api.dict_to_message
def dict_to_message(dct, msg)
Definition: api.py:992
grepros.api.TypeMeta._cls
_cls
Definition: api.py:449
grepros.api.TypeMeta.__enter__
def __enter__(self, *_, **__)
Definition: api.py:453
grepros.api.scalar
def scalar(typename)
Definition: api.py:1113
grepros.api.TypeMeta._CHILDREN
dictionary _CHILDREN
{id(msg): [id(nested msg), ]}
Definition: api.py:433
grepros.api.TypeMeta._type
_type
Definition: api.py:446
grepros.api.TypeMeta.typehash
def typehash(self)
Definition: api.py:467
grepros.api.BaseBag.mode
def mode(self)
Definition: api.py:329
grepros.api.Bag
Definition: api.py:350
grepros.api.BaseBag.get_message_count
def get_message_count(self, topic_filters=None)
Definition: api.py:211
grepros.api.make_message_hash
def make_message_hash(msg, include=(), exclude=())
Definition: api.py:938
grepros.api.BaseBag.__copy__
def __copy__(self)
Definition: api.py:145
grepros.api.TypeMeta.__init__
def __init__(self, msg, topic=None, source=None, data=None)
Definition: api.py:441
grepros.api.BaseBag.open
def open(self)
Definition: api.py:302
grepros.api.get_message_definition
def get_message_definition(msg_or_type)
Definition: api.py:732
grepros.api.get_message_type
def get_message_type(msg_or_cls)
Definition: api.py:755
grepros.api.BaseBag.get_start_time
def get_start_time(self)
Definition: api.py:219
grepros.api.get_message_value
def get_message_value(msg, name, typename)
Definition: api.py:760
grepros.api.TypeMeta
Definition: api.py:416
grepros.api.make_duration
def make_duration(secs=0, nsecs=0)
Definition: api.py:928
grepros.api.BaseBag.read_messages
def read_messages(self, topics=None, start_time=None, end_time=None, raw=False, **__)
Definition: api.py:271
grepros.api.BaseBag.write
def write(self, topic, msg, t=None, raw=False, **kwargs)
Definition: api.py:288
grepros.api.message_to_dict
def message_to_dict(msg, replace=None)
Definition: api.py:967
grepros.api.to_time
def to_time(val)
Definition: api.py:1176
grepros.api.BaseBag.__nonzero__
def __nonzero__(self)
Definition: api.py:137
grepros.api.TypeMeta._LASTSWEEP
_LASTSWEEP
time.time() of last cleaning of stale messages
Definition: api.py:439
grepros.api.TypeMeta.__exit__
def __exit__(self, *_, **__)
Definition: api.py:457
grepros.api.BaseBag.stop_on_error
def stop_on_error(self)
Definition: api.py:339
grepros.api.to_datetime
def to_datetime(val)
Definition: api.py:1143
grepros.api.get_topic_types
def get_topic_types()
Definition: api.py:785
grepros.api.Bag.__new__
def __new__(cls, f, mode="r", reindex=False, progress=False, **kwargs)
Definition: api.py:371
grepros.api.serialize_message
def serialize_message(msg)
Definition: api.py:1103
grepros.api.TypeMeta._source
_source
Definition: api.py:444
grepros.api.TypeMeta._CACHE
dictionary _CACHE
{id(msg): TypeMeta()}
Definition: api.py:430
grepros.api.format_message_value
def format_message_value(msg, name, value)
Definition: api.py:717
grepros.api.BaseBag.get_message_definition
def get_message_definition(self, msg_or_type)
Definition: api.py:259
grepros.api.TypeMeta._def
_def
Definition: api.py:447
grepros.api.BaseBag.__exit__
def __exit__(self, exc_type, exc_value, traceback)
Definition: api.py:124


grepros
Author(s): Erki Suurjaak
autogenerated on Sat Jan 6 2024 03:11:29