test_library.py
Go to the documentation of this file.
1 #!/usr/bin/env python3
2 # -*- coding: utf-8 -*-
3 """
4 Test: main functions and classes of grepros as library.
5 
6 ------------------------------------------------------------------------------
7 This file is part of grepros - grep for ROS bag files and live topics.
8 Released under the BSD License.
9 
10 @author Erki Suurjaak
11 @created 15.12.2022
12 @modified 28.12.2023
13 ------------------------------------------------------------------------------
14 """
15 import glob
16 import inspect
17 import logging
18 import os
19 import random
20 import re
21 import sys
22 import tempfile
23 
24 import std_msgs.msg
25 
26 import grepros
27 from grepros import api
28 
29 
30 sys.path.insert(0, os.path.join(os.path.dirname(__file__), ".."))
31 from test import testbase
32 
33 logger = logging.getLogger()
34 
35 
37  """Tests using grepros main functions and classes as a library."""
38 
39 
40  NAME = os.path.splitext(os.path.basename(__file__))[0]
41 
42 
43  OUTPUT_LABEL = "various sinks"
44 
45 
46  OUTPUT_SUFFIX = testbase.TestBase.BAG_SUFFIX
47 
48 
49  def __init__(self, *args, **kwargs):
50  super().__init__(*args, **kwargs)
51  self._tempnames = [] # Names of temporary files for write output
52 
53 
54  def setUp(self):
55  """Collects and verifies bags in data directory."""
56  super().setUp()
57  grepros.init()
58  self.verify_bags()
59 
60 
61  def tearDown(self):
62  """Deletes temporary output files, if any."""
63  while self._tempnames:
64  try: os.unlink(self._tempnames.pop())
65  except Exception: pass
66  super().tearDown()
67 
68 
69  def test_bag_rw_grep(self):
70  """Tests reading and writing bags and matching messages."""
71  logger.info("Verifying reading and writing bags, and grepping messages.")
72  grep = grepros.Scanner(pattern=self.SEARCH_WORDS,
73  topic="/match/this*", no_topic="/not/this*",
74  type="std_msgs/*", no_type="std_msgs/Bool")
75  logger.debug("Writing to bag %r.", self._outname)
76  with grepros.Bag(self._outname, mode="w") as outbag:
77  for bagname in self._bags:
78  logger.debug("Reading from bag %r.", bagname)
79  with grepros.Bag(bagname) as inbag:
80  for topic, msg, stamp in inbag:
81  if grep.match(topic, msg, stamp):
82  outbag.write(topic, msg, stamp)
83 
84  logger.debug("Validating messages written to %r.", self._outname)
85  messages = {} # {topic: [msg, ]}
86  outfile = self._outfile = testbase.BagReader(self._outname)
87  for topic, msg, _ in outfile.read_messages():
88  messages.setdefault(topic, []).append(msg)
89  outfile.close()
90  fulltext = "\n".join(str(m) for mm in messages.values() for m in mm)
91  super(TestLibrary, self).verify_topics(messages, fulltext)
92 
93 
95  """Tests Bag class general interface."""
96  logger.info("Verifying Bag-class attributes.")
97  self.verify_bag_attributes(grepros.Bag, self._bags[0], self._outname)
98  if ".mcap" in api.BAG_EXTENSIONS:
99  outname = self.mkfile(".mcap")
100  self.verify_bag_attributes(grepros.McapBag, outname, outname)
101 
102 
103  def verify_bag_attributes(self, bagcls, infilename, outfilename):
104  """Tests general interface for given bag class."""
105  logger.info("Verifying Bag %s attributes.", bagcls)
106 
107  bag = bagcls(outfilename, mode="w")
108  self.assertEqual(bag.mode, "w", "Unexpected result for Bag.mode.")
109  self.assertGreaterEqual(bag.size, 0, "Unexpected result for Bag.size.")
110  bag.open()
111  self.assertFalse(bag.closed, "Unexpected result for Bag.closed.")
112  self.assertEqual(bag.get_message_count(), 0,
113  "Unexpected result for Bag.get_message_count().")
114  self.assertEqual(bag.get_start_time(), None,
115  "Unexpected result for Bag.get_start_time().")
116  self.assertEqual(bag.get_end_time(), None,
117  "Unexpected result for Bag.get_end_time().")
118  self.assertIsInstance(bag.get_topic_info(), dict,
119  "Unexpected result for Bag.get_topic_info().")
120  self.assertIsInstance(bag.get_type_and_topic_info(), tuple,
121  "Unexpected result for Bag.get_type_and_topic_info().")
122  bag.write("/my/topic", std_msgs.msg.Bool())
123  with self.assertRaises(Exception):
124  next(bag, None) # Should raise as mode is "w"
125 
126  bag.close()
127  self.assertTrue(bag.closed, "Unexpected result for Bag.closed.")
128 
129  bag = bagcls(infilename)
130  self.assertIsInstance(bag.size, int, "Unexpected result for Bag.size.")
131  with bag:
132  self.assertFalse(bag.closed, "Unexpected result for Bag.closed.")
133  topic, msg, stamp = next(bag)
134  self.assertIsInstance(topic, str, "Unexpected result for next(Bag).")
135  self.assertTrue(api.is_ros_message(msg), "Unexpected result for next(Bag).")
136  self.assertTrue(api.is_ros_time(stamp), "Unexpected result for next(Bag).")
137  with self.assertRaises(Exception):
138  bag.write(topic, msg, stamp) # Should raise as mode is "r"
139 
140  self.assertIsInstance(len(bag), int, "Unexpected result for len(Bag).")
141  self.assertTrue(bool(bag), "Unexpected result for bool(Bag).")
142  self.assertIsInstance(bag.size, int, "Unexpected result for Bag.size.")
143  self.assertEqual(bag.mode, "r", "Unexpected result for Bag.mode.")
144 
145  self.assertTrue(callable(bag.get_message_class),
146  "Unexpected result for Bag.get_message_class.")
147  self.assertTrue(callable(bag.get_message_definition),
148  "Unexpected result for Bag.get_message_definition.")
149  self.assertTrue(callable(bag.get_message_type_hash),
150  "Unexpected result for Bag.get_message_type_hash.")
151  self.assertTrue(callable(bag.get_qoses),
152  "Unexpected result for Bag.get_qoses.")
153 
154  self.assertIsInstance(bag.get_message_count(), int,
155  "Unexpected result for Bag.get_message_count().")
156  self.assertIsInstance(bag.get_end_time(), (float, int),
157  "Unexpected result for Bag.get_start_time().")
158  self.assertIsInstance(bag.get_end_time(), (float, int),
159  "Unexpected result for Bag.get_end_time().")
160  self.assertIsInstance(bag.get_topic_info(), dict,
161  "Unexpected result for Bag.get_topic_info().")
162  self.assertIsInstance(bag.get_type_and_topic_info(), tuple,
163  "Unexpected result for Bag.get_type_and_topic_info().")
164 
165  self.assertTrue(bag.closed, "Unexpected result for Bag.closed.")
166 
167 
169  """Tests parameters to Bag functions."""
170  logger.info("Verifying invoking Bag methods with parameters.")
173  if ".mcap" in api.BAG_EXTENSIONS:
174  outname = self.mkfile(".mcap")
177 
178 
179  def verify_bag_parameters_read(self, bagcls, filename):
180  """Tests parameters to read functions of given Bag class."""
181  NAME = lambda f, *a: "%s.%s(%s)" % (f.__module__, (f.__name__), ", ".join(map(repr, a)))
182  ERR = lambda f, *a: "Unexpected result from %s(%s)." % (f.__name__, ", ".join(map(repr, a)))
183 
184  logger.info("Verifying invoking Bag %r read methods with parameters.", bagcls)
185 
186  messages = {} # {topic: [(message, stamp)]}
187  with bagcls(filename) as bag:
188  for t, m, s in bag: messages.setdefault(t, []).append((m, s))
189  self.assertTrue(messages, "Unexpected result for reading bag contents.")
190 
191  bag = bagcls(filename)
192  bag.open()
193 
194  func = bag.get_message_class
195  with self.subTest(NAME(func)):
196  logger.info("Testing %s.", NAME(func))
197  typename = "std_msgs/Bool"
198  self.assertEqual(func(typename + "unknown"), None, ERR(func))
199  self.assertEqual(func(typename, "wronghash"), None, ERR(func))
200  cls = func(typename)
201  self.assertTrue(api.is_ros_message(cls), ERR(func))
202  self.assertEqual(api.get_message_type(cls), typename, ERR(func))
203 
204  func = bag.read_messages
205  with self.subTest(NAME(func)):
206  # Bag.read_messages(topics=None, start_time=None, end_time=None, raw=False)
207  logger.info("Testing %s.", NAME(func))
208 
209  logger.debug("Verifying %s.", NAME(func, "topics"))
210  topics = random.sample(list(messages), 2)
211  mymsgs = {}
212  for topic, msg, stamp in func(topics):
213  mymsgs.setdefault(topic, []).append((msg, stamp))
214  for topic in topics:
215 
216  self.assertEqual([(api.message_to_dict(m), t) for m, t in mymsgs[topic]],
217  [(api.message_to_dict(m), t) for m, t in messages[topic]],
218  ERR(func, "topics"))
219 
220  topic, shift = next(iter(topics)), api.make_duration(1)
221  logger.debug("Verifying %s.", NAME(func, "topic", "start_time=.."))
222  start_time = messages[topic][-1][-1] + shift
223  nomsgs = list(func(topic, start_time=start_time))
224  self.assertFalse(nomsgs, ERR(func, "topic", "start_time=.."))
225  logger.debug("Verifying %s.", NAME(func, "topic", "end_time=.."))
226  end_time = messages[topic][0][-1] - shift
227  nomsgs = list(func(topic, end_time=end_time))
228  self.assertFalse(nomsgs, ERR(func, "topic", "end_time=.."))
229 
230  logger.debug("Verifying %s.", NAME(func, "topic", "..", "raw=True"))
231  start_time, end_time = messages[topic][0][-1], messages[topic][-1][-1]
232  for _, msg, _ in func(topic, start_time=start_time, end_time=end_time, raw=True):
233  bbytes, typeclass = msg[1], msg[-1]
234  self.assertIsInstance(bbytes, bytes, ERR(func, "topic", "..", "raw=True"))
235  self.assertTrue(inspect.isclass(typeclass), ERR(func, "topic", "..", "raw=True"))
236 
237  func = bag.get_message_definition
238  with self.subTest(NAME(func)):
239  # Bag.get_message_definition(msg_or_type)
240  logger.info("Testing %s.", NAME(func))
241  msgcls = func("std_msgs/Bool")
242  self.assertTrue(msgcls, ERR(func))
243  self.assertIsInstance(msgcls, str, ERR(func))
244  msgcls = func(std_msgs.msg.Bool)
245  self.assertTrue(msgcls, ERR(func))
246  self.assertIsInstance(msgcls, str, ERR(func))
247 
248  func = bag.get_message_type_hash
249  with self.subTest(NAME(func)):
250  # Bag.get_message_type_hash(msg_or_type)
251  logger.info("Testing %s.", NAME(func))
252  typehash = func("std_msgs/Bool")
253  self.assertTrue(typehash, ERR(func))
254  self.assertIsInstance(typehash, str, ERR(func))
255  typehash = func(std_msgs.msg.Bool)
256  self.assertTrue(typehash, ERR(func))
257  self.assertIsInstance(typehash, str, ERR(func))
258 
259  func = bag.get_qoses
260  with self.subTest(NAME(func)):
261  # Bag.get_qoses(topic, typename)
262  logger.info("Testing %s.", NAME(func))
263  topic = next(iter(messages))
264  typename = api.get_message_type(messages[topic][0][0])
265  received = func(topic, typename)
266  expected = type(None) if api.ROS1 else (list, type(None))
267  self.assertIsInstance(received, expected, ERR(func))
268 
269  func = bag.get_type_and_topic_info
270  with self.subTest(NAME(func)):
271  # Bag.get_type_and_topic_info(topic_filters=None)
272  logger.info("Testing %s.", NAME(func))
273  topic = next(iter(messages))
274  typename = api.get_message_type(messages[topic][0][0])
275  msg_types, topics = func(topic_filters=topic)
276  self.assertGreaterEqual(len(msg_types), 1, ERR(func, "topic_filters=sometopic"))
277  self.assertEqual(len(topics), 1, ERR(func, "topic_filters=sometopic"))
278  self.assertIn(typename, msg_types, ERR(func, "topic_filters=sometopic"))
279  self.assertIn(topic, topics, ERR(func, "topic_filters=sometopic"))
280 
281  func = bag.get_message_count
282  with self.subTest(NAME(func)):
283  # Bag.get_message_count(topic_filters=None)
284  logger.info("Testing %s.", NAME(func))
285  for count in (1, 2):
286  topics = random.sample(list(messages), count)
287  received = func(topic_filters=topics)
288  expected = sum(len(messages[t]) for t in topics)
289  self.assertEqual(received, expected, ERR(func, "topic_filters=sometopics"))
290 
291  bag.close()
292 
293 
294  bag = bagcls(filename)
295  bag.open()
296 
297  func = bag.get_topic_info
298  with self.subTest(NAME(func)):
299  # Bag.get_topic_info(counts=False)
300  logger.info("Testing %s.", NAME(func))
301  counts = list(func(counts=True).values())
302  self.assertNotIn(None, counts, ERR(func, "counts=True"))
303 
304 
305  def verify_bag_parameters_write(self, bagcls, filename):
306  """Tests parameters to write functions of given Bag class."""
307  NAME = lambda f, *a: "%s.%s(%s)" % (f.__module__, (f.__name__), ", ".join(map(repr, a)))
308  ERR = lambda f, *a: "Unexpected result from %s(%s)." % (f.__name__, ", ".join(map(repr, a)))
309 
310  logger.info("Verifying invoking Bag %r write methods with parameters.", bagcls)
311 
312  messages = {} # {topic: [message, ]}
313  bag = bagcls(filename, "w")
314  bag.open()
315 
316  func = bag.write
317  with self.subTest(NAME(func)):
318  # Bag.write(topic, msg, t=None, raw=False)
319  logger.info("Testing %s.", NAME(func))
320  topicbase, typename = "/my/topic", "std_msgs/Bool"
321  typehash, typeclass = api.get_message_type_hash(typename), std_msgs.msg.Bool
322  for i in range(5):
323  topic, msg = "%s/%s" % (topicbase, i % 2), std_msgs.msg.Bool(data=bool(i % 2))
324  bbytes = api.serialize_message(msg)
325  bag.write(topic, (typename, bbytes, typehash, typeclass), raw=True)
326  messages.setdefault(topic, []).append(msg)
327 
328  bag.close()
329  bag = bagcls(filename)
330  bag.open()
331  for topic, msg, stamp in bag:
332  self.assertIn(topic, messages, ERR(func, "..", "raw=True"))
333  self.assertTrue(any(api.message_to_dict(msg) == api.message_to_dict(m)
334  for m in messages[topic]), ERR(func, "..", "raw=True"))
335 
336  bag.close()
337 
338 
340  """Tests grepros global functions: init(), grep(), source(), sink()."""
341  grepros.init() # Should not raise if called twice
342  self.verify_grep()
343  self.verify_sources_sinks()
344 
345 
346  def test_rollover(self):
347  """Tests rollover settings for sinks."""
348  NAME = lambda f: "%s.%s" % (f.__module__, f.__name__)
349  logger.debug("Verifying sink rollover.")
351  ([grepros.McapSink] if ".mcap" in api.BAG_EXTENSIONS else [])
352  TEMPLATE = "test_%Y_%m_%d__%(index)s__%(index)s"
353  OPTS = [ # [({..rollover opts..}, (min files, max files or None for undetermined))]
354  (dict(rollover_size=2000), (2, None)),
355  (dict(rollover_count=40), (2, 3)),
356  (dict(rollover_duration=40), (2, 3)),
357  ]
358  OPT_OVERRIDES = {grepros.McapSink: dict(rollover_size=None)} # MCAP has 1MB cache
359 
360  START = api.to_time(12345)
361  for cls in SINKS:
362  EXT = api.BAG_EXTENSIONS[0] if cls is grepros.BagSink else cls.FILE_EXTENSIONS[0]
363  WRITE, OUTDIR = next((x, os.path.dirname(x)) for x in [self.mkfile(EXT)])
364  with self.subTest(NAME(cls)):
365  logger.info("Testing %s rollover.", NAME(cls))
366  for ropts, output_range in OPTS:
367  if cls in OPT_OVERRIDES and any(k in ropts for k in OPT_OVERRIDES[cls]):
368  ropts.update(OPT_OVERRIDES[cls])
369  if not any(ropts.values()): continue # for ropts
370  logger.info("Testing %s rollover with %s.", NAME(cls), ropts)
371  SUFF = "".join("%s=%s" % x for x in ropts.items())
372  template = os.path.join(OUTDIR, TEMPLATE + SUFF + EXT)
373 
374  with cls(WRITE, write_options=dict(ropts, rollover_template=template)) as sink:
375  for i in range(100):
376  msg = std_msgs.msg.Bool(data=not i % 2)
377  sink.emit("my/topic%s" % (i % 2), msg, START + api.make_duration(i))
378 
379  outputs = sorted(glob.glob(os.path.join(OUTDIR, "test_*" + SUFF + EXT)))
380  self._tempnames.extend(outputs)
381  self.assertGreaterEqual(len(outputs), output_range[0],
382  "Unexpected output files from %s." % NAME(cls))
383  if output_range[1] is not None:
384  self.assertLessEqual(len(outputs), output_range[1],
385  "Unexpected output files from %s." % NAME(cls))
386  self.assertFalse(os.path.exists(WRITE), "Unexpected output from %s." % NAME(cls))
387  for name in map(os.path.basename, outputs):
388  self.assertTrue(re.search(r"^test_\d+_\d+_\d+__\d+__\d+", name),
389  "Unexpected output file from %s." % NAME(cls))
390 
391 
392  def verify_grep(self):
393  """Tests grepros.grep()."""
394  NAME = lambda f, **w: "%s.%s(%s)" % (f.__module__, f.__name__, "**%s" % w if w else "")
395  ERR = lambda f, **w: "Unexpected result from %s." % NAME(f, **w)
396  logger.info("Verifying reading bags and grepping messages, via grepros.grep().")
397  messages = {} # {topic: [msg, ]}
398  args = dict(pattern=self.SEARCH_WORDS, topic="/match/this*", no_topic="/not/this*",
399  file=self._bags, type="std_msgs/*", no_type="std_msgs/Bool")
400  for topic, msg, stamp, match, index in grepros.grep(**args):
401  self.assertIn("/match/this", topic, ERR(grepros.grep, **args))
402  self.assertNotIn("/not/this", topic, ERR(grepros.grep, **args))
403  self.assertIn("std_msgs/", api.get_message_type(msg), ERR(grepros.grep, **args))
404  self.assertNotIn("/Bool", api.get_message_type(msg), ERR(grepros.grep, **args))
405  self.assertTrue(match, ERR(grepros.grep, **args))
406  self.assertIsInstance(index, int, ERR(grepros.grep, **args))
407  messages.setdefault(topic, []).append(msg)
408  fulltext = "\n".join(str(m) for mm in messages.values() for m in mm)
409  super(TestLibrary, self).verify_topics(messages, fulltext)
410 
411 
413  """Tests general Source and Sink API."""
414  NAME = lambda f, **w: "%s.%s(%s)" % (f.__module__, f.__name__, "**%s" % w if w else "")
415  ERR = lambda f, **w: "Unexpected result from %s." % NAME(f, **w)
416 
417  FUNC_TESTS = { # {function: [({..kwargs..}, expected source class), ]}
418  grepros.source: [
419  (dict(app=True), grepros.AppSource),
420  (dict(file=self._bags), grepros.BagSource),
421  (dict(live=True), grepros.TopicSource),
422  ],
423  grepros.sink: [
424  (dict(app=True), grepros.AppSink),
425  (dict(app=lambda *_: _), grepros.AppSink),
426  (dict(console=True), grepros.ConsoleSink),
427  (dict(publish=True), grepros.TopicSink),
428  (dict(app=True, console=True), grepros.MultiSink),
429  (dict(app=True, publish=True), grepros.MultiSink),
430  (dict(console=True, publish=True), grepros.MultiSink),
431  (dict(write=self._outname), grepros.BagSink),
432  (dict(write=self.mkfile(".csv")), grepros.CsvSink),
433  (dict(write=self.mkfile(".html")), grepros.HtmlSink),
434  (dict(write=self.mkfile(".sql")), grepros.SqlSink),
435  (dict(write=self.mkfile(".sqlite")), grepros.SqliteSink),
436  ],
437  }
438  if ".mcap" in api.BAG_EXTENSIONS: FUNC_TESTS[grepros.sink].append(
439  (dict(write=self.mkfile(".mcap")), grepros.McapSink),
440  )
441  if "parquet" in grepros.MultiSink.FORMAT_CLASSES: FUNC_TESTS[grepros.sink].append(
442  (dict(write=self.mkfile(".parquet")), grepros.ParquetSink),
443  )
444 
445  for func, args in FUNC_TESTS.items():
446  logger.info("Verifying %s.", NAME(func))
447  for kwargs, cls in args:
448  logger.debug("Verifying %s.", NAME(func, **kwargs))
449  with func(**kwargs) as source:
450  self.assertIsInstance(source, cls, ERR(func, **kwargs))
451 
452 
453  logger.debug("Verifying grepros.PostgresSink failing for invalid configuration.",)
454  with self.assertRaises(Exception, msg="Unexpected success from PostgresSink()."):
455  with grepros.PostgresSink("username=nosuchuser dbname=nosuchdb") as sink:
456  sink.validate()
457  with self.assertRaises(Exception, msg="Unexpected success from PostgresSink()."):
458  with grepros.sink("postgresql://nosuchuser/nosuchdb") as sink:
459  sink.validate()
460 
461  logger.debug("Verifying grepros.AppSource and AppSink.")
462  expected, received = [], []
463  iterable = [("/my/topic", std_msgs.msg.String(data="my")), None]
464  emitter = lambda *a: received.append(a)
465  source = grepros.AppSource(iterable=iterable)
466  sink = grepros.AppSink(emit=emitter)
467  for topic, msg, stamp in source:
468  sink.emit(topic, msg, stamp)
469  expected.append((topic, msg, stamp))
470  source.push("/other/topic", std_msgs.msg.String(data="other"))
471  source.push("/third/topic", std_msgs.msg.String(data="third"))
472  source.push(None)
473  for topic, msg, stamp in source:
474  sink.emit(topic, msg, stamp)
475  expected.append((topic, msg, stamp))
476  self.assertEqual(len(received), len(expected), ERR(type(sink)))
477  for a, b in zip(received, expected):
478  self.assertEqual(a[:2], b[:2], ERR(type(sink)))
479 
480 
481  def mkfile(self, suffix):
482  """Returns temporary filename with given suffix, deleted in teardown."""
483  name = tempfile.NamedTemporaryFile(suffix=suffix).name
484  self._tempnames.append(name)
485  return name
486 
487 
488 if "__main__" == __name__:
489  TestLibrary.run_rostest()
test.test_library.TestLibrary.setUp
def setUp(self)
Definition: test_library.py:54
grepros.outputs.BagSink
Definition: outputs.py:591
test.test_library.TestLibrary.__init__
def __init__(self, *args, **kwargs)
Definition: test_library.py:49
test.test_library.TestLibrary.verify_bag_parameters_read
def verify_bag_parameters_read(self, bagcls, filename)
Definition: test_library.py:179
grepros.outputs.ConsoleSink
Definition: outputs.py:506
test.test_library.TestLibrary.NAME
NAME
Test name used in flow logging.
Definition: test_library.py:40
test.test_library.TestLibrary._tempnames
_tempnames
Definition: test_library.py:51
grepros.plugins.auto.sqlite.SqliteSink
Definition: sqlite.py:28
test.testbase.TestBase
Definition: testbase.py:46
test.testbase.TestBase.SEARCH_WORDS
list SEARCH_WORDS
Words searched in bag.
Definition: testbase.py:68
grepros.outputs.MultiSink
Definition: outputs.py:850
grepros.inputs.TopicSource
Definition: inputs.py:806
grepros.search.Scanner
Definition: search.py:26
grepros.plugins.auto.postgres.PostgresSink
Definition: postgres.py:30
grepros.inputs.AppSource
Definition: inputs.py:1023
grepros.plugins.auto.csv.CsvSink
Definition: csv.py:29
grepros.outputs.AppSink
Definition: outputs.py:812
test.testbase.TestBase.verify_topics
def verify_topics(self, topics, messages=None)
Definition: testbase.py:176
test.test_library.TestLibrary.test_rollover
def test_rollover(self)
Definition: test_library.py:346
test.test_library.TestLibrary.verify_bag_attributes
def verify_bag_attributes(self, bagcls, infilename, outfilename)
Definition: test_library.py:103
grepros.outputs.TopicSink
Definition: outputs.py:728
test.test_library.TestLibrary
Definition: test_library.py:36
test.testbase.TestBase.subTest
def subTest(self, msg=None, **params)
Definition: testbase.py:123
test.test_library.TestLibrary.test_bag_attributes
def test_bag_attributes(self)
Definition: test_library.py:94
test.test_library.TestLibrary.tearDown
def tearDown(self)
Definition: test_library.py:61
test.testbase.TestBase._outname
_outname
Definition: testbase.py:97
grepros.api.Bag
Definition: api.py:350
test.test_library.TestLibrary.verify_grep
def verify_grep(self)
Definition: test_library.py:392
test.test_library.TestLibrary._outfile
_outfile
Definition: test_library.py:86
grepros.plugins.sql.SqlSink
Definition: sql.py:30
test.test_library.TestLibrary.verify_sources_sinks
def verify_sources_sinks(self)
Definition: test_library.py:412
grepros.plugins.auto.html.HtmlSink
Definition: html.py:30
test.test_library.TestLibrary.verify_bag_parameters_write
def verify_bag_parameters_write(self, bagcls, filename)
Definition: test_library.py:305
test.test_library.TestLibrary.mkfile
def mkfile(self, suffix)
Definition: test_library.py:481
test.testbase.TestBase._bags
_bags
Definition: testbase.py:94
test.test_library.TestLibrary.test_global_library
def test_global_library(self)
Definition: test_library.py:339
grepros.inputs.BagSource
Definition: inputs.py:428
grepros.plugins.mcap.McapSink
Definition: mcap.py:562
test.test_library.TestLibrary.test_bag_parameters
def test_bag_parameters(self)
Definition: test_library.py:168
test.testbase.TestBase.verify_bags
def verify_bags(self)
Definition: testbase.py:169
grepros.plugins.parquet.ParquetSink
Definition: parquet.py:34
test.test_library.TestLibrary.test_bag_rw_grep
def test_bag_rw_grep(self)
Definition: test_library.py:69
grepros.plugins.mcap.McapBag
Definition: mcap.py:41


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