From 508cef4ef5ada7c804d5b537a5f900decb5d62f5 Mon Sep 17 00:00:00 2001 From: Paul Nechifor Date: Tue, 6 Jan 2026 05:28:33 +0200 Subject: [PATCH 1/4] fix skills --- .../unitree_webrtc/unitree_skill_container.py | 26 +++++-------------- 1 file changed, 7 insertions(+), 19 deletions(-) diff --git a/dimos/robot/unitree_webrtc/unitree_skill_container.py b/dimos/robot/unitree_webrtc/unitree_skill_container.py index 5c52128a32..1d2557da4d 100644 --- a/dimos/robot/unitree_webrtc/unitree_skill_container.py +++ b/dimos/robot/unitree_webrtc/unitree_skill_container.py @@ -18,7 +18,6 @@ import difflib import math import time -from typing import TYPE_CHECKING from unitree_webrtc_connect.constants import RTC_TOPIC @@ -31,9 +30,6 @@ from dimos.robot.unitree_webrtc.unitree_skills import UNITREE_WEBRTC_CONTROLS from dimos.utils.logging_config import setup_logger -if TYPE_CHECKING: - from dimos.core.rpc_client import RpcCall - logger = setup_logger() @@ -47,13 +43,12 @@ class UnitreeSkillContainer(SkillModule): """Container for Unitree Go2 robot skills using the new framework.""" - _publish_request: RpcCall | None = None - rpc_calls: list[str] = [ "NavigationInterface.set_goal", "NavigationInterface.get_state", "NavigationInterface.is_goal_reached", "NavigationInterface.cancel_goal", + "GO2Connection.publish_request", ] @rpc @@ -66,16 +61,6 @@ def start(self) -> None: def stop(self) -> None: super().stop() - @rpc - def set_ConnectionModule_move(self, callable: RpcCall) -> None: - self._move = callable - self._move.set_rpc(self.rpc) # type: ignore[arg-type] - - @rpc - def set_ConnectionModule_publish_request(self, callable: RpcCall) -> None: - self._publish_request = callable - self._publish_request.set_rpc(self.rpc) # type: ignore[arg-type] - @skill() def relative_move(self, forward: float = 0.0, left: float = 0.0, degrees: float = 0.0) -> str: """Move the robot relative to its current position. @@ -166,8 +151,11 @@ def current_time(self): # type: ignore[no-untyped-def] @skill() def execute_sport_command(self, command_name: str) -> str: - if self._publish_request is None: - return f"Error: Robot not connected (cannot execute {command_name})" + try: + publish_request = self.get_rpc_calls("GO2Connection.publish_request") + except Exception: + logger.error("GO2Connection not connected properly") + return "Failed to connect to GO2Connection." if command_name not in _UNITREE_COMMANDS: suggestions = difflib.get_close_matches( @@ -178,7 +166,7 @@ def execute_sport_command(self, command_name: str) -> str: id_, _ = _UNITREE_COMMANDS[command_name] try: - self._publish_request(RTC_TOPIC["SPORT_MOD"], {"api_id": id_}) + publish_request(RTC_TOPIC["SPORT_MOD"], {"api_id": id_}) return f"'{command_name}' command executed successfully." except Exception as e: logger.error(f"Failed to execute {command_name}: {e}") From a6d8952a1755820d7b4171f5a542e3153cefc53c Mon Sep 17 00:00:00 2001 From: Paul Nechifor Date: Tue, 6 Jan 2026 05:33:47 +0200 Subject: [PATCH 2/4] fix: was using wrong connection for skills --- dimos/agents/test_mock_agent.py | 6 +- .../robot/unitree_webrtc/modular/__init__.py | 1 - .../modular/connection_module.py | 340 ------------------ .../unitree_webrtc/modular/ivan_unitree.py | 98 ----- 4 files changed, 3 insertions(+), 442 deletions(-) delete mode 100644 dimos/robot/unitree_webrtc/modular/__init__.py delete mode 100644 dimos/robot/unitree_webrtc/modular/connection_module.py delete mode 100644 dimos/robot/unitree_webrtc/modular/ivan_unitree.py diff --git a/dimos/agents/test_mock_agent.py b/dimos/agents/test_mock_agent.py index 9bc3cc5098..c711e23143 100644 --- a/dimos/agents/test_mock_agent.py +++ b/dimos/agents/test_mock_agent.py @@ -26,7 +26,7 @@ from dimos.msgs.geometry_msgs import PoseStamped, Vector3 from dimos.msgs.sensor_msgs import Image from dimos.protocol.skill.test_coordinator import SkillContainerTest -from dimos.robot.unitree_webrtc.modular.connection_module import ConnectionModule +from dimos.robot.unitree.connection.go2 import GO2Connection from dimos.robot.unitree_webrtc.type.lidar import LidarMessage @@ -157,11 +157,11 @@ def test_tool_call_implicit_detections() -> None: system_prompt="You are a helpful robot assistant with camera capabilities.", ) - robot_connection = dimos.deploy(ConnectionModule, connection_type="fake") + robot_connection = dimos.deploy(GO2Connection, connection_type="fake") robot_connection.lidar.transport = LCMTransport("/lidar", LidarMessage) robot_connection.odom.transport = LCMTransport("/odom", PoseStamped) robot_connection.video.transport = LCMTransport("/image", Image) - robot_connection.movecmd.transport = LCMTransport("/cmd_vel", Vector3) + robot_connection.cmd_vel.transport = LCMTransport("/cmd_vel", Vector3) robot_connection.camera_info.transport = LCMTransport("/camera_info", CameraInfo) robot_connection.start() diff --git a/dimos/robot/unitree_webrtc/modular/__init__.py b/dimos/robot/unitree_webrtc/modular/__init__.py deleted file mode 100644 index 5c2169cc9b..0000000000 --- a/dimos/robot/unitree_webrtc/modular/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from dimos.robot.unitree_webrtc.modular.connection_module import deploy_connection diff --git a/dimos/robot/unitree_webrtc/modular/connection_module.py b/dimos/robot/unitree_webrtc/modular/connection_module.py deleted file mode 100644 index b6a08f9857..0000000000 --- a/dimos/robot/unitree_webrtc/modular/connection_module.py +++ /dev/null @@ -1,340 +0,0 @@ -#!/usr/bin/env python3 - -#!/usr/bin/env python3 - -# 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 dataclasses import dataclass -import functools -import logging -import os -import queue -import warnings - -from dimos_lcm.sensor_msgs import CameraInfo -import reactivex as rx -from reactivex import operators as ops -from reactivex.observable import Observable - -from dimos.agents import Output, Reducer, Stream, skill # type: ignore[attr-defined] -from dimos.constants import DEFAULT_CAPACITY_COLOR_IMAGE -from dimos.core import DimosCluster, In, LCMTransport, Module, ModuleConfig, Out, pSHMTransport, rpc -from dimos.core.global_config import GlobalConfig -from dimos.msgs.geometry_msgs import PoseStamped, Quaternion, Transform, Twist, Vector3 -from dimos.msgs.sensor_msgs.Image import Image -from dimos.msgs.std_msgs import Header -from dimos.robot.unitree.connection.connection import UnitreeWebRTCConnection -from dimos.robot.unitree_webrtc.type.lidar import LidarMessage -from dimos.utils.data import get_data -from dimos.utils.decorators import simple_mcache -from dimos.utils.logging_config import setup_logger -from dimos.utils.testing import TimedSensorReplay, TimedSensorStorage - -logger = setup_logger(level=logging.INFO) - -# Suppress verbose loggers -logging.getLogger("aiortc.codecs.h264").setLevel(logging.ERROR) -logging.getLogger("lcm_foxglove_bridge").setLevel(logging.ERROR) -logging.getLogger("websockets.server").setLevel(logging.ERROR) -logging.getLogger("FoxgloveServer").setLevel(logging.ERROR) -logging.getLogger("asyncio").setLevel(logging.ERROR) -logging.getLogger("root").setLevel(logging.WARNING) - - -# Suppress warnings -warnings.filterwarnings("ignore", message="coroutine.*was never awaited") -warnings.filterwarnings("ignore", message="H264Decoder.*failed to decode") - -image_resize_factor = 1 -originalwidth, originalheight = (1280, 720) - - -class FakeRTC(UnitreeWebRTCConnection): - dir_name = "unitree_go2_office_walk2" - - # we don't want UnitreeWebRTCConnection to init - def __init__( # type: ignore[no-untyped-def] - self, - **kwargs, - ) -> None: - get_data(self.dir_name) - self.replay_config = { - "loop": kwargs.get("loop"), - "seek": kwargs.get("seek"), - "duration": kwargs.get("duration"), - } - - def connect(self) -> None: - pass - - def start(self) -> None: - pass - - def standup(self) -> None: - print("standup suppressed") - - def liedown(self) -> None: - print("liedown suppressed") - - @simple_mcache - def lidar_stream(self): # type: ignore[no-untyped-def] - print("lidar stream start") - lidar_store = TimedSensorReplay(f"{self.dir_name}/lidar") # type: ignore[var-annotated] - return lidar_store.stream(**self.replay_config) # type: ignore[arg-type] - - @simple_mcache - def odom_stream(self): # type: ignore[no-untyped-def] - print("odom stream start") - odom_store = TimedSensorReplay(f"{self.dir_name}/odom") # type: ignore[var-annotated] - return odom_store.stream(**self.replay_config) # type: ignore[arg-type] - - # we don't have raw video stream in the data set - @simple_mcache - def video_stream(self): # type: ignore[no-untyped-def] - print("video stream start") - video_store = TimedSensorReplay(f"{self.dir_name}/video") # type: ignore[var-annotated] - - return video_store.stream(**self.replay_config) # type: ignore[arg-type] - - def move(self, vector: Twist, duration: float = 0.0) -> None: # type: ignore[override] - pass - - def publish_request(self, topic: str, data: dict): # type: ignore[no-untyped-def, type-arg] - """Fake publish request for testing.""" - return {"status": "ok", "message": "Fake publish"} - - -@dataclass -class ConnectionModuleConfig(ModuleConfig): - ip: str | None = None - connection_type: str = "fake" # or "fake" or "mujoco" - loop: bool = False # For fake connection - speed: float = 1.0 # For fake connection - - -class ConnectionModule(Module): - camera_info: Out[CameraInfo] - odom: Out[PoseStamped] - lidar: Out[LidarMessage] - video: Out[Image] - movecmd: In[Twist] - - connection = None - - default_config = ConnectionModuleConfig - - # mega temporary, skill should have a limit decorator for number of - # parallel calls - video_running: bool = False - - def __init__(self, connection_type: str = "webrtc", *args, **kwargs) -> None: # type: ignore[no-untyped-def] - self.connection_config = kwargs - self.connection_type = connection_type - Module.__init__(self, *args, **kwargs) - - @skill(stream=Stream.passive, output=Output.image, reducer=Reducer.latest) # type: ignore[arg-type] - def video_stream_tool(self) -> Image: # type: ignore[misc] - """implicit video stream skill, don't call this directly""" - if self.video_running: - return "video stream already running" - self.video_running = True - _queue = queue.Queue(maxsize=1) # type: ignore[var-annotated] - self.connection.video_stream().subscribe(_queue.put) # type: ignore[attr-defined] - - yield from iter(_queue.get, None) - - @rpc - def record(self, recording_name: str) -> None: - lidar_store: TimedSensorStorage = TimedSensorStorage(f"{recording_name}/lidar") # type: ignore[type-arg] - lidar_store.save_stream(self.connection.lidar_stream()).subscribe(lambda x: x) # type: ignore[arg-type, attr-defined] - - odom_store: TimedSensorStorage = TimedSensorStorage(f"{recording_name}/odom") # type: ignore[type-arg] - odom_store.save_stream(self.connection.odom_stream()).subscribe(lambda x: x) # type: ignore[arg-type, attr-defined] - - video_store: TimedSensorStorage = TimedSensorStorage(f"{recording_name}/video") # type: ignore[type-arg] - video_store.save_stream(self.connection.video_stream()).subscribe(lambda x: x) # type: ignore[arg-type, attr-defined] - - @rpc - def start(self): # type: ignore[no-untyped-def] - """Start the connection and subscribe to sensor streams.""" - - super().start() - - match self.connection_type: - case "webrtc": - self.connection = UnitreeWebRTCConnection(**self.connection_config) - case "fake": - self.connection = FakeRTC(**self.connection_config, seek=12.0) - case "mujoco": - from dimos.robot.unitree_webrtc.mujoco_connection import MujocoConnection - - self.connection = MujocoConnection(GlobalConfig()) # type: ignore[assignment] - self.connection.start() # type: ignore[union-attr] - case _: - raise ValueError(f"Unknown connection type: {self.connection_type}") - - unsub = self.connection.odom_stream().subscribe( # type: ignore[union-attr] - lambda odom: self._publish_tf(odom) and self.odom.publish(odom) # type: ignore[func-returns-value] - ) - self._disposables.add(unsub) - - # Connect sensor streams to outputs - unsub = self.connection.lidar_stream().subscribe(self.lidar.publish) # type: ignore[union-attr] - self._disposables.add(unsub) - - # self.connection.lidar_stream().subscribe(lambda lidar: print("LIDAR", lidar.ts)) - # self.connection.video_stream().subscribe(lambda video: print("IMAGE", video.ts)) - # self.connection.odom_stream().subscribe(lambda odom: print("ODOM", odom.ts)) - - def resize(image: Image) -> Image: - return image.resize( - int(originalwidth / image_resize_factor), int(originalheight / image_resize_factor) - ) - - unsub = self.connection.video_stream().subscribe(self.video.publish) # type: ignore[union-attr] - self._disposables.add(unsub) - unsub = self.camera_info_stream().subscribe(self.camera_info.publish) - self._disposables.add(unsub) - unsub = self.movecmd.subscribe(self.connection.move) # type: ignore[union-attr] - self._disposables.add(unsub) # type: ignore[arg-type] - - @rpc - def stop(self) -> None: - if self.connection: - self.connection.stop() - - super().stop() - - @classmethod - def _odom_to_tf(cls, odom: PoseStamped) -> list[Transform]: - camera_link = Transform( - translation=Vector3(0.3, 0.0, 0.0), - rotation=Quaternion(0.0, 0.0, 0.0, 1.0), - frame_id="base_link", - child_frame_id="camera_link", - ts=odom.ts, - ) - - camera_optical = Transform( - translation=Vector3(0.0, 0.0, 0.0), - rotation=Quaternion(-0.5, 0.5, -0.5, 0.5), - frame_id="camera_link", - child_frame_id="camera_optical", - ts=odom.ts, - ) - - sensor = Transform( - translation=Vector3(0.0, 0.0, 0.0), - rotation=Quaternion(0.0, 0.0, 0.0, 1.0), - frame_id="world", - child_frame_id="sensor", - ts=odom.ts, - ) - - return [ - Transform.from_pose("base_link", odom), - camera_link, - camera_optical, - sensor, - ] - - def _publish_tf(self, msg) -> None: # type: ignore[no-untyped-def] - self.odom.publish(msg) - self.tf.publish(*self._odom_to_tf(msg)) - - @rpc - def publish_request(self, topic: str, data: dict): # type: ignore[no-untyped-def, type-arg] - """Publish a request to the WebRTC connection. - Args: - topic: The RTC topic to publish to - data: The data dictionary to publish - Returns: - The result of the publish request - """ - return self.connection.publish_request(topic, data) # type: ignore[union-attr] - - @classmethod - def _camera_info(cls) -> Out[CameraInfo]: - fx, fy, cx, cy = list( - map( - lambda x: int(x / image_resize_factor), - [819.553492, 820.646595, 625.284099, 336.808987], - ) - ) - width, height = tuple( - map( - lambda x: int(x / image_resize_factor), - [originalwidth, originalheight], - ) - ) - - # Camera matrix K (3x3) - K = [fx, 0, cx, 0, fy, cy, 0, 0, 1] - - # No distortion coefficients for now - D = [0.0, 0.0, 0.0, 0.0, 0.0] - - # Identity rotation matrix - R = [1, 0, 0, 0, 1, 0, 0, 0, 1] - - # Projection matrix P (3x4) - P = [fx, 0, cx, 0, 0, fy, cy, 0, 0, 0, 1, 0] - - base_msg = { - "D_length": len(D), - "height": height, - "width": width, - "distortion_model": "plumb_bob", - "D": D, - "K": K, - "R": R, - "P": P, - "binning_x": 0, - "binning_y": 0, - } - - return CameraInfo(**base_msg, header=Header("camera_optical")) # type: ignore[no-any-return] - - @functools.cache - def camera_info_stream(self) -> Observable[CameraInfo]: - return rx.interval(1).pipe(ops.map(lambda _: self._camera_info())) - - -def deploy_connection(dimos: DimosCluster, **kwargs): # type: ignore[no-untyped-def] - foxglove_bridge = dimos.deploy(FoxgloveBridge) # type: ignore[attr-defined, name-defined] - foxglove_bridge.start() - - connection = dimos.deploy( # type: ignore[attr-defined] - ConnectionModule, - ip=os.getenv("ROBOT_IP"), - connection_type=os.getenv("CONNECTION_TYPE", "fake"), - **kwargs, - ) - - connection.odom.transport = LCMTransport("/odom", PoseStamped) - - connection.video.transport = pSHMTransport( - "/image", default_capacity=DEFAULT_CAPACITY_COLOR_IMAGE - ) - - connection.lidar.transport = pSHMTransport( - "/lidar", default_capacity=DEFAULT_CAPACITY_COLOR_IMAGE - ) - - connection.video.transport = LCMTransport("/image", Image) - connection.lidar.transport = LCMTransport("/lidar", LidarMessage) - connection.movecmd.transport = LCMTransport("/cmd_vel", Twist) - connection.camera_info.transport = LCMTransport("/camera_info", CameraInfo) - - return connection diff --git a/dimos/robot/unitree_webrtc/modular/ivan_unitree.py b/dimos/robot/unitree_webrtc/modular/ivan_unitree.py deleted file mode 100644 index e3d2a9a00f..0000000000 --- a/dimos/robot/unitree_webrtc/modular/ivan_unitree.py +++ /dev/null @@ -1,98 +0,0 @@ -# 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. - -import logging -import time - -from dimos.agents.spec import Model, Provider -from dimos.core import LCMTransport, start -from dimos.msgs.foxglove_msgs import ImageAnnotations -from dimos.msgs.sensor_msgs import Image -from dimos.msgs.vision_msgs import Detection2DArray -from dimos.perception.detection.module2D import Detection2DModule -from dimos.perception.detection.reid import ReidModule -from dimos.protocol.pubsub import lcm # type: ignore[attr-defined] -from dimos.robot.foxglove_bridge import FoxgloveBridge -from dimos.robot.unitree_webrtc.modular import deploy_connection # type: ignore[attr-defined] -from dimos.robot.unitree_webrtc.modular.connection_module import ConnectionModule -from dimos.utils.logging_config import setup_logger - -logger = setup_logger(level=logging.INFO) - - -def detection_unitree() -> None: - dimos = start(8) - connection = deploy_connection(dimos) - - def goto(pose) -> bool: # type: ignore[no-untyped-def] - print("NAVIGATION REQUESTED:", pose) - return True - - detector = dimos.deploy( # type: ignore[attr-defined] - Detection2DModule, - camera_info=ConnectionModule._camera_info(), - ) - - detector.image.connect(connection.video) - - detector.annotations.transport = LCMTransport("/annotations", ImageAnnotations) - detector.detections.transport = LCMTransport("/detections", Detection2DArray) - - detector.detected_image_0.transport = LCMTransport("/detected/image/0", Image) - detector.detected_image_1.transport = LCMTransport("/detected/image/1", Image) - detector.detected_image_2.transport = LCMTransport("/detected/image/2", Image) - - reid = dimos.deploy(ReidModule) # type: ignore[attr-defined] - - reid.image.connect(connection.video) - reid.detections.connect(detector.detections) - reid.annotations.transport = LCMTransport("/reid/annotations", ImageAnnotations) - - detector.start() - connection.start() - reid.start() - - from dimos.agents import Agent # type: ignore[attr-defined] - from dimos.agents.cli.human import HumanInput - - agent = Agent( - system_prompt="You are a helpful assistant for controlling a Unitree Go2 robot.", - model=Model.GPT_4O, # Could add CLAUDE models to enum - provider=Provider.OPENAI, # type: ignore[attr-defined] # Would need ANTHROPIC provider - ) - - human_input = dimos.deploy(HumanInput) # type: ignore[attr-defined] - agent.register_skills(human_input) - agent.register_skills(detector) - - bridge = FoxgloveBridge( - shm_channels=[ - "/image#sensor_msgs.Image", - "/lidar#sensor_msgs.PointCloud2", - ] - ) - time.sleep(1) - bridge.start() - - try: - while True: - time.sleep(1) - except KeyboardInterrupt: - connection.stop() - logger.info("Shutting down...") - - -if __name__ == "__main__": - lcm.autoconf() - detection_unitree() From 183be923dbbf0867c923725dc63498fda97e7155 Mon Sep 17 00:00:00 2001 From: Paul Nechifor Date: Tue, 6 Jan 2026 05:34:33 +0200 Subject: [PATCH 3/4] chore: linting fixes --- dimos/core/module.py | 4 +--- dimos/hardware/sensors/camera/module.py | 1 - dimos/utils/docs/test_doclinks.py | 24 ++++++++++++------------ 3 files changed, 13 insertions(+), 16 deletions(-) diff --git a/dimos/core/module.py b/dimos/core/module.py index 62afc94f40..08e428d3c7 100644 --- a/dimos/core/module.py +++ b/dimos/core/module.py @@ -15,7 +15,6 @@ from collections.abc import Callable from dataclasses import dataclass from functools import partial -import inspect import sys import threading from typing import ( @@ -36,7 +35,7 @@ from dimos.core import colors from dimos.core.core import T, rpc -from dimos.core.introspection.module import INTERNAL_RPCS, extract_module_info, render_module_io +from dimos.core.introspection.module import extract_module_info, render_module_io from dimos.core.resource import Resource from dimos.core.rpc_client import RpcCall from dimos.core.stream import In, Out, RemoteIn, RemoteOut, Transport @@ -276,7 +275,6 @@ def __get__( @classmethod def _module_info_class(cls) -> "ModuleInfo": """Class-level module_info() - returns ModuleInfo from annotations.""" - from dimos.core.introspection.module import ModuleInfo hints = get_type_hints(cls) diff --git a/dimos/hardware/sensors/camera/module.py b/dimos/hardware/sensors/camera/module.py index de2c3b8c78..10c541723a 100644 --- a/dimos/hardware/sensors/camera/module.py +++ b/dimos/hardware/sensors/camera/module.py @@ -19,7 +19,6 @@ import reactivex as rx from reactivex import operators as ops -from reactivex.observable import Observable from dimos.agents import Output, Reducer, Stream, skill from dimos.core import Module, ModuleConfig, Out, rpc diff --git a/dimos/utils/docs/test_doclinks.py b/dimos/utils/docs/test_doclinks.py index 48f4bbdc21..7313ec3676 100644 --- a/dimos/utils/docs/test_doclinks.py +++ b/dimos/utils/docs/test_doclinks.py @@ -133,7 +133,7 @@ def test_auto_links_symbol(self, file_index): content = "The `Configurable` class is in [`service/spec.py`]()" doc_path = REPO_ROOT / "docs/test.md" - new_content, changes, errors = process_markdown( + new_content, _changes, errors = process_markdown( content, REPO_ROOT, doc_path, @@ -151,7 +151,7 @@ def test_preserves_existing_line_fragment(self, file_index): content = "See [`service/spec.py`](#L99)" doc_path = REPO_ROOT / "docs/test.md" - new_content, changes, errors = process_markdown( + new_content, _changes, _errors = process_markdown( content, REPO_ROOT, doc_path, @@ -187,7 +187,7 @@ def test_skips_non_file_refs(self, file_index): content = "The `MyClass` is documented at [`MyClass`]()" doc_path = REPO_ROOT / "docs/test.md" - new_content, changes, errors = process_markdown( + _new_content, changes, errors = process_markdown( content, REPO_ROOT, doc_path, @@ -205,7 +205,7 @@ def test_errors_on_ambiguous(self, file_index): content = "See [`spec.py`]() for details" # Multiple spec.py files doc_path = REPO_ROOT / "docs/test.md" - new_content, changes, errors = process_markdown( + _new_content, _changes, errors = process_markdown( content, REPO_ROOT, doc_path, @@ -223,7 +223,7 @@ def test_errors_on_not_found(self, file_index): content = "See [`nonexistent/file.py`]() for details" doc_path = REPO_ROOT / "docs/test.md" - new_content, changes, errors = process_markdown( + _new_content, _changes, errors = process_markdown( content, REPO_ROOT, doc_path, @@ -241,7 +241,7 @@ def test_github_mode(self, file_index): content = "See [`service/spec.py`]()" doc_path = REPO_ROOT / "docs/test.md" - new_content, changes, errors = process_markdown( + new_content, _changes, _errors = process_markdown( content, REPO_ROOT, doc_path, @@ -258,7 +258,7 @@ def test_relative_mode(self, file_index): content = "See [`service/spec.py`]()" doc_path = REPO_ROOT / "docs/concepts/test.md" - new_content, changes, errors = process_markdown( + new_content, _changes, _errors = process_markdown( content, REPO_ROOT, doc_path, @@ -313,7 +313,7 @@ def test_case_insensitive_lookup(self, file_index, doc_index): content = "See [CONFIGURATION](.md) for details" doc_path = REPO_ROOT / "docs/test.md" - new_content, changes, errors = process_markdown( + new_content, _changes, errors = process_markdown( content, REPO_ROOT, doc_path, @@ -333,7 +333,7 @@ def test_doc_link_github_mode(self, file_index, doc_index): content = "See [Configuration](.md)" doc_path = REPO_ROOT / "docs/test.md" - new_content, changes, errors = process_markdown( + new_content, _changes, _errors = process_markdown( content, REPO_ROOT, doc_path, @@ -352,7 +352,7 @@ def test_doc_link_relative_mode(self, file_index, doc_index): content = "See [Development](.md)" doc_path = REPO_ROOT / "docs/concepts/test.md" - new_content, changes, errors = process_markdown( + new_content, _changes, errors = process_markdown( content, REPO_ROOT, doc_path, @@ -372,7 +372,7 @@ def test_doc_not_found_error(self, file_index, doc_index): content = "See [NonexistentDoc](.md)" doc_path = REPO_ROOT / "docs/test.md" - new_content, changes, errors = process_markdown( + _new_content, _changes, errors = process_markdown( content, REPO_ROOT, doc_path, @@ -391,7 +391,7 @@ def test_skips_regular_links(self, file_index, doc_index): content = "See [regular link](https://example.com) here" doc_path = REPO_ROOT / "docs/test.md" - new_content, changes, errors = process_markdown( + new_content, _changes, _errors = process_markdown( content, REPO_ROOT, doc_path, From be1c560b6a338258cbc2c640eb7715bc594f7276 Mon Sep 17 00:00:00 2001 From: Paul Nechifor Date: Tue, 6 Jan 2026 05:46:41 +0200 Subject: [PATCH 4/4] fix: tests --- dimos/agents/skills/conftest.py | 2 -- .../skills/test_unitree_skill_container.py | 22 +++++-------------- 2 files changed, 6 insertions(+), 18 deletions(-) diff --git a/dimos/agents/skills/conftest.py b/dimos/agents/skills/conftest.py index 6cf50f9b2d..0e2e3e0636 100644 --- a/dimos/agents/skills/conftest.py +++ b/dimos/agents/skills/conftest.py @@ -72,8 +72,6 @@ def google_maps_skill_container(mocker): @pytest.fixture def unitree_skills(mocker): container = UnitreeSkillContainer() - container._move = mocker.Mock() - container._publish_request = mocker.Mock() container.start() yield container container.stop() diff --git a/dimos/agents/skills/test_unitree_skill_container.py b/dimos/agents/skills/test_unitree_skill_container.py index 16088875c5..29dfade979 100644 --- a/dimos/agents/skills/test_unitree_skill_container.py +++ b/dimos/agents/skills/test_unitree_skill_container.py @@ -13,29 +13,19 @@ # limitations under the License. -def test_pounce(create_unitree_skills_agent, unitree_skills) -> None: +def test_pounce(mocker, create_unitree_skills_agent, unitree_skills) -> None: agent = create_unitree_skills_agent(fixture="test_pounce.json") + publish_request_mock = mocker.Mock() + unitree_skills.get_rpc_calls = mocker.Mock(return_value=publish_request_mock) response = agent.query("pounce") assert "front pounce" in response.lower() - unitree_skills._publish_request.assert_called_once_with( - "rt/api/sport/request", {"api_id": 1032} - ) - - -def test_show_your_love(create_unitree_skills_agent, unitree_skills) -> None: - agent = create_unitree_skills_agent(fixture="test_show_your_love.json") - - response = agent.query("show your love") - - assert "finger heart" in response.lower() - unitree_skills._publish_request.assert_called_once_with( - "rt/api/sport/request", {"api_id": 1036} - ) + publish_request_mock.assert_called_once_with("rt/api/sport/request", {"api_id": 1032}) -def test_did_you_mean(unitree_skills) -> None: +def test_did_you_mean(mocker, unitree_skills) -> None: + unitree_skills.get_rpc_calls = mocker.Mock() assert ( unitree_skills.execute_sport_command("Pounce") == "There's no 'Pounce' command. Did you mean: ['FrontPounce', 'Pose']"