Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions synchros2/synchros2/logging.py
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,14 @@ def log(message: str) -> bool:
return log


def clear_logging_caches() -> None:
"""Clears the caches of memoized logging functions.

This is useful for testing purposes, to avoid interference between tests due to cached logging functions.
"""
make_logging_function.cache_clear()


class MemoizingRcutilsLogger:
"""An alternative, more efficient implementation of RcutilsLogger.

Expand Down
3 changes: 2 additions & 1 deletion synchros2/test/test_logging.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
from rclpy.time import Time

from synchros2.futures import unwrap_future
from synchros2.logging import LoggingSeverity, logs_to_ros
from synchros2.logging import LoggingSeverity, clear_logging_caches, logs_to_ros
from synchros2.scope import ROSAwareScope
from synchros2.subscription import Subscription

Expand All @@ -29,6 +29,7 @@ def callback(message: Log) -> None:

logger = verbose_ros.node.get_logger()
logger.set_level(LoggingSeverity.INFO)
clear_logging_caches() # ensure no interference from previous tests

assert not logger.debug("Debug message should not be logged")

Expand Down
3 changes: 1 addition & 2 deletions synchros2/test/test_tf_listener_wrapper.py
Original file line number Diff line number Diff line change
Expand Up @@ -86,8 +86,7 @@ def test_existing_transform(ros: ROSAwareScope, tf_pair: Tuple[MockTfPublisherNo
timestamp = ros.node.get_clock().now()
trans = Transform(translation=Vector3(x=1.0, y=2.0, z=3.0), rotation=Quaternion(w=1.0, x=0.0, y=0.0, z=0.0))
tf_publisher.publish_transform(trans, timestamp)
time.sleep(0.2)
t = tf_listener.lookup_a_tform_b(FRAME_ID, CHILD_FRAME_ID, timestamp)
t = tf_listener.lookup_a_tform_b(FRAME_ID, CHILD_FRAME_ID, timestamp, timeout_sec=10.0, wait_for_frames=True)
assert equal_transform(t.transform, trans)


Expand Down
Loading