Public Member Functions | Static Public Attributes | List of all members
grepros.api.BaseBag Class Reference
Inheritance diagram for grepros.api.BaseBag:
Inheritance graph
[legend]

Public Member Functions

def __bool__ (self)
 
def __contains__ (self, key)
 
def __copy__ (self)
 
def __deepcopy__ (self, memo=None)
 
def __enter__ (self)
 
def __exit__ (self, exc_type, exc_value, traceback)
 
def __getitem__ (self, key)
 
def __iter__ (self)
 
def __len__ (self)
 
def __next__ (self)
 
def __nonzero__ (self)
 
def __str__ (self)
 
def close (self)
 
def closed (self)
 
def filename (self)
 
def flush (self)
 
def get_end_time (self)
 
def get_message_class (self, typename, typehash=None)
 
def get_message_count (self, topic_filters=None)
 
def get_message_definition (self, msg_or_type)
 
def get_message_type_hash (self, msg_or_type)
 
def get_qoses (self, topic, typename)
 
def get_start_time (self)
 
def get_topic_info (self, counts=True)
 
def get_type_and_topic_info (self, topic_filters=None)
 
def mode (self)
 
def open (self)
 
def read_messages (self, topics=None, start_time=None, end_time=None, raw=False, **__)
 
def size (self)
 
def stop_on_error (self)
 
def stop_on_error (self, flag)
 
def topics (self)
 
def write (self, topic, msg, t=None, raw=False, **kwargs)
 

Static Public Attributes

 BagMessage = collections.namedtuple("BagMessage", "topic message timestamp")
 Returned from read_messages() as (topic name, ROS message, ROS timestamp object). More...
 
tuple MODES = ("r", "w", "a")
 Supported opening modes, overridden in subclasses. More...
 
 next
 
bool STREAMABLE = True
 Whether bag supports reading or writing stream objects, overridden in subclasses. More...
 
 TopicTuple
 Returned from get_type_and_topic_info() as (typename, message count, connection count, median frequency). More...
 
 TypesAndTopicsTuple = collections.namedtuple("TypesAndTopicsTuple", ["msg_types", "topics"])
 Returned from get_type_and_topic_info() as ({typename: typehash}, {topic name: TopicTuple}). More...
 

Detailed Description

ROS bag interface.

%Bag can be used a context manager, is an iterable providing (topic, message, timestamp) tuples
and supporting `len(bag)`; and supports topic-based membership
(`if mytopic in bag`, `for t, m, s in bag[mytopic]`, `len(bag[mytopic])`).

Extra methods and properties compared with rosbag.Bag: Bag.get_message_class(),
Bag.get_message_definition(), Bag.get_message_type_hash(), Bag.get_topic_info();
Bag.closed and Bag.topics.

Definition at line 85 of file api.py.

Member Function Documentation

◆ __bool__()

def grepros.api.BaseBag.__bool__ (   self)

Definition at line 139 of file api.py.

◆ __contains__()

def grepros.api.BaseBag.__contains__ (   self,
  key 
)
Returns whether bag contains given topic.

Reimplemented in grepros.ros2.ROS2Bag, grepros.plugins.mcap.McapBag, grepros.ros1.ROS1Bag, and grepros.plugins.embag.EmbagReader.

Definition at line 141 of file api.py.

◆ __copy__()

def grepros.api.BaseBag.__copy__ (   self)

Definition at line 145 of file api.py.

◆ __deepcopy__()

def grepros.api.BaseBag.__deepcopy__ (   self,
  memo = None 
)

Definition at line 147 of file api.py.

◆ __enter__()

def grepros.api.BaseBag.__enter__ (   self)
Context manager entry, opens bag if not open.

Definition at line 119 of file api.py.

◆ __exit__()

def grepros.api.BaseBag.__exit__ (   self,
  exc_type,
  exc_value,
  traceback 
)
Context manager exit, closes bag.

Definition at line 124 of file api.py.

◆ __getitem__()

def grepros.api.BaseBag.__getitem__ (   self,
  key 
)
Returns an iterator yielding messages from the bag in given topic, supporting len().

Definition at line 149 of file api.py.

◆ __iter__()

def grepros.api.BaseBag.__iter__ (   self)
Iterates over all messages in the bag.

Definition at line 115 of file api.py.

◆ __len__()

def grepros.api.BaseBag.__len__ (   self)
Returns the number of messages in the bag.

Definition at line 128 of file api.py.

◆ __next__()

def grepros.api.BaseBag.__next__ (   self)
Retrieves next message from bag as (topic, message, timestamp).

Reimplemented in grepros.ros2.ROS2Bag, grepros.plugins.mcap.McapBag, grepros.ros1.ROS1Bag, and grepros.plugins.embag.EmbagReader.

Definition at line 132 of file api.py.

◆ __nonzero__()

def grepros.api.BaseBag.__nonzero__ (   self)

