Skip to content

Commit

Permalink
Merge branch 'main' into mhidalgo-bdai/deferred-feed-start
Browse files Browse the repository at this point in the history
  • Loading branch information
mhidalgo-bdai authored Nov 21, 2024
2 parents 633f292 + e4d5c80 commit a76b9fa
Show file tree
Hide file tree
Showing 3 changed files with 59 additions and 1 deletion.
5 changes: 5 additions & 0 deletions bdai_ros2_wrappers/bdai_ros2_wrappers/feeds.py
Original file line number Diff line number Diff line change
Expand Up @@ -74,6 +74,11 @@ def latest(self) -> Optional[MessageT]:
"""Gets the latest message received, if any."""
return self._tape.head

@property
def latest_update(self) -> FutureLike[MessageT]:
"""Gets the future to the latest message, which may not have been received yet."""
return self._tape.latest_write

@property
def update(self) -> FutureLike[MessageT]:
"""Gets the future to the next message yet to be received."""
Expand Down
19 changes: 18 additions & 1 deletion bdai_ros2_wrappers/bdai_ros2_wrappers/utilities.py
Original file line number Diff line number Diff line change
Expand Up @@ -169,6 +169,23 @@ def __init__(self, max_length: Optional[int] = None) -> None:
self._future_matching_writes: List[Tuple[Callable[[T], bool], Future]] = []
self._closed = False

@property
def latest_write(self) -> FutureLike[T]:
"""Gets the future to the latest data written or to be written."""
with self._lock:
if self._content is None:
raise RuntimeError("zero-length tape only writes forward")
if len(self._content) > 0:
data = self._content[-1]
latest_write = Future()
latest_write.set_result(data)
return latest_write
if self._future_write is None:
self._future_write = Future()
if self._closed:
self._future_write.cancel()
return self._future_write

@property
def future_write(self) -> FutureLike[T]:
"""Gets the future to the next data yet to be written."""
Expand Down Expand Up @@ -232,7 +249,7 @@ def head(self) -> Optional[T]:
return None
if len(self._content) == 0:
return None
return self._content[0]
return self._content[-1]

@overload
def content(
Expand Down
36 changes: 36 additions & 0 deletions bdai_ros2_wrappers/test/test_utilities.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,15 @@
from bdai_ros2_wrappers.utilities import Tape, either_or, ensure, namespace_with


def test_tape_head() -> None:
tape: Tape[int] = Tape()
assert tape.head is None
expected_sequence = list(range(10))
for i in expected_sequence:
tape.write(i)
assert tape.head == i


def test_tape_content_iteration() -> None:
tape: Tape[int] = Tape()
expected_sequence = list(range(10))
Expand Down Expand Up @@ -71,6 +80,33 @@ def test_tape_drops_unused_streams() -> None:
assert len(tape._streams) == 0


def test_tape_future_writes() -> None:
tape: Tape[int] = Tape()
tape.write(0)
future = tape.future_write
assert not future.done()
tape.write(1)
assert future.done()
assert future.result() == 1
tape.close()
future = tape.future_write
assert future.cancelled()


def test_tape_latest_writes() -> None:
tape: Tape[int] = Tape()
assert tape.head is None
future = tape.latest_write
assert not future.done()
tape.write(0)
assert tape.head == 0
assert future.done()
assert future.result() == tape.head
future = tape.latest_write
assert future.done()
assert future.result() == tape.head


def test_either_or() -> None:
assert either_or(None, "value", True)
data = argparse.Namespace(value=True)
Expand Down

0 comments on commit a76b9fa

Please sign in to comment.