diff --git a/.github/workflows/code-cleanup.yml b/.github/workflows/code-cleanup.yml index 48f6ea281e..7177b3f9d1 100644 --- a/.github/workflows/code-cleanup.yml +++ b/.github/workflows/code-cleanup.yml @@ -1,8 +1,7 @@ name: code-cleanup on: push: - paths-ignore: - - '**.md' + pull_request: permissions: contents: write diff --git a/dimos/hardware/sensors/camera/webcam.py b/dimos/hardware/sensors/camera/webcam.py index 54989ca568..51199624fe 100644 --- a/dimos/hardware/sensors/camera/webcam.py +++ b/dimos/hardware/sensors/camera/webcam.py @@ -19,12 +19,11 @@ from typing import Literal import cv2 -from dimos_lcm.sensor_msgs import CameraInfo from reactivex import create from reactivex.observable import Observable from dimos.hardware.sensors.camera.spec import CameraConfig, CameraHardware -from dimos.msgs.sensor_msgs import Image +from dimos.msgs.sensor_msgs import CameraInfo, Image from dimos.msgs.sensor_msgs.Image import ImageFormat from dimos.utils.reactive import backpressure diff --git a/docs/concepts/assets/abstraction_layers.svg b/docs/concepts/assets/abstraction_layers.svg new file mode 100644 index 0000000000..0903cfbf27 --- /dev/null +++ b/docs/concepts/assets/abstraction_layers.svg @@ -0,0 +1,20 @@ + + +Blueprints + + + +Modules + + + +Transports + + + +PubSub +robot configs +camera, nav +LCM, SHM, ROS +pub/sub API + diff --git a/docs/concepts/assets/lcmspy.png b/docs/concepts/assets/lcmspy.png new file mode 100644 index 0000000000..6e68fde03a --- /dev/null +++ b/docs/concepts/assets/lcmspy.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:91da9ef9f7797cce332da448739e28591f7ecfc0fd674e8b4be973cf28331438 +size 7118 diff --git a/docs/concepts/assets/pubsub_benchmark.png b/docs/concepts/assets/pubsub_benchmark.png new file mode 100644 index 0000000000..759a8b3977 --- /dev/null +++ b/docs/concepts/assets/pubsub_benchmark.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:728484a4358df18ced7b5763a88a962701c2b02b5d319eb9a8b28c6c72d009fe +size 23946 diff --git a/docs/concepts/transports.md b/docs/concepts/transports.md index 6c9e5fca99..7ddc29714f 100644 --- a/docs/concepts/transports.md +++ b/docs/concepts/transports.md @@ -1,119 +1,243 @@ +# Transports -# Dimos Transports +Transports connect **module streams** across **process boundaries** and/or **networks**. -Transports enable communication between [modules](modules.md) across process boundaries and networks. When modules run in different processes or on different machines, they need a transport layer to exchange messages. +* **Module**: a running component (e.g., camera, mapping, nav). +* **Stream**: a unidirectional flow of messages owned by a module (one broadcaster → many receivers). +* **Topic**: the name/identifier used by a transport or pubsub backend. +* **Message**: payload carried on a stream (often `dimos.msgs.*`, but can be bytes / images / pointclouds / etc.). -While the interface is called "PubSub", transports aren't limited to traditional pub-sub services. A topic can be anything that identifies a communication channel: an IP address and port, a shared memory segment name, a file path, or a Redis channel. The abstraction is flexible enough to support any communication pattern that can publish and subscribe to named channels. +Each edge in the graph is a **transported stream** (potentially different protocols). Each node is a **module**: -## The PubSub Interface +![go2_nav](assets/go2_nav.svg) -At the core of all transports is the `PubSub` abstract class. Any transport implementation must provide two methods: +## What the transport layer guarantees (and what it doesn’t) -```python session=pubsub_demo ansi=false -from dimos.protocol.pubsub.spec import PubSub +Modules **don’t** know or care *how* data moves. They just: -# The interface every transport must implement: -import inspect -print(inspect.getsource(PubSub.publish)) -print(inspect.getsource(PubSub.subscribe)) +* emit messages (broadcast) +* subscribe to messages (receive) + +A transport is responsible for the mechanics of delivery (IPC, sockets, Redis, ROS 2, etc.). + +**Important:** delivery semantics depend on the backend: + +* Some are **best-effort** (e.g., UDP multicast / LCM): loss can happen. +* Some can be **reliable** (e.g., TCP-backed, Redis, some DDS configs) but may add latency/backpressure. + +So: treat the API as uniform, but pick a backend whose semantics match the task. + +--- + +## Benchmarks + +Quick view on performance of our pubsub backends: + +```sh skip +python -m pytest -svm tool -k "not bytes" dimos/protocol/pubsub/benchmark/test_benchmark.py ``` +![Benchmark results](assets/pubsub_benchmark.png) + +--- + +## Abstraction layers + +
Pikchr + +```pikchr output=assets/abstraction_layers.svg fold +color = white +fill = none +linewid = 0.5in +boxwid = 1.0in +boxht = 0.4in + +# Boxes with labels +B: box "Blueprints" rad 10px +arrow +M: box "Modules" rad 5px +arrow +T: box "Transports" rad 5px +arrow +P: box "PubSub" rad 5px + +# Descriptions below +text "robot configs" at B.s + (0.1, -0.2in) +text "camera, nav" at M.s + (0, -0.2in) +text "LCM, SHM, ROS" at T.s + (0, -0.2in) +text "pub/sub API" at P.s + (0, -0.2in) ``` -@abstractmethod -def publish(self, topic: TopicT, message: MsgT) -> None: - """Publish a message to a topic.""" - ... -@abstractmethod -def subscribe( - self, topic: TopicT, callback: Callable[[MsgT, TopicT], None] -) -> Callable[[], None]: - """Subscribe to a topic with a callback. returns unsubscribe function""" - ... + +
+ + +![output](assets/abstraction_layers.svg) + +We’ll go through these layers top-down. + +--- + +## Using transports with blueprints + +See [Blueprints](blueprints.md) for the blueprint API. + +From [`unitree_go2_blueprints.py`](/dimos/robot/unitree_webrtc/unitree_go2_blueprints.py). + +Example: rebind a few streams from the default `LCMTransport` to `ROSTransport` (defined at [`transport.py`](/dimos/core/transport.py#L226)) so you can visualize in **rviz2**. + +```python skip +nav = autoconnect( + basic, + voxel_mapper(voxel_size=0.1), + cost_mapper(), + replanning_a_star_planner(), + wavefront_frontier_explorer(), +).global_config(n_dask_workers=6, robot_model="unitree_go2") + +ros = nav.transports( + { + ("lidar", PointCloud2): ROSTransport("lidar", PointCloud2), + ("global_map", PointCloud2): ROSTransport("global_map", PointCloud2), + ("odom", PoseStamped): ROSTransport("odom", PoseStamped), + ("color_image", Image): ROSTransport("color_image", Image), + } +) ``` -Key points: -- `publish(topic, message)` - Send a message to all subscribers on a topic -- `subscribe(topic, callback)` - Register a callback, returns an unsubscribe function +--- -## Implementing a Simple Transport +## Using transports with modules -The simplest transport is `Memory`, which works within a single process: +Each **stream** on a module can use a different transport. Set `.transport` on the stream **before starting** modules. -```python session=memory_demo ansi=false -from dimos.protocol.pubsub.memory import Memory +```python ansi=false +import time -# Create a memory transport -bus = Memory() +from dimos.core import In, Module, start +from dimos.core.transport import LCMTransport +from dimos.hardware.sensors.camera.module import CameraModule +from dimos.msgs.sensor_msgs import Image -# Track received messages -received = [] -# Subscribe to a topic -unsubscribe = bus.subscribe("sensor/data", lambda msg, topic: received.append(msg)) +class ImageListener(Module): + image: In[Image] -# Publish messages -bus.publish("sensor/data", {"temperature": 22.5}) -bus.publish("sensor/data", {"temperature": 23.0}) + def start(self): + super().start() + self.image.subscribe(lambda img: print(f"Received: {img.shape}")) -print(f"Received {len(received)} messages:") -for msg in received: - print(f" {msg}") -# Unsubscribe when done -unsubscribe() +if __name__ == "__main__": + # Start local cluster and deploy modules to separate processes + dimos = start(2) + + camera = dimos.deploy(CameraModule, frequency=2.0) + listener = dimos.deploy(ImageListener) + + # Choose a transport for the stream (example: LCM typed channel) + camera.color_image.transport = LCMTransport("/camera/rgb", Image) + + # Connect listener input to camera output + listener.image.connect(camera.color_image) + + camera.start() + listener.start() + + time.sleep(2) + dimos.stop() ``` ``` -Received 2 messages: - {'temperature': 22.5} - {'temperature': 23.0} +Initialized dimos local cluster with 2 workers, memory limit: auto +2026-01-24T13:17:50.190559Z [info ] Deploying module. [dimos/core/__init__.py] module=CameraModule +2026-01-24T13:17:50.218466Z [info ] Deployed module. [dimos/core/__init__.py] module=CameraModule worker_id=1 +2026-01-24T13:17:50.229474Z [info ] Deploying module. [dimos/core/__init__.py] module=ImageListener +2026-01-24T13:17:50.250199Z [info ] Deployed module. [dimos/core/__init__.py] module=ImageListener worker_id=0 +Received: (480, 640, 3) +Received: (480, 640, 3) +Received: (480, 640, 3) ``` -The full implementation is minimal. See [`memory.py`](/dimos/protocol/pubsub/memory.py) for the complete source. +See [Modules](modules.md) for more on module architecture. -## Available Transports +--- -Dimos includes several transport implementations: +## Inspecting LCM traffic (CLI) -| Transport | Use Case | Process Boundary | Network | -|-----------|----------|------------------|---------| -| `Memory` | Testing, single process | No | No | -| `SharedMemory` | Multi-process on same machine | Yes | No | -| `LCM` | Network communication (UDP multicast) | Yes | Yes | -| `Redis` | Network communication via Redis server | Yes | Yes | +`lcmspy` shows topic frequency/bandwidth stats: -### SharedMemory Transport +![lcmspy](assets/lcmspy.png) -For inter-process communication on the same machine, `SharedMemory` provides high-performance message passing: +`dimos topic echo /topic` listens on typed channels like `/topic#pkg.Msg` and decodes automatically: -```python session=shm_demo ansi=false -from dimos.protocol.pubsub.shmpubsub import PickleSharedMemory +```sh skip +Listening on /camera/rgb (inferring from typed LCM channels like '/camera/rgb#pkg.Msg')... (Ctrl+C to stop) +Image(shape=(480, 640, 3), format=RGB, dtype=uint8, dev=cpu, ts=2026-01-24 20:28:59) +``` -shm = PickleSharedMemory(prefer="cpu") -shm.start() +--- -received = [] -shm.subscribe("test/topic", lambda msg, topic: received.append(msg)) -shm.publish("test/topic", {"data": [1, 2, 3]}) +## Implementing a transport -import time -time.sleep(0.1) # Allow message to propagate +At the stream layer, a transport is implemented by subclassing `Transport` (see [`core/stream.py`](/dimos/core/stream.py#L83)) and implementing: -print(f"Received: {received}") -shm.stop() +* `broadcast(...)` +* `subscribe(...)` + +Your `Transport.__init__` args can be anything meaningful for your backend: + +* `(ip, port)` +* a shared-memory segment name +* a filesystem path +* a Redis channel + +Encoding is an implementation detail, but we encourage using LCM-compatible message types when possible. + +### Encoding helpers + +Many of our message types provide `lcm_encode` / `lcm_decode` for compact, language-agnostic binary encoding (often faster than pickle). For details, see [LCM](/docs/concepts/lcm.md). + +--- + +## PubSub transports + +Even though transport can be anything (TCP connection, unix socket) for now all our transport backends implement the `PubSub` interface. + +* `publish(topic, message)` +* `subscribe(topic, callback) -> unsubscribe` + +```python +from dimos.protocol.pubsub.spec import PubSub +import inspect + +print(inspect.getsource(PubSub.publish)) +print(inspect.getsource(PubSub.subscribe)) ``` -``` -Received: [{'data': [1, 2, 3]}] +```python + @abstractmethod + def publish(self, topic: TopicT, message: MsgT) -> None: + """Publish a message to a topic.""" + ... + + @abstractmethod + def subscribe( + self, topic: TopicT, callback: Callable[[MsgT, TopicT], None] + ) -> Callable[[], None]: + """Subscribe to a topic with a callback. returns unsubscribe function""" + ... ``` -### LCM Transport +Topic/message types are flexible: bytes, JSON, or our ROS-compatible [LCM](/docs/concepts/lcm.md) types. We also have pickle-based transports for arbitrary Python objects. -For network communication, LCM uses UDP multicast and supports typed messages: +### LCM (UDP multicast) -```python session=lcm_demo ansi=false +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 from dimos.protocol.pubsub.lcmpubsub import LCM, Topic from dimos.msgs.geometry_msgs import Vector3 @@ -121,7 +245,7 @@ lcm = LCM(autoconf=True) lcm.start() received = [] -topic = Topic(topic="/robot/velocity", lcm_type=Vector3) +topic = Topic("/robot/velocity", Vector3) lcm.subscribe(topic, lambda msg, t: received.append(msg)) lcm.publish(topic, Vector3(1.0, 0.0, 0.5)) @@ -138,243 +262,140 @@ lcm.stop() Received velocity: x=1.0, y=0.0, z=0.5 ``` -### Inspecting LCM traffic (CLI) - -- `dimos lcmspy` shows topic frequency/bandwidth stats. -- `dimos topic echo /topic` listens on typed channels like `/topic#pkg.Msg` and decodes automatically. -- `dimos topic echo /topic TypeName` is the explicit legacy form. +### Shared memory (IPC) -## Encoder Mixins +Shared memory is highest performance, but only works on the **same machine**. -Transports can use encoder mixins to serialize messages. The `PubSubEncoderMixin` pattern wraps publish/subscribe to encode/decode automatically: - -```python session=encoder_demo ansi=false -from dimos.protocol.pubsub.spec import PubSubEncoderMixin, PickleEncoderMixin - -# PickleEncoderMixin provides: -# - encode(msg, topic) -> bytes (uses pickle.dumps) -# - decode(bytes, topic) -> msg (uses pickle.loads) - -# Create a transport with pickle encoding by mixing in: -from dimos.protocol.pubsub.memory import Memory +```python +from dimos.protocol.pubsub.shmpubsub import PickleSharedMemory -class PickleMemory(PickleEncoderMixin, Memory): - pass +shm = PickleSharedMemory(prefer="cpu") +shm.start() -bus = PickleMemory() received = [] -bus.subscribe("data", lambda msg, t: received.append(msg)) -bus.publish("data", {"complex": [1, 2, 3], "nested": {"key": "value"}}) +shm.subscribe("test/topic", lambda msg, topic: received.append(msg)) +shm.publish("test/topic", {"data": [1, 2, 3]}) -print(f"Received: {received[0]}") +import time +time.sleep(0.1) + +print(f"Received: {received}") +shm.stop() ``` ``` -Received: {'complex': [1, 2, 3], 'nested': {'key': 'value'}} +Received: [{'data': [1, 2, 3]}] ``` -## Using Transports with Modules +--- -Modules use the `Transport` wrapper class which adapts `PubSub` to the stream interface. You can set a transport on any module stream: +## A minimal transport: `Memory` -```python session=module_transport ansi=false -from dimos.core.transport import pLCMTransport, pSHMTransport +The simplest toy backend is `Memory` (single process). Start from there when implementing a new pubsub backend. -# Transport wrappers for module streams: -# - pLCMTransport: Pickle-encoded LCM -# - LCMTransport: Native LCM encoding -# - pSHMTransport: Pickle-encoded SharedMemory -# - SHMTransport: Native SharedMemory -# - JpegShmTransport: JPEG-compressed images via SharedMemory -# - JpegLcmTransport: JPEG-compressed images via LCM - -# Example: Set a transport on a module output -# camera.set_transport("color_image", pSHMTransport("camera/color")) -print("Available transport wrappers in dimos.core.transport:") -from dimos.core import transport -print([name for name in dir(transport) if "Transport" in name]) -``` - - -``` -Available transport wrappers in dimos.core.transport: -['JpegLcmTransport', 'JpegShmTransport', 'LCMTransport', 'PubSubTransport', 'SHMTransport', 'ZenohTransport', 'pLCMTransport', 'pSHMTransport'] -``` +```python +from dimos.protocol.pubsub.memory import Memory -## Testing Custom Transports +bus = Memory() +received = [] -The test suite in [`pubsub/test_spec.py`](/dimos/protocol/pubsub/test_spec.py) uses pytest parametrization to run the same tests against all transport implementations. To add your custom transport to the test grid: +unsubscribe = bus.subscribe("sensor/data", lambda msg, topic: received.append(msg)) -```python session=test_grid ansi=false -# The test grid pattern from test_spec.py: -test_pattern = """ -from contextlib import contextmanager +bus.publish("sensor/data", {"temperature": 22.5}) +bus.publish("sensor/data", {"temperature": 23.0}) -@contextmanager -def my_transport_context(): - transport = MyCustomTransport() - transport.start() - yield transport - transport.stop() +print(f"Received {len(received)} messages:") +for msg in received: + print(f" {msg}") -# Add to testdata list: -testdata.append( - (my_transport_context, "my_topic", ["value1", "value2", "value3"]) -) -""" -print(test_pattern) +unsubscribe() ``` ``` - -from contextlib import contextmanager - -@contextmanager -def my_transport_context(): - transport = MyCustomTransport() - transport.start() - yield transport - transport.stop() - -# Add to testdata list: -testdata.append( - (my_transport_context, "my_topic", ["value1", "value2", "value3"]) -) - +Received 2 messages: + {'temperature': 22.5} + {'temperature': 23.0} ``` -The test suite validates: -- Basic publish/subscribe -- Multiple subscribers receiving the same message -- Unsubscribe functionality -- Multiple messages in order -- Async iteration -- High-volume message handling (10,000 messages) - -Run the tests with: -```bash -pytest dimos/protocol/pubsub/test_spec.py -v -``` +See [`memory.py`](/dimos/protocol/pubsub/memory.py) for the complete source. -## Creating a Custom Transport +--- -To implement a new transport: +## Encode/decode mixins -1. **Subclass `PubSub`** and implement `publish()` and `subscribe()` -2. **Add encoding** if needed via `PubSubEncoderMixin` -3. **Create a `Transport` wrapper** by subclassing `PubSubTransport` -4. **Add to the test grid** in `test_spec.py` +Transports often need to serialize messages before sending and deserialize after receiving. -Here's a minimal template: +`PubSubEncoderMixin` at [`pubsub/spec.py`](/dimos/protocol/pubsub/spec.py#L95) provides a clean way to add encoding/decoding to any pubsub implementation. -```python session=custom_transport ansi=false -template = ''' -from dimos.protocol.pubsub.spec import PubSub, PickleEncoderMixin -from dimos.core.transport import PubSubTransport +### Available mixins -class MyPubSub(PubSub[str, bytes]): - """Custom pub/sub implementation.""" +| Mixin | Encoding | Use case | +|----------------------|-----------------|------------------------------------| +| `PickleEncoderMixin` | Python pickle | Any Python object, Python-only | +| `LCMEncoderMixin` | LCM binary | Cross-language (C/C++/Python/Go/…) | +| `JpegEncoderMixin` | JPEG compressed | Image data, reduces bandwidth | - def __init__(self): - self._subscribers = {} +`LCMEncoderMixin` is especially useful: you can use LCM message definitions with *any* transport (not just UDP multicast). See [LCM](/docs/concepts/lcm.md) for details. - def start(self): - # Initialize connection/resources - pass +### Creating a custom mixin - def stop(self): - # Cleanup - pass +```python session=jsonencoder no-result +from dimos.protocol.pubsub.spec import PubSubEncoderMixin +import json - def publish(self, topic: str, message: bytes) -> None: - # Send message to all subscribers on topic - for cb in self._subscribers.get(topic, []): - cb(message, topic) +class JsonEncoderMixin(PubSubEncoderMixin[str, dict, bytes]): + def encode(self, msg: dict, topic: str) -> bytes: + return json.dumps(msg).encode("utf-8") - def subscribe(self, topic, callback): - # Register callback, return unsubscribe function - if topic not in self._subscribers: - self._subscribers[topic] = [] - self._subscribers[topic].append(callback) + def decode(self, msg: bytes, topic: str) -> dict: + return json.loads(msg.decode("utf-8")) +``` - def unsubscribe(): - self._subscribers[topic].remove(callback) - return unsubscribe +Combine with a pubsub implementation via multiple inheritance: +```python session=jsonencoder no-result +from dimos.protocol.pubsub.memory import Memory -# With pickle encoding -class MyPicklePubSub(PickleEncoderMixin, MyPubSub): +class MyJsonPubSub(JsonEncoderMixin, Memory): pass - - -# Transport wrapper for use with modules -class MyTransport(PubSubTransport): - def __init__(self, topic: str): - super().__init__(topic) - self.pubsub = MyPicklePubSub() - - def broadcast(self, _, msg): - self.pubsub.publish(self.topic, msg) - - def subscribe(self, callback, selfstream=None): - return self.pubsub.subscribe(self.topic, lambda msg, t: callback(msg)) -''' -print(template) -``` - - ``` -from dimos.protocol.pubsub.spec import PubSub, PickleEncoderMixin -from dimos.core.transport import PubSubTransport +Swap serialization by changing the mixin: -class MyPubSub(PubSub[str, bytes]): - """Custom pub/sub implementation.""" +```python session=jsonencoder no-result +from dimos.protocol.pubsub.spec import PickleEncoderMixin - def __init__(self): - self._subscribers = {} - - def start(self): - # Initialize connection/resources - pass - - def stop(self): - # Cleanup - pass +class MyPicklePubSub(PickleEncoderMixin, Memory): + pass +``` - def publish(self, topic: str, message: bytes) -> None: - # Send message to all subscribers on topic - for cb in self._subscribers.get(topic, []): - cb(message, topic) +--- - def subscribe(self, topic, callback): - # Register callback, return unsubscribe function - if topic not in self._subscribers: - self._subscribers[topic] = [] - self._subscribers[topic].append(callback) +## Testing and benchmarks - def unsubscribe(): - self._subscribers[topic].remove(callback) - return unsubscribe +### Spec tests +See [`pubsub/test_spec.py`](/dimos/protocol/pubsub/test_spec.py) for the grid tests your new backend should pass. -# With pickle encoding -class MyPicklePubSub(PickleEncoderMixin, MyPubSub): - pass +### Benchmarks +Add your backend to benchmarks to compare in context: -# Transport wrapper for use with modules -class MyTransport(PubSubTransport): - def __init__(self, topic: str): - super().__init__(topic) - self.pubsub = MyPicklePubSub() +```sh skip +python -m pytest -svm tool -k "not bytes" dimos/protocol/pubsub/benchmark/test_benchmark.py +``` - def broadcast(self, _, msg): - self.pubsub.publish(self.topic, msg) +--- - def subscribe(self, callback, selfstream=None): - return self.pubsub.subscribe(self.topic, lambda msg, t: callback(msg)) +# Available transports -``` +| Transport | Use case | Cross-process | Network | Notes | +|----------------|-------------------------------------|---------------|---------|--------------------------------------| +| `Memory` | Testing only, single process | No | No | Minimal reference impl | +| `SharedMemory` | Multi-process on same machine | Yes | No | Highest throughput (IPC) | +| `LCM` | Robot LAN broadcast (UDP multicast) | Yes | Yes | Best-effort; can drop packets on LAN | +| `Redis` | Network pubsub via Redis server | Yes | Yes | Central broker; adds hop | +| `ROS` | ROS 2 topic communication | Yes | Yes | Integrates with RViz/ROS tools | +| `DDS` | Cyclone DDS without ROS (WIP) | Yes | Yes | WIP | diff --git a/docs/assets/get_data_flow.svg b/docs/development/assets/get_data_flow.svg similarity index 100% rename from docs/assets/get_data_flow.svg rename to docs/development/assets/get_data_flow.svg diff --git a/pyproject.toml b/pyproject.toml index 2dcf5d548e..b91802eb2c 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -78,6 +78,7 @@ skillspy = "dimos.utils.cli.skillspy.skillspy:main" agentspy = "dimos.utils.cli.agentspy.agentspy:main" humancli = "dimos.utils.cli.human.humanclianim:main" dimos = "dimos.robot.cli.dimos:main" +doclinks = "dimos.utils.docs.doclinks:main" [project.optional-dependencies] misc = [