Definition at line 137 of file api.py.

◆ __str__()

def grepros.api.BaseBag.__str__ (   self)
Returns informative text for bag, with a full overview of topics and types.

Definition at line 155 of file api.py.

◆ close()

def grepros.api.BaseBag.close (   self)
Closes the bag file.

Reimplemented in grepros.ros2.ROS2Bag, grepros.plugins.mcap.McapBag, grepros.ros1.ROS1Bag, and grepros.plugins.embag.EmbagReader.

Definition at line 306 of file api.py.

◆ closed()

def grepros.api.BaseBag.closed (   self)
Returns whether file is closed.

Reimplemented in grepros.ros2.ROS2Bag, grepros.plugins.mcap.McapBag, grepros.ros1.ROS1Bag, and grepros.plugins.embag.EmbagReader.

Definition at line 334 of file api.py.

◆ filename()

def grepros.api.BaseBag.filename (   self)
Returns bag file path.

Reimplemented in grepros.ros2.ROS2Bag, grepros.plugins.mcap.McapBag, and grepros.plugins.embag.EmbagReader.

Definition at line 319 of file api.py.

◆ flush()

def grepros.api.BaseBag.flush (   self)
Ensures all changes are written to bag file.

Definition at line 310 of file api.py.

◆ get_end_time()

def grepros.api.BaseBag.get_end_time (   self)
Returns the end time of the bag, as UNIX timestamp, or None if bag empty.

Reimplemented in grepros.ros1.ROS1Bag, grepros.ros2.ROS2Bag, grepros.plugins.mcap.McapBag, and grepros.plugins.embag.EmbagReader.

Definition at line 223 of file api.py.

◆ get_message_class()

def grepros.api.BaseBag.get_message_class (   self,
  typename,
  typehash = None 
)
Returns ROS message type class, or None if unknown message type for bag.

Reimplemented in grepros.ros2.ROS2Bag, grepros.ros1.ROS1Bag, grepros.plugins.mcap.McapBag, and grepros.plugins.embag.EmbagReader.

Definition at line 255 of file api.py.

◆ get_message_count()

def grepros.api.BaseBag.get_message_count (   self,
  topic_filters = None 
)
Returns the number of messages in the bag.

@param   topic_filters  list of topics or a single topic to filter by, if any

Reimplemented in grepros.ros2.ROS2Bag, grepros.plugins.mcap.McapBag, and grepros.plugins.embag.EmbagReader.

Definition at line 211 of file api.py.

◆ get_message_definition()

def grepros.api.BaseBag.get_message_definition (   self,
  msg_or_type 
)
Returns ROS message type definition full text, including subtype definitions.

Returns None if unknown message type for bag.

Reimplemented in grepros.ros2.ROS2Bag, grepros.plugins.mcap.McapBag, grepros.ros1.ROS1Bag, and grepros.plugins.embag.EmbagReader.

Definition at line 259 of file api.py.

◆ get_message_type_hash()

def grepros.api.BaseBag.get_message_type_hash (   self,
  msg_or_type 
)
Returns ROS message type MD5 hash, or None if unknown message type for bag.

Reimplemented in grepros.ros2.ROS2Bag, grepros.ros1.ROS1Bag, grepros.plugins.mcap.McapBag, and grepros.plugins.embag.EmbagReader.

Definition at line 267 of file api.py.

◆ get_qoses()

def grepros.api.BaseBag.get_qoses (   self,
  topic,
  typename 
)
Returns topic Quality-of-Service profiles as a list of dicts, or None if not available.

Functional only in ROS2.

Reimplemented in grepros.ros2.ROS2Bag, and grepros.plugins.mcap.McapBag.

Definition at line 247 of file api.py.

◆ get_start_time()

def grepros.api.BaseBag.get_start_time (   self)
Returns the start time of the bag, as UNIX timestamp, or None if bag empty.

Reimplemented in grepros.ros1.ROS1Bag, grepros.ros2.ROS2Bag, grepros.plugins.mcap.McapBag, and grepros.plugins.embag.EmbagReader.

Definition at line 219 of file api.py.

◆ get_topic_info()

def grepros.api.BaseBag.get_topic_info (   self,
  counts = True 
)
Returns topic and message type metainfo as {(topic, typename, typehash): count}.

@param   counts  if false, counts may be returned as None if lookup is costly

Definition at line 227 of file api.py.

◆ get_type_and_topic_info()

def grepros.api.BaseBag.get_type_and_topic_info (   self,
  topic_filters = None 
)
Returns thorough metainfo on topic and message types.

@param   topic_filters  list of topics or a single topic to filter returned topics-dict by,
                if any
@return                 TypesAndTopicsTuple(msg_types, topics) namedtuple,
                msg_types as dict of {typename: typehash},
                topics as a dict of {topic: TopicTuple() namedtuple}.

