diff --git a/dimos/core/__init__.py b/dimos/core/__init__.py index bbdd22afef..a490477e16 100644 --- a/dimos/core/__init__.py +++ b/dimos/core/__init__.py @@ -14,6 +14,7 @@ from dimos.core.rpc_client import RPCClient from dimos.core.stream import In, Out, RemoteIn, RemoteOut, Transport from dimos.core.transport import ( + DDSTransport, LCMTransport, SHMTransport, ZenohTransport, @@ -36,6 +37,7 @@ "LCMRPC", "LCMTF", "TF", + "DDSTransport", "DimosCluster", "In", "LCMTransport", diff --git a/dimos/core/transport.py b/dimos/core/transport.py index 318c25195f..88b19bc8a0 100644 --- a/dimos/core/transport.py +++ b/dimos/core/transport.py @@ -14,6 +14,7 @@ from __future__ import annotations +import threading from typing import Any, TypeVar import dimos.core.colors as colors @@ -27,6 +28,7 @@ from dimos.core.stream import In, Out, Stream, Transport from dimos.msgs.protocol import DimosMsg +from dimos.protocol.pubsub.ddspubsub import DDS, Topic as DDSTopic from dimos.protocol.pubsub.impl.jpeg_shm import JpegSharedMemory from dimos.protocol.pubsub.impl.lcmpubsub import LCM, JpegLCM, PickleLCM, Topic as LCMTopic from dimos.protocol.pubsub.impl.rospubsub import DimosROS, ROSTopic @@ -258,4 +260,36 @@ def stop(self) -> None: self._ros = None +class DDSTransport(PubSubTransport[T]): + def __init__(self, topic: str, type: type, **kwargs) -> None: # type: ignore[no-untyped-def] + super().__init__(DDSTopic(topic, type)) + self.dds = DDS(**kwargs) + self._started: bool = False + self._start_lock = threading.RLock() + + def start(self) -> None: + with self._start_lock: + if not self._started: + self.dds.start() + self._started = True + + def stop(self) -> None: + with self._start_lock: + if self._started: + self.dds.stop() + self._started = False + + def broadcast(self, _, msg) -> None: + with self._start_lock: + if not self._started: + self.start() + self.dds.publish(self.topic, msg) + + def subscribe(self, callback: Callable[[T], None], selfstream: In[T] = None) -> None: # type: ignore[assignment, override] + with self._start_lock: + if not self._started: + self.start() + return self.dds.subscribe(self.topic, lambda msg, topic: callback(msg)) # type: ignore[return-value] + + class ZenohTransport(PubSubTransport[T]): ... diff --git a/dimos/protocol/pubsub/__init__.py b/dimos/protocol/pubsub/__init__.py index 94a58b60de..0c88af0b60 100644 --- a/dimos/protocol/pubsub/__init__.py +++ b/dimos/protocol/pubsub/__init__.py @@ -1,3 +1,4 @@ +import dimos.protocol.pubsub.ddspubsub as dds import dimos.protocol.pubsub.impl.lcmpubsub as lcm from dimos.protocol.pubsub.impl.memory import Memory from dimos.protocol.pubsub.spec import PubSub @@ -5,5 +6,6 @@ __all__ = [ "Memory", "PubSub", + "dds", "lcm", ] diff --git a/dimos/protocol/pubsub/benchmark/testdata.py b/dimos/protocol/pubsub/benchmark/testdata.py index bc0941e50b..724bec7f59 100644 --- a/dimos/protocol/pubsub/benchmark/testdata.py +++ b/dimos/protocol/pubsub/benchmark/testdata.py @@ -14,12 +14,21 @@ from collections.abc import Generator from contextlib import contextmanager +from dataclasses import dataclass from typing import Any +from cyclonedds.idl import IdlStruct +from cyclonedds.idl.types import sequence, uint8 import numpy as np from dimos.msgs.sensor_msgs.Image import Image, ImageFormat from dimos.protocol.pubsub.benchmark.type import Case +from dimos.protocol.pubsub.ddspubsub import ( + DDS, + HIGH_THROUGHPUT_QOS, + RELIABLE_QOS, + Topic as DDSTopic, +) from dimos.protocol.pubsub.impl.lcmpubsub import LCM, LCMPubSubBase, Topic as LCMTopic from dimos.protocol.pubsub.impl.memory import Memory from dimos.protocol.pubsub.impl.shmpubsub import ( @@ -174,6 +183,52 @@ def shm_lcm_pubsub_channel() -> Generator[LCMSharedMemory, None, None]: ) +@dataclass +class DDSBenchmarkData(IdlStruct): + """DDS message type for benchmarking with variable-size byte payload.""" + + data: sequence[uint8] # type: ignore[type-arg] + + +@contextmanager +def dds_high_throughput_pubsub_channel() -> Generator[DDS, None, None]: + """DDS with HIGH_THROUGHPUT_QOS - BestEffort, optimized for speed.""" + dds_pubsub = DDS(qos=HIGH_THROUGHPUT_QOS) + dds_pubsub.start() + yield dds_pubsub + dds_pubsub.stop() + + +@contextmanager +def dds_reliable_pubsub_channel() -> Generator[DDS, None, None]: + """DDS with RELIABLE_QOS - guaranteed delivery.""" + dds_pubsub = DDS(qos=RELIABLE_QOS) + dds_pubsub.start() + yield dds_pubsub + dds_pubsub.stop() + + +def dds_msggen(size: int) -> tuple[DDSTopic, DDSBenchmarkData]: + """Generate DDS message for benchmark.""" + topic = DDSTopic(name="benchmark/dds", data_type=DDSBenchmarkData) + return (topic, DDSBenchmarkData(data=list(make_data_bytes(size)))) + + +testcases.append( + Case( + pubsub_context=dds_high_throughput_pubsub_channel, + msg_gen=dds_msggen, + ) +) + +testcases.append( + Case( + pubsub_context=dds_reliable_pubsub_channel, + msg_gen=dds_msggen, + ) +) + + try: from dimos.protocol.pubsub.impl.redispubsub import Redis diff --git a/dimos/protocol/pubsub/ddspubsub.py b/dimos/protocol/pubsub/ddspubsub.py new file mode 100644 index 0000000000..889b0b8449 --- /dev/null +++ b/dimos/protocol/pubsub/ddspubsub.py @@ -0,0 +1,178 @@ +# Copyright 2025-2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from __future__ import annotations + +from collections.abc import Callable +from dataclasses import dataclass +import threading +from typing import TYPE_CHECKING, Any, TypeAlias + +from cyclonedds.core import Listener +from cyclonedds.pub import DataWriter as DDSDataWriter +from cyclonedds.qos import Policy, Qos +from cyclonedds.sub import DataReader as DDSDataReader +from cyclonedds.topic import Topic as DDSTopic + +from dimos.protocol.pubsub.spec import PubSub +from dimos.protocol.service.ddsservice import DDSService +from dimos.utils.logging_config import setup_logger + +if TYPE_CHECKING: + from cyclonedds.idl import IdlStruct + +logger = setup_logger() + + +# High-throughput QoS preset +HIGH_THROUGHPUT_QOS = Qos( + Policy.Reliability.BestEffort, + Policy.History.KeepLast(depth=1), + Policy.Durability.Volatile, +) + +# Reliable QoS preset +RELIABLE_QOS = Qos( + Policy.Reliability.Reliable(max_blocking_time=0), + Policy.History.KeepLast(depth=5000), + Policy.Durability.Volatile, +) + + +@dataclass(frozen=True) +class Topic: + """Represents a DDS topic.""" + + name: str + data_type: type[IdlStruct] + + def __str__(self) -> str: + return f"{self.name}#{self.data_type.__name__}" + + +MessageCallback: TypeAlias = Callable[[Any, Topic], None] + + +class _DDSMessageListener(Listener): + """Listener for DataReader that dispatches messages to callbacks.""" + + __slots__ = ("_callbacks", "_lock", "_topic") + + def __init__(self, topic: Topic) -> None: + super().__init__() + self._topic = topic + self._callbacks: tuple[MessageCallback, ...] = () + self._lock = threading.Lock() + + def add_callback(self, callback: MessageCallback) -> None: + """Add a callback to the listener.""" + with self._lock: + self._callbacks = (*self._callbacks, callback) + + def remove_callback(self, callback: MessageCallback) -> None: + """Remove a callback from the listener.""" + with self._lock: + self._callbacks = tuple(cb for cb in self._callbacks if cb is not callback) + + def on_data_available(self, reader: DDSDataReader[Any]) -> None: + """Called when data is available on the reader.""" + try: + samples = reader.take() + except Exception as e: + logger.error(f"Error reading from topic {self._topic}: {e}", exc_info=True) + return + for sample in samples: + if sample is not None: + for callback in self._callbacks: + try: + callback(sample, self._topic) + except Exception as e: + logger.error(f"Callback error on topic {self._topic}: {e}", exc_info=True) + + +class DDS(DDSService, PubSub[Topic, Any]): + def __init__(self, qos: Qos | None = None, **kwargs: Any) -> None: + super().__init__(**kwargs) + self._qos = qos + self._writers: dict[Topic, DDSDataWriter[Any]] = {} + self._writer_lock = threading.Lock() + self._readers: dict[Topic, DDSDataReader[Any]] = {} + self._reader_lock = threading.Lock() + self._listeners: dict[Topic, _DDSMessageListener] = {} + + @property + def qos(self) -> Qos | None: + """Get the QoS settings.""" + return self._qos + + def _get_writer(self, topic: Topic) -> DDSDataWriter[Any]: + """Get or create a DataWriter for the given topic.""" + with self._writer_lock: + if topic not in self._writers: + dds_topic = DDSTopic(self.participant, topic.name, topic.data_type) + self._writers[topic] = DDSDataWriter(self.participant, dds_topic, qos=self._qos) + return self._writers[topic] + + def publish(self, topic: Topic, message: Any) -> None: + """Publish a message to a DDS topic.""" + writer = self._get_writer(topic) + try: + writer.write(message) + except Exception as e: + logger.error(f"Error publishing to topic {topic}: {e}", exc_info=True) + + def _get_listener(self, topic: Topic) -> _DDSMessageListener: + """Get or create a listener and reader for the given topic.""" + with self._reader_lock: + if topic not in self._readers: + dds_topic = DDSTopic(self.participant, topic.name, topic.data_type) + listener = _DDSMessageListener(topic) + self._readers[topic] = DDSDataReader( + self.participant, dds_topic, qos=self._qos, listener=listener + ) + self._listeners[topic] = listener + return self._listeners[topic] + + def subscribe(self, topic: Topic, callback: MessageCallback) -> Callable[[], None]: + """Subscribe to a DDS topic with a callback.""" + listener = self._get_listener(topic) + listener.add_callback(callback) + return lambda: self._unsubscribe_callback(topic, callback) + + def _unsubscribe_callback(self, topic: Topic, callback: MessageCallback) -> None: + """Unsubscribe a callback from a topic.""" + with self._reader_lock: + listener = self._listeners.get(topic) + if listener: + listener.remove_callback(callback) + + def stop(self) -> None: + """Stop the DDS service and clean up resources.""" + with self._reader_lock: + self._readers.clear() + self._listeners.clear() + with self._writer_lock: + self._writers.clear() + super().stop() + + +__all__ = [ + "DDS", + "HIGH_THROUGHPUT_QOS", + "RELIABLE_QOS", + "MessageCallback", + "Policy", + "Qos", + "Topic", +] diff --git a/dimos/protocol/service/ddsservice.py b/dimos/protocol/service/ddsservice.py new file mode 100644 index 0000000000..52c008c5d6 --- /dev/null +++ b/dimos/protocol/service/ddsservice.py @@ -0,0 +1,79 @@ +# Copyright 2025-2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from __future__ import annotations + +from dataclasses import dataclass +import threading +from typing import TYPE_CHECKING, Any + +from cyclonedds.domain import DomainParticipant + +from dimos.protocol.service.spec import Service +from dimos.utils.logging_config import setup_logger + +if TYPE_CHECKING: + from cyclonedds.qos import Qos + +logger = setup_logger() + +_participant: DomainParticipant | None = None +_participant_lock = threading.Lock() + + +@dataclass +class DDSConfig: + """Configuration for DDS service.""" + + domain_id: int = 0 + qos: Qos | None = None + + +class DDSService(Service[DDSConfig]): + default_config = DDSConfig + + def __init__(self, **kwargs: Any) -> None: + super().__init__(**kwargs) + + def start(self) -> None: + """Start the DDS service.""" + global _participant + with _participant_lock: + if _participant is None: + _participant = DomainParticipant(self.config.domain_id) + logger.info(f"DDS service started with Cyclone DDS domain {self.config.domain_id}") + super().start() + + def stop(self) -> None: + """Stop the DDS service.""" + global _participant + with _participant_lock: + if _participant is not None: + _participant.close() + _participant = None + logger.info("DDS service stopped") + super().stop() + + @property + def participant(self) -> DomainParticipant: + """Get the DomainParticipant instance.""" + if _participant is None: + raise RuntimeError("DomainParticipant not initialized") + return _participant + + +__all__ = [ + "DDSConfig", + "DDSService", +] diff --git a/dimos/protocol/service/system_configurator.py b/dimos/protocol/service/system_configurator.py index 44b8c45276..ecc43cfa70 100644 --- a/dimos/protocol/service/system_configurator.py +++ b/dimos/protocol/service/system_configurator.py @@ -282,11 +282,13 @@ def fix(self) -> None: # ------------------------------ specific checks: buffers ------------------------------ IDEAL_RMEM_SIZE = 67_108_864 # 64MB +IDEAL_WMEM_SIZE = 67_108_864 # 64MB class BufferConfiguratorLinux(SystemConfigurator): critical = False + TARGET_WMEM_SIZE = IDEAL_WMEM_SIZE TARGET_RMEM_SIZE = IDEAL_RMEM_SIZE def __init__(self) -> None: @@ -297,6 +299,8 @@ def check(self) -> bool: for key, target in [ ("net.core.rmem_max", self.TARGET_RMEM_SIZE), ("net.core.rmem_default", self.TARGET_RMEM_SIZE), + ("net.core.wmem_max", self.TARGET_WMEM_SIZE), + ("net.core.wmem_default", self.TARGET_WMEM_SIZE), ]: current = _read_sysctl_int(key) if current is None or current < target: diff --git a/docs/concepts/transports.md b/docs/concepts/transports.md index faac9a2ec5..46fbae7ca2 100644 --- a/docs/concepts/transports.md +++ b/docs/concepts/transports.md @@ -11,9 +11,9 @@ Each edge in the graph is a **transported stream** (potentially different protoc ![go2_nav](assets/go2_nav.svg) -## What the transport layer guarantees (and what it doesn’t) +## What the transport layer guarantees (and what it doesn't) -Modules **don’t** know or care *how* data moves. They just: +Modules **don't** know or care *how* data moves. They just: * emit messages (broadcast) * subscribe to messages (receive) @@ -73,7 +73,7 @@ text "pub/sub API" at P.s + (0, -0.2in) ![output](assets/abstraction_layers.svg) -We’ll go through these layers top-down. +We'll go through these layers top-down. --- @@ -234,7 +234,7 @@ Topic/message types are flexible: bytes, JSON, or our ROS-compatible [LCM](/docs ### LCM (UDP multicast) -LCM is UDP multicast. It’s very fast on a robot LAN, but it’s **best-effort** (packets can drop). +LCM is UDP multicast. It's very fast on a robot LAN, but it's **best-effort** (packets can drop). For local emission it autoconfigures system in a way in which it's more robust and faster then other more common protocols like ROS, DDS ```python @@ -288,6 +288,40 @@ shm.stop() Received: [{'data': [1, 2, 3]}] ``` +### DDS Transport + +For network communication, DDS uses the Data Distribution Service (DDS) protocol: + +```python session=dds_demo ansi=false +from dataclasses import dataclass +from cyclonedds.idl import IdlStruct +from dimos.protocol.pubsub.ddspubsub import DDS, Topic + +@dataclass +class SensorReading(IdlStruct): + value: float + +dds = DDS() +dds.start() + +received = [] +sensor_topic = Topic(name="sensors/temperature", data_type=SensorReading) + +dds.subscribe(sensor_topic, lambda msg, t: received.append(msg)) +dds.publish(sensor_topic, SensorReading(value=22.5)) + +import time +time.sleep(0.1) + +print(f"Received: {received}") +dds.stop() +``` + + +``` +Received: [SensorReading(value=22.5)] +``` + --- ## A minimal transport: `Memory` diff --git a/flake.nix b/flake.nix index 50738effc0..ed98bfb25f 100644 --- a/flake.nix +++ b/flake.nix @@ -165,6 +165,7 @@ } ); } + { vals.pkg=pkgs.cyclonedds; flags.ldLibraryGroup=true; flags.packageConfGroup=true; } ]; # ------------------------------------------------------------ @@ -211,6 +212,8 @@ export GI_TYPELIB_PATH="${giTypelibPackagesString}:$GI_TYPELIB_PATH" export PKG_CONFIG_PATH=${lib.escapeShellArg packageConfPackagesString} export PYTHONPATH="$PYTHONPATH:"${lib.escapeShellArg manualPythonPackages} + export CYCLONEDDS_HOME="${pkgs.cyclonedds}" + export CMAKE_PREFIX_PATH="${pkgs.cyclonedds}:$CMAKE_PREFIX_PATH" # CC, CFLAGS, and LDFLAGS are bascially all for `pip install pyaudio` export CFLAGS="$(pkg-config --cflags portaudio-2.0) $CFLAGS" export LDFLAGS="-L$(pkg-config --variable=libdir portaudio-2.0) $LDFLAGS" diff --git a/pyproject.toml b/pyproject.toml index eeb401ecde..82b2491cb8 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -31,6 +31,7 @@ readme = "README.md" dependencies = [ # Transport Protocols "dimos-lcm", + "cyclonedds>=0.10.5", "PyTurboJPEG==1.8.2", # Core @@ -61,7 +62,6 @@ dependencies = [ "terminaltexteffects==0.12.2", "typer>=0.19.2,<1", "plotext==5.3.2", - # Used for calculating the occupancy map. "numba>=0.60.0", # First version supporting Python 3.12 "llvmlite>=0.42.0", # Required by numba 0.60+ diff --git a/uv.lock b/uv.lock index f11421e7ce..4d3468c9cb 100644 --- a/uv.lock +++ b/uv.lock @@ -1261,6 +1261,22 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e7/05/c19819d5e3d95294a6f5947fb9b9629efb316b96de511b418c53d245aae6/cycler-0.12.1-py3-none-any.whl", hash = "sha256:85cef7cff222d8644161529808465972e51340599459b8ac3ccbac5a854e0d30", size = 8321, upload-time = "2023-10-07T05:32:16.783Z" }, ] +[[package]] +name = "cyclonedds" +version = "0.10.5" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "rich-click" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/91/cf/28eb9c823dfc245c540f5286d71b44aeee2a51021fc85b25bb9562be78cc/cyclonedds-0.10.5.tar.gz", hash = "sha256:63fc4d6fdb2fd35181c40f4e90757149f2def5f570ef19fb71edc4f568755f8a", size = 156919, upload-time = "2024-06-05T18:50:42.999Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/cb/c3/69ba063a51c06ba24fa4fd463157d4cc2bc54ab1a2ab8ebdf88e8f3dde25/cyclonedds-0.10.5-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:03644e406d0c1cac45887b378d35054a0033c48f2e29d9aab3bfc1ee6c4b9aa6", size = 864591, upload-time = "2024-06-05T18:50:46.563Z" }, + { url = "https://files.pythonhosted.org/packages/cf/98/08508aff65c87bcef473e23a51506a100fb35bf70450c40eb227a576a018/cyclonedds-0.10.5-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:4a0d9fa8747827dc9bd678d73ed6f12b0ab9853b2cb7ebadbf3d8d89625f0e34", size = 799626, upload-time = "2024-06-05T18:50:48.17Z" }, + { url = "https://files.pythonhosted.org/packages/99/0d/02da52ffd27b92b85b64997cc449106479456648da17aa44a09124e8ebe5/cyclonedds-0.10.5-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:861d2ffd9513126d6a62ad9f842e85122518a7db1fb0a11d6e4fa86e3cacf61c", size = 6631487, upload-time = "2024-06-05T18:50:50.747Z" }, + { url = "https://files.pythonhosted.org/packages/e4/2b/d8fff5008c2c62882c2ffc185bdb0d4d1c9caf7bc5aaaef77bd9739bdc12/cyclonedds-0.10.5-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:8276b2bc347540e3ca892adf976421dbce4c6d2672934a32409db121a1431b86", size = 6653044, upload-time = "2024-06-05T18:50:52.786Z" }, + { url = "https://files.pythonhosted.org/packages/07/ab/acaa119f552019bdb2b06478553cf712967672f5970be80ecc9b4ca805f4/cyclonedds-0.10.5-cp310-cp310-win_amd64.whl", hash = "sha256:103a681e9490229f12c151a125e00c4db8fdb344c8e12e35ee515cd9d5d1ecd7", size = 1200672, upload-time = "2024-06-05T18:50:54.303Z" }, +] + [[package]] name = "cython" version = "3.2.4" @@ -1396,6 +1412,7 @@ dependencies = [ { name = "annotation-protocol" }, { name = "asyncio" }, { name = "colorlog" }, + { name = "cyclonedds" }, { name = "dask", extra = ["complete"] }, { name = "dimos-lcm" }, { name = "llvmlite" }, @@ -1639,6 +1656,7 @@ requires-dist = [ { name = "ctransformers", marker = "extra == 'cpu'", specifier = "==0.2.27" }, { name = "ctransformers", extras = ["cuda"], marker = "extra == 'cuda'", specifier = "==0.2.27" }, { name = "cupy-cuda12x", marker = "extra == 'cuda'", specifier = "==13.6.0" }, + { name = "cyclonedds", specifier = ">=0.10.5" }, { name = "dask", extras = ["complete"], specifier = "==2025.5.1" }, { name = "dimos", extras = ["agents", "web", "perception", "visualization", "sim"], marker = "extra == 'base'" }, { name = "dimos", extras = ["base"], marker = "extra == 'unitree'" }, @@ -7626,6 +7644,21 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/25/7a/b0178788f8dc6cafce37a212c99565fa1fe7872c70c6c9c1e1a372d9d88f/rich-14.2.0-py3-none-any.whl", hash = "sha256:76bc51fe2e57d2b1be1f96c524b890b816e334ab4c1e45888799bfaab0021edd", size = 243393, upload-time = "2025-10-09T14:16:51.245Z" }, ] +[[package]] +name = "rich-click" +version = "1.9.5" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "click" }, + { name = "colorama", marker = "sys_platform == 'win32'" }, + { name = "rich" }, + { name = "typing-extensions", marker = "python_full_version < '3.11'" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/6b/d1/b60ca6a8745e76800b50c7ee246fd73f08a3be5d8e0b551fc93c19fa1203/rich_click-1.9.5.tar.gz", hash = "sha256:48120531493f1533828da80e13e839d471979ec8d7d0ca7b35f86a1379cc74b6", size = 73927, upload-time = "2025-12-21T14:49:44.167Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/25/0a/d865895e1e5d88a60baee0fc3703eb111c502ee10c8c107516bc7623abf8/rich_click-1.9.5-py3-none-any.whl", hash = "sha256:9b195721a773b1acf0e16ff9ec68cef1e7d237e53471e6e3f7ade462f86c403a", size = 70580, upload-time = "2025-12-21T14:49:42.905Z" }, +] + [[package]] name = "rpds-py" version = "0.30.0"