Reimplemented in grepros.ros2.ROS2Bag, grepros.plugins.mcap.McapBag, and grepros.plugins.embag.EmbagReader.

Definition at line 235 of file api.py.

◆ mode()

def grepros.api.BaseBag.mode (   self)
Returns file open mode.

Reimplemented in grepros.ros2.ROS2Bag, grepros.plugins.mcap.McapBag, and grepros.plugins.embag.EmbagReader.

Definition at line 329 of file api.py.

◆ open()

def grepros.api.BaseBag.open (   self)
Opens the bag file if not already open.

Reimplemented in grepros.ros2.ROS2Bag, grepros.plugins.mcap.McapBag, grepros.ros1.ROS1Bag, and grepros.plugins.embag.EmbagReader.

Definition at line 302 of file api.py.

◆ read_messages()

def grepros.api.BaseBag.read_messages (   self,
  topics = None,
  start_time = None,
  end_time = None,
  raw = False,
**  __ 
)
Yields messages from the bag, optionally filtered by topic and timestamp.

@param   topics      list of topics or a single topic to filter by, if any
@param   start_time  earliest timestamp of message to return, as ROS time or convertible
             (int/float/duration/datetime/decimal)
@param   end_time    latest timestamp of message to return, as ROS time
             (int/float/duration/datetime/decimal)
@param   raw         if true, then returned messages are tuples of
             (typename, bytes, typehash, typeclass)
             or (typename, bytes, typehash, position, typeclass),
             depending on file format
@return              BagMessage namedtuples of (topic, message, timestamp as ROS time)

Reimplemented in grepros.ros2.ROS2Bag.

Definition at line 271 of file api.py.

◆ size()

def grepros.api.BaseBag.size (   self)
Returns current file size in bytes.

Reimplemented in grepros.ros2.ROS2Bag, grepros.plugins.mcap.McapBag, and grepros.plugins.embag.EmbagReader.

Definition at line 324 of file api.py.

◆ stop_on_error() [1/2]

def grepros.api.BaseBag.stop_on_error (   self)
Whether raising read error on unknown message type (ROS2 SQLite .db3 specific).

Definition at line 339 of file api.py.

◆ stop_on_error() [2/2]

def grepros.api.BaseBag.stop_on_error (   self,
  flag 
)
Sets whether to raise read error on unknown message type (ROS2 SQLite .db3 specific).

Definition at line 344 of file api.py.

◆ topics()

def grepros.api.BaseBag.topics (   self)
Returns the list of topics in bag, in alphabetic order.

Reimplemented in grepros.ros2.ROS2Bag, grepros.plugins.mcap.McapBag, grepros.ros1.ROS1Bag, and grepros.plugins.embag.EmbagReader.

Definition at line 314 of file api.py.

◆ write()

def grepros.api.BaseBag.write (   self,
  topic,
  msg,
  t = None,
  raw = False,
**  kwargs 
)
Writes a message to the bag.

@param   topic   name of topic
@param   msg     ROS message
@param   t       message timestamp if not using current wall time, as ROS time
         or convertible (int/float/duration/datetime/decimal)
@param   raw     if true, `msg` is in raw format, (typename, bytes, typehash, typeclass)
@param   kwargs  ROS version-specific arguments,
         like `connection_header` for ROS1 or `qoses` for ROS2

Reimplemented in grepros.plugins.mcap.McapBag.

Definition at line 288 of file api.py.

Member Data Documentation

◆ BagMessage

grepros.api.BaseBag.BagMessage = collections.namedtuple("BagMessage", "topic message timestamp")
static

Returned from read_messages() as (topic name, ROS message, ROS timestamp object).

Definition at line 99 of file api.py.

◆ MODES

tuple grepros.api.BaseBag.MODES = ("r", "w", "a")
static

Supported opening modes, overridden in subclasses.

Definition at line 110 of file api.py.

◆ next

grepros.api.BaseBag.next
static

Definition at line 135 of file api.py.

◆ STREAMABLE

bool grepros.api.BaseBag.STREAMABLE = True
static

Whether bag supports reading or writing stream objects, overridden in subclasses.

Definition at line 113 of file api.py.

◆ TopicTuple

grepros.api.BaseBag.TopicTuple
static
Initial value:
= collections.namedtuple("TopicTuple", ["msg_type", "message_count",
"connections", "frequency"])

Returned from get_type_and_topic_info() as (typename, message count, connection count, median frequency).

Definition at line 103 of file api.py.

◆ TypesAndTopicsTuple

grepros.api.BaseBag.TypesAndTopicsTuple = collections.namedtuple("TypesAndTopicsTuple", ["msg_types", "topics"])
static

Returned from get_type_and_topic_info() as ({typename: typehash}, {topic name: TopicTuple}).

Definition at line 107 of file api.py.


The documentation for this class was generated from the following file:


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