diff --git a/data/.lfs/markers_go2.db.tar.gz b/data/.lfs/markers_go2.db.tar.gz new file mode 100644 index 0000000000..1f207ddccd --- /dev/null +++ b/data/.lfs/markers_go2.db.tar.gz @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5a43529f8dbc2aedcccca6ae89747235826123c2bc066e0dc8b87c2042219dae +size 99270761 diff --git a/dimos/mapping/voxels.py b/dimos/mapping/voxels.py index de9f1684aa..3f9b57a634 100644 --- a/dimos/mapping/voxels.py +++ b/dimos/mapping/voxels.py @@ -248,6 +248,7 @@ class VoxelGridMapperConfig(ModuleConfig): device: str = "CUDA:0" carve_columns: bool = True frame_id: str = "world" + emit_every: int = 1 class VoxelGridMapper(StreamModule[PointCloud2, PointCloud2]): diff --git a/dimos/perception/fiducial/marker_tf_module.py b/dimos/perception/fiducial/marker_tf_module.py index 8deff5360b..0912d2e4f2 100644 --- a/dimos/perception/fiducial/marker_tf_module.py +++ b/dimos/perception/fiducial/marker_tf_module.py @@ -21,10 +21,10 @@ empty distortion supported best; refine intrinsics on hardware when needed). Camera calibration runbook: ``docs/usage/camera_calibration.md``. -The pose chain is ``base_link -> -> marker`` where ```` is +The pose chain is ``world -> -> marker`` where ```` is ``Image.frame_id`` when set, else ``CameraInfo.frame_id``, else ``camera_optical``. -That matches the frame the pixels live in. Then ``world -> base_link`` is applied -before publishing the marker namespace. +That matches the frame the pixels live in. The TF graph resolves ``world -> optical`` +in one lookup; the module no longer needs an intermediate ``base_link`` hop. OpenCV 4.7+ uses ``ArucoDetector``; pose uses ``solvePnP`` (``estimatePoseSingleMarkers`` was removed in newer OpenCV builds). @@ -79,6 +79,13 @@ from dimos.core.rpc_client import ModuleProxy +_FISHEYE_MODELS = frozenset({"equidistant", "fisheye", "kannala_brandt"}) + + +def _is_fisheye_model(distortion_model: str | None) -> bool: + return (distortion_model or "").strip().lower() in _FISHEYE_MODELS + + def camera_info_to_cv_matrices(camera_info: CameraInfo) -> tuple[np.ndarray, np.ndarray]: """Build OpenCV ``cameraMatrix`` and ``distCoeffs`` from ``CameraInfo``.""" k = np.array(camera_info.K, dtype=np.float64).reshape(3, 3) @@ -117,15 +124,34 @@ def estimate_marker_pose( marker_length_m: float, camera_matrix: np.ndarray, dist_coeffs: np.ndarray, + *, + distortion_model: str | None = None, ) -> tuple[np.ndarray, np.ndarray] | None: - """Return ``(rvec, tvec)`` for camera optical <- marker from undistorted solvePnP.""" + """Return ``(rvec, tvec)`` for camera optical <- marker from undistorted solvePnP. + + For fisheye/equidistant intrinsics, corners are first undistorted into the + same pinhole ``K`` so the radtan-only ``solvePnP`` sees pinhole-equivalent + pixels. Otherwise the radtan ``dist_coeffs`` are passed straight through. + """ obj = _aruco_marker_object_points(marker_length_m) - img = corners_px.reshape(4, 1, 2).astype(np.float32) + img: np.ndarray = corners_px.reshape(4, 1, 2).astype(np.float32) + if _is_fisheye_model(distortion_model): + d_flat = np.asarray(dist_coeffs, dtype=np.float64).reshape(-1) + if d_flat.size < 4: + raise ValueError( + f"Fisheye/equidistant distortion model requires at least 4 coefficients; " + f"got {d_flat.size}. Check CameraInfo.D." + ) + d_fisheye = d_flat[:4].reshape(4, 1) + img = cv2.fisheye.undistortPoints(img, camera_matrix, d_fisheye, P=camera_matrix) + solve_dist: np.ndarray = np.zeros((0, 1), dtype=np.float64) + else: + solve_dist = dist_coeffs ok, rvec, tvec = cv2.solvePnP( obj, img, camera_matrix, - dist_coeffs, + solve_dist, flags=cv2.SOLVEPNP_IPPE_SQUARE, ) if not ok: @@ -170,14 +196,13 @@ class MarkerTfModuleConfig(ModuleConfig): """ world_frame: str = "world" - base_frame: str = "base_link" markers_frame: str = "markers" marker_namespace_prefix: str | None = None aruco_dictionary: str = "DICT_APRILTAG_36h11" marker_length_m: float = Field( ..., gt=0.0, description="Physical square marker edge length in meters." ) - max_freq: float = 15.0 + max_freq: float = 5.0 tf_lookup_tolerance: float = 0.5 @@ -207,7 +232,7 @@ def _marker_child_frame(self, marker_id: int) -> str: def _maybe_warn_distortion(self, camera_info: CameraInfo) -> None: model = (camera_info.distortion_model or "").strip().lower() - if model in ("", "plumb_bob"): + if model in ("", "plumb_bob") or _is_fisheye_model(model): return if not self._warned_distortion_model: logger.warning( @@ -242,31 +267,16 @@ def _process_color_image(self, image: Image) -> None: cam_mtx, dist = camera_info_to_cv_matrices(info) optical = _camera_optical_frame_id(image, info) - t_world_base = self.tf.get( + t_world_optical = self.tf.get( self.config.world_frame, - self.config.base_frame, - image.ts, - self.config.tf_lookup_tolerance, - ) - if t_world_base is None: - logger.debug( - "MarkerTfModule: no TF %s -> %s at ts=%s", - self.config.world_frame, - self.config.base_frame, - image.ts, - ) - return - - t_base_optical = self.tf.get( - self.config.base_frame, optical, image.ts, self.config.tf_lookup_tolerance, ) - if t_base_optical is None: + if t_world_optical is None: logger.debug( "MarkerTfModule: no TF %s -> %s at ts=%s", - self.config.base_frame, + self.config.world_frame, optical, image.ts, ) @@ -291,6 +301,7 @@ def _process_color_image(self, image: Image) -> None: self.config.marker_length_m, cam_mtx, dist, + distortion_model=info.distortion_model, ) if pose is None: continue @@ -302,8 +313,7 @@ def _process_color_image(self, image: Image) -> None: child_frame_id="__marker_tmp", ts=ts, ) - t_base_marker = t_base_optical + t_optical_marker - t_world_marker = t_world_base + t_base_marker + t_world_marker = t_world_optical + t_optical_marker out.append( Transform( translation=t_world_marker.translation, diff --git a/dimos/protocol/pubsub/registry.py b/dimos/protocol/pubsub/registry.py new file mode 100644 index 0000000000..82afd2cef6 --- /dev/null +++ b/dimos/protocol/pubsub/registry.py @@ -0,0 +1,171 @@ +# 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. + +"""Pubsub URI registry: ``":[#]"`` -> started ``PubSubTransport``. + +Maps user-facing protocol names onto the concrete transport classes in +``dimos.core.transport``. Used by CLIs and config files that need to accept +a single string describing both how and where to subscribe. + +URI grammar:: + + :[#] + +- ````: registry key, e.g. ``lcm``, ``jpeg_lcm``, ``plcm``, ``pshm``, + ``shm``, ``jpeg_shm``. +- ````: channel/key, passed verbatim to the transport constructor. +- ````: optional ``module.ClassName`` resolved via + ``dimos.msgs.helpers.resolve_msg_type`` (e.g. ``sensor_msgs.Image``). + +Typed protos (``lcm``, ``jpeg_lcm``) require a message type — either from the +``#``-suffix or the ``msg_type`` kwarg. Pickled / self-describing protos +(``plcm``, ``pshm``, ``shm``, ``jpeg_shm``) don't. +""" + +from __future__ import annotations + +from typing import TYPE_CHECKING, Any + +if TYPE_CHECKING: + from collections.abc import Callable + + from dimos.core.transport import PubSubTransport + + +def _make_lcm(topic: str, msg_type: type | None) -> Any: + if msg_type is None: + raise ValueError("proto 'lcm' requires a message type (URI '#suffix' or msg_type kwarg)") + from dimos.core.transport import LCMTransport + + return LCMTransport(topic, msg_type) + + +def _make_jpeg_lcm(topic: str, msg_type: type | None) -> Any: + if msg_type is None: + raise ValueError( + "proto 'jpeg_lcm' requires a message type (URI '#suffix' or msg_type kwarg)" + ) + from dimos.core.transport import JpegLcmTransport + + return JpegLcmTransport(topic, msg_type) + + +def _make_plcm(topic: str, msg_type: type | None) -> Any: + # pickled LCM: receivers unpickle Python objects, no type registration needed. + from dimos.core.transport import pLCMTransport + + return pLCMTransport(topic) + + +def _make_pshm(topic: str, msg_type: type | None) -> Any: + # pickled shared memory: same shape as plcm but over /dev/shm. + from dimos.core.transport import pSHMTransport + + return pSHMTransport(topic) + + +def _make_shm(topic: str, msg_type: type | None) -> Any: + # raw-bytes shared memory: subscribers receive bytes; caller decodes. + from dimos.core.transport import SHMTransport + + return SHMTransport(topic) + + +def _make_jpeg_shm(topic: str, msg_type: type | None) -> Any: + # JPEG-encoded shared memory: subscribers receive decoded Image objects. + from dimos.core.transport import JpegShmTransport + + return JpegShmTransport(topic) + + +_REGISTRY: dict[str, Callable[[str, type | None], Any]] = { + "lcm": _make_lcm, + "jpeg_lcm": _make_jpeg_lcm, + "plcm": _make_plcm, + "pshm": _make_pshm, + "shm": _make_shm, + "jpeg_shm": _make_jpeg_shm, +} + + +def supported_protos() -> list[str]: + """Return the sorted list of registered proto names.""" + return sorted(_REGISTRY.keys()) + + +def parse_pubsub_uri(uri: str) -> tuple[str, str, str | None]: + """Split ``":[#]"`` into its three parts. + + Returns ``(proto, topic, msg_type_name_or_None)``. Raises ``ValueError`` + on malformed input or an unknown proto. + """ + if ":" not in uri: + raise ValueError( + f"Invalid pubsub URI {uri!r}: expected ':'. " + f"Supported protos: {supported_protos()}" + ) + proto, rest = uri.split(":", 1) + if not proto: + raise ValueError(f"Invalid pubsub URI {uri!r}: empty proto") + if proto not in _REGISTRY: + raise ValueError(f"Unsupported proto {proto!r}; supported: {supported_protos()}") + msg_type_name: str | None + if "#" in rest: + topic, suffix = rest.split("#", 1) + msg_type_name = suffix or None + else: + topic, msg_type_name = rest, None + if not topic: + raise ValueError(f"Invalid pubsub URI {uri!r}: empty topic") + return proto, topic, msg_type_name + + +def make_pubsub_transport( + uri: str, + *, + msg_type: type | None = None, +) -> PubSubTransport[Any]: + """Build a ``PubSubTransport`` from a URI (does not call ``start()``). + + The ``#``-suffix in the URI wins over the ``msg_type`` kwarg if both are + present. Pickled / self-describing protos ignore ``msg_type``. + """ + proto, topic, msg_type_name = parse_pubsub_uri(uri) + resolved = msg_type + if msg_type_name is not None: + from dimos.msgs.helpers import resolve_msg_type + + resolved = resolve_msg_type(msg_type_name) + if resolved is None: + raise ValueError(f"Could not resolve message type {msg_type_name!r} from URI {uri!r}") + transport: PubSubTransport[Any] = _REGISTRY[proto](topic, resolved) + return transport + + +def subscribe_pubsub_uri( + uri: str, + callback: Callable[[Any], Any], + *, + msg_type: type | None = None, +) -> tuple[PubSubTransport[Any], Callable[[], None]]: + """Construct + start + subscribe in one step. + + Returns ``(transport, unsubscribe)``. The caller is responsible for + calling ``transport.stop()`` (and ``unsubscribe()`` if it needs to stop + receiving messages before the transport itself stops). + """ + transport = make_pubsub_transport(uri, msg_type=msg_type) + transport.start() + unsub = transport.subscribe(callback) + return transport, unsub diff --git a/dimos/protocol/pubsub/test_registry.py b/dimos/protocol/pubsub/test_registry.py new file mode 100644 index 0000000000..9d7796c2ce --- /dev/null +++ b/dimos/protocol/pubsub/test_registry.py @@ -0,0 +1,180 @@ +# 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 + +import pytest + +from dimos.core.transport import ( + JpegLcmTransport, + JpegShmTransport, + LCMTransport, + SHMTransport, + pLCMTransport, + pSHMTransport, +) +from dimos.msgs.sensor_msgs.Image import Image +from dimos.protocol.pubsub.registry import ( + make_pubsub_transport, + parse_pubsub_uri, + subscribe_pubsub_uri, + supported_protos, +) + + +def test_supported_protos_includes_known_set() -> None: + """Registry exposes the canonical proto names.""" + assert set(supported_protos()) >= {"lcm", "jpeg_lcm", "plcm", "pshm", "shm", "jpeg_shm"} + + +@pytest.mark.parametrize( + ("uri", "expected"), + [ + ("lcm:/color_image", ("lcm", "/color_image", None)), + ("jpeg_lcm:/color_image", ("jpeg_lcm", "/color_image", None)), + ("pshm:color_image", ("pshm", "color_image", None)), + ("shm:foo/bar", ("shm", "foo/bar", None)), + ( + "lcm:/odom#nav_msgs.Odometry", + ("lcm", "/odom", "nav_msgs.Odometry"), + ), + ( + "jpeg_lcm:/color_image#sensor_msgs.Image", + ("jpeg_lcm", "/color_image", "sensor_msgs.Image"), + ), + ], +) +def test_parse_pubsub_uri_happy_paths(uri: str, expected: tuple[str, str, str | None]) -> None: + assert parse_pubsub_uri(uri) == expected + + +@pytest.mark.parametrize( + "uri", + [ + "", + "no-colon-here", + ":/topic-with-empty-proto", + "lcm:", # empty topic + "unknown_proto:/topic", + ], +) +def test_parse_pubsub_uri_rejects_malformed(uri: str) -> None: + with pytest.raises(ValueError): + parse_pubsub_uri(uri) + + +def test_parse_pubsub_uri_error_lists_supported_protos() -> None: + with pytest.raises(ValueError, match="supported:") as exc: + parse_pubsub_uri("nope:/foo") + msg = str(exc.value) + for proto in ("lcm", "jpeg_lcm", "pshm"): + assert proto in msg + + +def test_make_pubsub_transport_lcm_uses_LCMTransport() -> None: + t = make_pubsub_transport("lcm:/color_image", msg_type=Image) + assert isinstance(t, LCMTransport) + + +def test_make_pubsub_transport_jpeg_lcm_uses_JpegLcmTransport() -> None: + t = make_pubsub_transport("jpeg_lcm:/color_image", msg_type=Image) + assert isinstance(t, JpegLcmTransport) + + +def test_make_pubsub_transport_plcm_uses_pLCMTransport() -> None: + t = make_pubsub_transport("plcm:/anything") + assert isinstance(t, pLCMTransport) + + +def test_make_pubsub_transport_pshm_uses_pSHMTransport() -> None: + t = make_pubsub_transport("pshm:color_image") + assert isinstance(t, pSHMTransport) + + +def test_make_pubsub_transport_shm_uses_SHMTransport() -> None: + t = make_pubsub_transport("shm:bytes_topic") + assert isinstance(t, SHMTransport) + + +def test_make_pubsub_transport_jpeg_shm_uses_JpegShmTransport() -> None: + # The Python `turbojpeg` package is importable even when the native + # libturbojpeg.so is missing; the RuntimeError only fires when TurboJPEG() + # is actually constructed. Probe by trying to instantiate it. + turbojpeg = pytest.importorskip("turbojpeg") + try: + turbojpeg.TurboJPEG() + except RuntimeError as exc: + pytest.skip(f"libturbojpeg not available: {exc}") + t = make_pubsub_transport("jpeg_shm:color_image") + assert isinstance(t, JpegShmTransport) + + +def test_make_pubsub_transport_typed_proto_without_msg_type_raises() -> None: + with pytest.raises(ValueError, match="requires a message type"): + make_pubsub_transport("lcm:/color_image") + + +def test_make_pubsub_transport_uri_suffix_resolves_msg_type() -> None: + """The '#' suffix is resolved via resolve_msg_type and used for typed protos.""" + t = make_pubsub_transport("lcm:/color_image#sensor_msgs.Image") + assert isinstance(t, LCMTransport) + + +def test_make_pubsub_transport_unknown_msg_type_raises() -> None: + with pytest.raises(ValueError, match="Could not resolve message type"): + make_pubsub_transport("lcm:/x#not_a_module.NotAType") + + +def test_subscribe_pubsub_uri_returns_transport_and_unsubscribe( + monkeypatch: pytest.MonkeyPatch, +) -> None: + """``subscribe_pubsub_uri`` starts the transport and wires the callback.""" + events: dict[str, object] = {"started": False, "callback": None, "unsubscribed": False} + + class _FakeTransport: + def start(self) -> None: + events["started"] = True + + def stop(self) -> None: + events["stopped"] = True + + def subscribe(self, cb: object) -> object: + events["callback"] = cb + + def _unsub() -> None: + events["unsubscribed"] = True + + return _unsub + + monkeypatch.setattr( + "dimos.protocol.pubsub.registry.make_pubsub_transport", + lambda uri, *, msg_type=None: _FakeTransport(), + ) + + cb_calls: list[object] = [] + + def _record(msg: object) -> None: + cb_calls.append(msg) + + transport, unsub = subscribe_pubsub_uri("lcm:/x", _record, msg_type=Image) + + assert isinstance(transport, _FakeTransport) + assert events["started"] is True + # The registry wires the user's callback to the transport's subscribe verbatim. + assert events["callback"] is _record + events["callback"]("hello") # type: ignore[operator] + assert cb_calls == ["hello"] + + unsub() + assert events["unsubscribed"] is True diff --git a/dimos/protocol/tf/test_tf.py b/dimos/protocol/tf/test_tf.py index b0843bfccd..c7ee8b4a32 100644 --- a/dimos/protocol/tf/test_tf.py +++ b/dimos/protocol/tf/test_tf.py @@ -371,6 +371,32 @@ def test_time_tolerance(self) -> None: result = ttbuffer.get("world", "robot", time_point=base_time + 0.5, time_tolerance=0.1) assert result is None + def test_same_frame_returns_identity(self) -> None: + ttbuffer = MultiTBuffer() + + # Empty buffer: same-frame lookup still returns identity + result = ttbuffer.get("base_link", "base_link") + assert result is not None + assert result.frame_id == "base_link" + assert result.child_frame_id == "base_link" + assert result.translation.x == 0.0 + assert result.translation.y == 0.0 + assert result.translation.z == 0.0 + assert result.rotation.x == 0.0 + assert result.rotation.y == 0.0 + assert result.rotation.z == 0.0 + assert result.rotation.w == 1.0 + + # Same behavior when the frame happens to exist in the buffer + ttbuffer.receive_transform( + Transform(frame_id="world", child_frame_id="base_link", ts=time.time()) + ) + result = ttbuffer.get("world", "world") + assert result is not None + assert result.frame_id == "world" + assert result.child_frame_id == "world" + assert result.rotation.w == 1.0 + def test_nonexistent_frame_pair(self) -> None: ttbuffer = MultiTBuffer() diff --git a/dimos/protocol/tf/tf.py b/dimos/protocol/tf/tf.py index 6e25af7704..a182464ca7 100644 --- a/dimos/protocol/tf/tf.py +++ b/dimos/protocol/tf/tf.py @@ -18,6 +18,7 @@ from collections import deque from dataclasses import field from functools import reduce +import time from dimos.memory.timeseries.inmemory import InMemoryStore from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped @@ -26,6 +27,10 @@ from dimos.protocol.pubsub.impl.lcmpubsub import LCM, Topic from dimos.protocol.pubsub.spec import PubSub from dimos.protocol.service.spec import BaseConfig, Service +from dimos.types.timestamped import to_human_readable +from dimos.utils.logging_config import setup_logger + +logger = setup_logger() # generic configuration for transform service @@ -85,8 +90,6 @@ def __str__(self) -> str: first_item = self.first() time_range = self.time_range() if time_range and first_item: - from dimos.types.timestamped import to_human_readable - start_time = to_human_readable(time_range[0]) end_time = to_human_readable(time_range[1]) duration = time_range[1] - time_range[0] @@ -141,6 +144,13 @@ def get_transform( time_point: float | None = None, time_tolerance: float | None = None, ) -> Transform | None: + if parent_frame == child_frame: + return Transform( + frame_id=parent_frame, + child_frame_id=child_frame, + ts=time_point if time_point is not None else time.time(), + ) + # Check forward direction key = (parent_frame, child_frame) if key in self.buffers: @@ -154,14 +164,24 @@ def get_transform( return None - def get(self, *args, **kwargs) -> Transform | None: # type: ignore[no-untyped-def] - simple = self.get_transform(*args, **kwargs) + def get( + self, + parent_frame: str, + child_frame: str, + time_point: float | None = None, + time_tolerance: float | None = None, + ) -> Transform | None: + simple = self.get_transform(parent_frame, child_frame, time_point, time_tolerance) + if simple is not None: return simple - complex = self.get_transform_search(*args, **kwargs) + complex = self.get_transform_search(parent_frame, child_frame, time_point, time_tolerance) if complex is None: + logger.warning( + f"No direct transform found between '{parent_frame}' and '{child_frame}' at '{to_human_readable(time_point or time.time())}', {self}" + ) return None return reduce(lambda t1, t2: t1 + t2, complex) diff --git a/dimos/robot/all_blueprints.py b/dimos/robot/all_blueprints.py index 25a0f8c936..0e24b7514e 100644 --- a/dimos/robot/all_blueprints.py +++ b/dimos/robot/all_blueprints.py @@ -101,6 +101,7 @@ "unitree-go2-detection": "dimos.robot.unitree.go2.blueprints.smart.unitree_go2_detection:unitree_go2_detection", "unitree-go2-fleet": "dimos.robot.unitree.go2.blueprints.basic.unitree_go2_fleet:unitree_go2_fleet", "unitree-go2-keyboard-teleop": "dimos.robot.unitree.go2.blueprints.basic.unitree_go2_keyboard_teleop:unitree_go2_keyboard_teleop", + "unitree-go2-markers": "dimos.robot.unitree.go2.blueprints.smart.unitree_go2:unitree_go2_markers", "unitree-go2-memory": "dimos.robot.unitree.go2.blueprints.smart.unitree_go2:unitree_go2_memory", "unitree-go2-ros": "dimos.robot.unitree.go2.blueprints.smart.unitree_go2_ros:unitree_go2_ros", "unitree-go2-security": "dimos.robot.unitree.go2.blueprints.agentic.unitree_go2_security:unitree_go2_security", diff --git a/dimos/robot/cli/dimos.py b/dimos/robot/cli/dimos.py index 344c3d43f1..77902a30fe 100644 --- a/dimos/robot/cli/dimos.py +++ b/dimos/robot/cli/dimos.py @@ -687,11 +687,24 @@ def send( @main.command() def cameracalibrate( - source: str = typer.Option(..., "--source", help="Frame source: webcam or folder"), + source: str = typer.Option(..., "--source", help="Frame source: webcam, folder, or topic"), device_index: int = typer.Option(0, "--device-index", help="Webcam device index"), images: Path | None = typer.Option( None, "--images", help="Directory of calibration images for --source folder" ), + topic: str | None = typer.Option( + None, + "--topic", + help=( + "Pubsub URI for --source topic (proto:channel), " + "e.g. 'jpeg_lcm:/color_image' or 'pshm:color_image'." + ), + ), + topic_timeout_sec: float = typer.Option( + 60.0, + "--topic-timeout-sec", + help="Abort --source topic if no frames arrive within this many seconds.", + ), cols: int = typer.Option(..., "--cols", help="Inner chessboard corner columns"), rows: int = typer.Option(..., "--rows", help="Inner chessboard corner rows"), square_size_m: float = typer.Option( @@ -704,6 +717,14 @@ def cameracalibrate( camera_name: str = typer.Option("webcam", "--camera-name", help="Camera name in YAML"), target_count: int = typer.Option(20, "--target-count", help="Accepted webcam frame count"), no_display: bool = typer.Option(False, "--no-display", help="Disable OpenCV preview windows"), + distortion_model: str = typer.Option( + "plumb_bob", + "--distortion-model", + help=( + "Lens model: 'plumb_bob' (5 coeffs, near-pinhole) or 'fisheye' " + "(4 coeffs, wide-angle / fisheye; written as ROS 'equidistant')." + ), + ), ) -> None: """Calibrate camera intrinsics and write ROS CameraInfo YAML.""" from dimos.utils.cli.cameracalibrate.cameracalibrate import run_calibration @@ -716,6 +737,8 @@ def cameracalibrate( source=source, device_index=device_index, images=images, + topic=topic, + topic_timeout_sec=topic_timeout_sec, cols=cols, rows=rows, square_size_m=square_size_m, @@ -724,6 +747,7 @@ def cameracalibrate( camera_name=camera_name, target_count=target_count, no_display=no_display, + distortion_model=distortion_model, ) except (ValueError, RuntimeError) as exc: raise typer.BadParameter(str(exc)) from exc diff --git a/dimos/robot/cli/topic.py b/dimos/robot/cli/topic.py index a60b079105..368b36ae2d 100644 --- a/dimos/robot/cli/topic.py +++ b/dimos/robot/cli/topic.py @@ -37,11 +37,11 @@ def _resolve_type(type_name: str) -> type: for module_name in _modules_to_try: try: - module = importlib.import_module(module_name) - if hasattr(module, type_name): - return getattr(module, type_name) # type: ignore[no-any-return] + module = importlib.import_module(f"{module_name}.{type_name}") except ImportError: continue + if hasattr(module, type_name): + return getattr(module, type_name) # type: ignore[no-any-return] raise ValueError(f"Could not find type '{type_name}' in any known message modules") diff --git a/dimos/robot/unitree/connection.py b/dimos/robot/unitree/connection.py index 919efc76f6..44101cc19d 100644 --- a/dimos/robot/unitree/connection.py +++ b/dimos/robot/unitree/connection.py @@ -17,7 +17,7 @@ import functools import threading import time -from typing import Any, TypeAlias +from typing import Any, TypeAlias, TypeVar import numpy as np from numpy.typing import NDArray @@ -44,16 +44,24 @@ from dimos.robot.unitree.type.lidar import ( RawLidarMsg, pointcloud2_from_webrtc_lidar, - repair_stale_ts, ) from dimos.robot.unitree.type.lowstate import LowStateMsg from dimos.robot.unitree.type.odometry import Odometry +from dimos.types.timestamped import Timestamped from dimos.utils.decorators.decorators import simple_mcache from dimos.utils.reactive import backpressure, callback_to_observable VideoMessage: TypeAlias = NDArray[np.uint8] # Shape: (height, width, 3) +_T = TypeVar("_T", bound=Timestamped) + + +def time_is_now(x: _T) -> _T: + x.ts = time.time() + return x + + @dataclass class SerializableVideoFrame: """Pickleable wrapper for av.VideoFrame with all metadata""" @@ -255,7 +263,8 @@ def lidar_stream(self) -> Observable[PointCloud2]: return backpressure( self.raw_lidar_stream().pipe( ops.map(pointcloud2_from_webrtc_lidar), - repair_stale_ts(), + ops.map(time_is_now), + # repair_stale_ts(), ) ) @@ -266,7 +275,14 @@ def tf_stream(self) -> Observable[Transform]: @simple_mcache def odom_stream(self) -> Observable[Pose]: - return backpressure(self.raw_odom_stream().pipe(ops.map(Odometry.from_msg))) + return backpressure( + self.raw_odom_stream().pipe( + ops.map( + Odometry.from_msg, + ), + ops.map(time_is_now), + ) + ) @simple_mcache def video_stream(self) -> Observable[Image]: @@ -279,8 +295,9 @@ def video_stream(self) -> Observable[Image]: frame.to_ndarray(format="rgb24"), # type: ignore[attr-defined] format=ImageFormat.RGB, # Frame is RGB24, not BGR frame_id="camera_optical", - ) + ), ), + ops.map(time_is_now), ) ) diff --git a/dimos/robot/unitree/go2/blueprints/basic/unitree_go2_basic.py b/dimos/robot/unitree/go2/blueprints/basic/unitree_go2_basic.py index 4f86ccb0a3..ea2af82051 100644 --- a/dimos/robot/unitree/go2/blueprints/basic/unitree_go2_basic.py +++ b/dimos/robot/unitree/go2/blueprints/basic/unitree_go2_basic.py @@ -22,7 +22,6 @@ from dimos.core.global_config import global_config from dimos.core.transport import pSHMTransport from dimos.msgs.sensor_msgs.Image import Image -from dimos.protocol.service.system_configurator.clock_sync import ClockSyncConfigurator from dimos.robot.unitree.go2.connection import GO2Connection from dimos.visualization.vis_module import vis_module @@ -133,9 +132,13 @@ def _go2_rerun_blueprint() -> Any: autoconnect( _with_vis, GO2Connection.blueprint(), - ) - .global_config(n_workers=4, robot_model="unitree_go2") - .configurators(ClockSyncConfigurator()) + ).global_config(n_workers=4, robot_model="unitree_go2") + # we temporarily disabled sensor timestamps + # and are derriving all timestmaps upon reception + # this is because image webrtc stream doesn't have timestamps, + # so it's difficult to corelate the streams otherwise + # + # .configurators(ClockSyncConfigurator()) ) __all__ = [ diff --git a/dimos/robot/unitree/go2/blueprints/smart/unitree_go2.py b/dimos/robot/unitree/go2/blueprints/smart/unitree_go2.py index 6055478d1d..3cbf3d85b8 100644 --- a/dimos/robot/unitree/go2/blueprints/smart/unitree_go2.py +++ b/dimos/robot/unitree/go2/blueprints/smart/unitree_go2.py @@ -29,11 +29,12 @@ from dimos.navigation.movement_manager.movement_manager import MovementManager from dimos.navigation.patrolling.module import PatrollingModule from dimos.navigation.replanning_a_star.module import ReplanningAStarPlanner +from dimos.perception.fiducial.marker_tf_module import MarkerTfModule from dimos.robot.unitree.go2.blueprints.basic.unitree_go2_basic import unitree_go2_basic unitree_go2 = autoconnect( unitree_go2_basic, - VoxelGridMapper.blueprint(), + VoxelGridMapper.blueprint(emit_every=5), CostMapper.blueprint(), ReplanningAStarPlanner.blueprint(), WavefrontFrontierExplorer.blueprint(), @@ -53,9 +54,14 @@ class Go2Memory(Recorder): config: Go2MemoryConfig -unitree_go2_memory = autoconnect( +unitree_go2_markers = autoconnect( unitree_go2, + MarkerTfModule.blueprint(marker_length_m=0.1), +).global_config(n_workers=11, robot_model="unitree_go2") + +unitree_go2_memory = autoconnect( + unitree_go2_markers, Go2Memory.blueprint(), -).global_config(n_workers=11) +).global_config(n_workers=12) -__all__ = ["unitree_go2", "unitree_go2_memory"] +__all__ = ["unitree_go2", "unitree_go2_markers", "unitree_go2_memory"] diff --git a/dimos/robot/unitree/go2/connection.py b/dimos/robot/unitree/go2/connection.py index 4083def93b..5a7c8b595a 100644 --- a/dimos/robot/unitree/go2/connection.py +++ b/dimos/robot/unitree/go2/connection.py @@ -13,6 +13,7 @@ # limitations under the License. from enum import Enum +from importlib import resources import sys from threading import Thread import time @@ -83,19 +84,14 @@ def enable_rage_mode(self) -> bool: ... def publish_request(self, topic: str, data: dict) -> dict: ... # type: ignore[type-arg] +_FRONT_CAMERA_720_YAML = resources.files("dimos.robot.unitree.go2").joinpath( + "front_camera_720.yaml" +) + + def _camera_info_static() -> CameraInfo: - fx, fy, cx, cy = (819.553492, 820.646595, 625.284099, 336.808987) - width, height = (1280, 720) - - return CameraInfo.from_intrinsics( - fx=fx, - fy=fy, - cx=cx, - cy=cy, - width=width, - height=height, - frame_id="camera_optical", - ) + with resources.as_file(_FRONT_CAMERA_720_YAML) as yaml_path: + return CameraInfo.from_yaml(str(yaml_path)) # Static camera mount chain: base_link -> camera_link -> camera_optical. diff --git a/dimos/robot/unitree/go2/front_camera_720.yaml b/dimos/robot/unitree/go2/front_camera_720.yaml new file mode 100644 index 0000000000..bf2eabca56 --- /dev/null +++ b/dimos/robot/unitree/go2/front_camera_720.yaml @@ -0,0 +1,54 @@ +image_width: 1280 +image_height: 720 +camera_name: go2_front_camera_720p +distortion_model: equidistant +camera_matrix: + rows: 3 + cols: 3 + data: + - 797.4756164864929 + - 0.0 + - 643.5352167821186 + - 0.0 + - 796.4872112769983 + - 349.2783605343087 + - 0.0 + - 0.0 + - 1.0 +distortion_coefficients: + rows: 1 + cols: 4 + data: + - -0.07309428880537933 + - -0.02341140740909078 + - -0.0069305931780026956 + - 0.009238684474464793 +rectification_matrix: + rows: 3 + cols: 3 + data: + - 1.0 + - 0.0 + - 0.0 + - 0.0 + - 1.0 + - 0.0 + - 0.0 + - 0.0 + - 1.0 +projection_matrix: + rows: 3 + cols: 4 + data: + - 797.4756164864929 + - 0.0 + - 643.5352167821186 + - 0.0 + - 0.0 + - 796.4872112769983 + - 349.2783605343087 + - 0.0 + - 0.0 + - 0.0 + - 1.0 + - 0.0 diff --git a/dimos/robot/unitree/params/front_camera_720.yaml b/dimos/robot/unitree/params/front_camera_720.yaml deleted file mode 100644 index 0030d5fc6c..0000000000 --- a/dimos/robot/unitree/params/front_camera_720.yaml +++ /dev/null @@ -1,26 +0,0 @@ -image_width: 1280 -image_height: 720 -camera_name: narrow_stereo -camera_matrix: - rows: 3 - cols: 3 - data: [864.39938, 0. , 639.19798, - 0. , 863.73849, 373.28118, - 0. , 0. , 1. ] -distortion_model: plumb_bob -distortion_coefficients: - rows: 1 - cols: 5 - data: [-0.354630, 0.102054, -0.001614, -0.001249, 0.000000] -rectification_matrix: - rows: 3 - cols: 3 - data: [1., 0., 0., - 0., 1., 0., - 0., 0., 1.] -projection_matrix: - rows: 3 - cols: 4 - data: [651.42609, 0. , 633.16224, 0. , - 0. , 804.93951, 373.8537 , 0. , - 0. , 0. , 1. , 0. ] diff --git a/dimos/utils/cli/cameracalibrate/cameracalibrate.py b/dimos/utils/cli/cameracalibrate/cameracalibrate.py index 00b7bbc243..83bebe4f1b 100644 --- a/dimos/utils/cli/cameracalibrate/cameracalibrate.py +++ b/dimos/utils/cli/cameracalibrate/cameracalibrate.py @@ -21,7 +21,10 @@ from enum import Enum import os from pathlib import Path +import threading +import time from typing import Any, TypedDict, cast +import warnings # Default OpenCL off: on Apple Silicon, CPU chessboard detection is often faster and more stable here. # Use setdefault so an explicit OPENCV_OPENCL_RUNTIME from the environment still wins. @@ -59,6 +62,25 @@ class Source(str, Enum): webcam = "webcam" folder = "folder" + topic = "topic" + + +class DistortionModel(str, Enum): + """Distortion model selected for ``calibrate_from_frames``. + + - ``plumb_bob``: ``cv2.calibrateCamera`` with 5-coefficient radial-tangential + model. Good for near-pinhole lenses (narrow webcams, etc). + - ``fisheye``: ``cv2.fisheye.calibrate`` with the 4-coefficient + Kannala-Brandt model. Required for genuine fisheye / very wide-angle lenses + (e.g. the Go2 front camera). The YAML written for this model uses the + ROS-canonical name ``equidistant``. + """ + + plumb_bob = "plumb_bob" + fisheye = "fisheye" + + def to_ros_name(self) -> str: + return "equidistant" if self is DistortionModel.fisheye else self.value app = typer.Typer( @@ -312,53 +334,37 @@ def _draw_capture_status( cv2.putText(preview, detail, (12, 48), cv2.FONT_HERSHEY_SIMPLEX, 0.55, color, 2) -def _capture_frames_from_webcam( - device_index: int, +def _interactive_capture( + next_frame: Callable[[], np.ndarray | None], target_count: int, cols: int, rows: int, *, - no_display: bool = False, + no_display: bool, ) -> _WebcamCapture: - """Capture ``target_count`` BGR frames from a webcam when the board is visible. + """Interactive chessboard preview + SPACE-accept / q-quit loop. - Shows a live preview (unless ``no_display`` is True, for headless runs and CI). - When a chessboard is detected, press SPACE to accept the current frame. Press - ``q`` to quit early (raises if fewer than ``target_count`` frames were accepted). - - ``no_display`` mirrors the CLI ``--no-display`` flag: no ``cv2.imshow`` or window - teardown; ``cv2.waitKey`` is still used so automated tests can inject key codes. + ``next_frame()`` returns the latest BGR (or grayscale) frame, or ``None`` to + skip the iteration without calling ``imshow``/``waitKey``. The caller owns + any wait-on-no-frame or fail-fast policy. ``no_display`` skips ``imshow`` + and window teardown; ``cv2.waitKey`` is still called so tests can inject keys. """ if target_count < 1: raise ValueError("target_count must be >= 1") accepted: list[np.ndarray] = [] accepted_corners: list[np.ndarray] = [] - cap: cv2.VideoCapture | None = None last_detected: tuple[int, int, str] | None = None locked_pattern: tuple[int, int, str] | None = None locked_exact_probe = False pattern_candidates = _pattern_candidates(cols, rows) pattern_candidate_index = 0 - consecutive_read_failures = 0 try: - cap = cv2.VideoCapture(device_index) - if not cap.isOpened(): - raise RuntimeError(f"Failed to open camera device_index={device_index!r}") - while len(accepted) < target_count: - ok, frame = cap.read() - if not ok or frame is None: - consecutive_read_failures += 1 - if consecutive_read_failures >= _MAX_CONSECUTIVE_WEBCAM_READ_FAILURES: - raise RuntimeError( - "Failed to read from camera " - f"device_index={device_index!r} for " - f"{_MAX_CONSECUTIVE_WEBCAM_READ_FAILURES} consecutive attempts." - ) + frame = next_frame() + if frame is None: continue - consecutive_read_failures = 0 if frame.ndim == 3: gray = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY) @@ -432,8 +438,6 @@ def _capture_frames_from_webcam( return _WebcamCapture(accepted, accepted_corners, locked_pattern) finally: - if cap is not None: - cap.release() if not no_display: try: cv2.destroyWindow(_CAMERACALIBRATE_WINDOW) @@ -442,6 +446,57 @@ def _capture_frames_from_webcam( cv2.waitKey(1) +def _capture_frames_from_webcam( + device_index: int, + target_count: int, + cols: int, + rows: int, + *, + no_display: bool = False, +) -> _WebcamCapture: + """Capture ``target_count`` BGR frames from a webcam when the board is visible. + + Shows a live preview (unless ``no_display`` is True, for headless runs and CI). + When a chessboard is detected, press SPACE to accept the current frame. Press + ``q`` to quit early (raises if fewer than ``target_count`` frames were accepted). + + ``no_display`` mirrors the CLI ``--no-display`` flag: no ``cv2.imshow`` or window + teardown; ``cv2.waitKey`` is still used so automated tests can inject key codes. + """ + if target_count < 1: + raise ValueError("target_count must be >= 1") + + cap: cv2.VideoCapture | None = None + consecutive_read_failures = 0 + + try: + cap = cv2.VideoCapture(device_index) + if not cap.isOpened(): + raise RuntimeError(f"Failed to open camera device_index={device_index!r}") + + def _next() -> np.ndarray | None: + nonlocal consecutive_read_failures + assert cap is not None # narrow for type-checker + ok, frame = cap.read() + if not ok or frame is None: + consecutive_read_failures += 1 + if consecutive_read_failures >= _MAX_CONSECUTIVE_WEBCAM_READ_FAILURES: + raise RuntimeError( + "Failed to read from camera " + f"device_index={device_index!r} for " + f"{_MAX_CONSECUTIVE_WEBCAM_READ_FAILURES} consecutive attempts." + ) + return None + consecutive_read_failures = 0 + return frame # type: ignore[no-any-return] + + return _interactive_capture(_next, target_count, cols, rows, no_display=no_display) + + finally: + if cap is not None: + cap.release() + + def capture_frames_from_webcam( device_index: int, target_count: int, @@ -460,6 +515,93 @@ def capture_frames_from_webcam( ).frames +def _capture_frames_from_topic( + topic_uri: str, + target_count: int, + cols: int, + rows: int, + *, + no_display: bool = False, + timeout_sec: float = 60.0, +) -> _WebcamCapture: + """Capture frames from an LCM/SHM image topic with the same interactive UX. + + ``topic_uri`` follows the pubsub registry format ``":"``, e.g. + ``"jpeg_lcm:/color_image"`` or ``"pshm:color_image"``. The publisher must + emit ``sensor_msgs.Image`` messages; ``Image.to_opencv()`` normalizes the + payload to BGR before detection. Raises ``RuntimeError`` if no frames arrive + within ``timeout_sec``. + """ + from dimos.msgs.sensor_msgs.Image import Image + from dimos.protocol.pubsub.registry import subscribe_pubsub_uri + + if target_count < 1: + raise ValueError("target_count must be >= 1") + + latest_frame: list[np.ndarray | None] = [None] + last_received_ts: list[float] = [time.time()] + lock = threading.Lock() + + def _on_image(msg: Any) -> None: + try: + arr = msg.to_opencv() + except (AttributeError, ValueError): + return + with lock: + latest_frame[0] = np.asarray(arr) + last_received_ts[0] = time.time() + + transport, unsub = subscribe_pubsub_uri(topic_uri, _on_image, msg_type=Image) + + def _next() -> np.ndarray | None: + with lock: + frame = latest_frame[0] + ts = last_received_ts[0] + if frame is None: + if time.time() - ts > timeout_sec: + raise RuntimeError( + f"No frames received on topic {topic_uri!r} within {timeout_sec:.1f}s." + ) + # Yield so the LCM/SHM callback thread can run; avoid busy spin. + time.sleep(0.01) + return None + return frame + + try: + return _interactive_capture(_next, target_count, cols, rows, no_display=no_display) + finally: + # Best-effort teardown: swallow per-transport quirks so cleanup + # never masks the original error from _interactive_capture. + try: + unsub() + except Exception: + pass + try: + transport.stop() + except Exception: + pass + + +def capture_frames_from_topic( + topic_uri: str, + target_count: int, + cols: int, + rows: int, + *, + no_display: bool = False, + timeout_sec: float = 60.0, +) -> list[np.ndarray]: + """Capture ``target_count`` frames from an LCM/SHM image topic.""" + return _capture_frames_from_topic( + topic_uri, + target_count, + cols, + rows, + no_display=no_display, + timeout_sec=timeout_sec, + ).frames + + def find_chessboard_corners(gray: np.ndarray, cols: int, rows: int) -> np.ndarray | None: """Detect inner chessboard corners and refine them with sub-pixel accuracy. @@ -507,6 +649,59 @@ def _select_calibration_pattern( return best_cols, best_rows, best_label +def _calibrate_pinhole( + objpoints: list[np.ndarray], + imgpoints: list[np.ndarray], + image_size: tuple[int, int], +) -> tuple[float, np.ndarray, np.ndarray]: + """Run ``cv2.calibrateCamera`` (plumb-bob).""" + _calibrate = cast("Callable[..., Any]", cv2.calibrateCamera) + rms, camera_matrix, dist_coeffs, _rvecs, _tvecs = _calibrate( + objpoints, + imgpoints, + image_size, + None, + None, + ) + K = np.asarray(camera_matrix, dtype=np.float64) + D = np.asarray(dist_coeffs, dtype=np.float64).reshape(-1) + return float(rms), K, D + + +def _calibrate_fisheye( + objpoints: list[np.ndarray], + imgpoints: list[np.ndarray], + image_size: tuple[int, int], +) -> tuple[float, np.ndarray, np.ndarray]: + """Run ``cv2.fisheye.calibrate`` (4-coeff Kannala-Brandt). + + ``objpoints`` must be a list of ``(N, 1, 3)`` arrays and ``imgpoints`` a list of + ``(N, 1, 2)`` arrays (the fisheye solver is strict about the extra middle axis). + """ + K = np.zeros((3, 3), dtype=np.float64) + D = np.zeros((4, 1), dtype=np.float64) + n_views = len(objpoints) + rvecs = [np.zeros((1, 1, 3), dtype=np.float64) for _ in range(n_views)] + tvecs = [np.zeros((1, 1, 3), dtype=np.float64) for _ in range(n_views)] + flags = cv2.fisheye.CALIB_RECOMPUTE_EXTRINSIC | cv2.fisheye.CALIB_FIX_SKEW + criteria = (cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, 30, 1e-6) + _calibrate = cast("Callable[..., Any]", cv2.fisheye.calibrate) + rms, camera_matrix, dist_coeffs, _rvecs, _tvecs = _calibrate( + objpoints, + imgpoints, + image_size, + K, + D, + rvecs, + tvecs, + flags, + criteria, + ) + K_out = np.asarray(camera_matrix, dtype=np.float64) + D_out = np.asarray(dist_coeffs, dtype=np.float64).reshape(-1) + return float(rms), K_out, D_out + + def calibrate_from_frames( frames: list[np.ndarray], cols: int, @@ -515,12 +710,16 @@ def calibrate_from_frames( *, pattern_hint: tuple[int, int, str] | None = None, image_points_hint: list[np.ndarray] | None = None, + distortion_model: DistortionModel | str = DistortionModel.plumb_bob, ) -> CalibrationResultDict: """Calibrate intrinsics from grayscale or BGR frames containing a chessboard. Each frame where ``find_chessboard_corners`` succeeds contributes one view. All frames must share the same resolution. + ``distortion_model`` picks the solver: ``plumb_bob`` (``cv2.calibrateCamera``, + 5 coeffs) or ``fisheye`` (``cv2.fisheye.calibrate``, 4 coeffs). + Returns: ``{"K", "D", "rms", "image_size", "n_used"}`` with ``K`` (3x3) and ``D`` (1-d), ``rms`` reprojection RMSE from OpenCV, ``image_size`` ``(width, height)``, and @@ -529,15 +728,20 @@ def calibrate_from_frames( if not frames: raise ValueError("frames must be non-empty") + model = DistortionModel(distortion_model) + if pattern_hint is None: actual_cols, actual_rows, pattern_label = _select_calibration_pattern(frames, cols, rows) else: actual_cols, actual_rows, pattern_label = pattern_hint - # Object points on Z=0 with XY spacing square_size_m; pairs with image_points from the detector. - objp = np.zeros((actual_rows * actual_cols, 3), dtype=np.float32) - objp[:, :2] = np.mgrid[0:actual_cols, 0:actual_rows].T.reshape(-1, 2).astype(np.float32) - objp *= float(square_size_m) + # Object points on Z=0 with XY spacing square_size_m. cv2.fisheye.calibrate + # demands an explicit middle axis on each view; cv2.calibrateCamera is fine + # with the flat (N, 3) shape. + objp_flat = np.zeros((actual_rows * actual_cols, 3), dtype=np.float32) + objp_flat[:, :2] = np.mgrid[0:actual_cols, 0:actual_rows].T.reshape(-1, 2).astype(np.float32) + objp_flat *= float(square_size_m) + objp_view = objp_flat.reshape(-1, 1, 3) if model is DistortionModel.fisheye else objp_flat objpoints: list[np.ndarray] = [] imgpoints: list[np.ndarray] = [] @@ -571,22 +775,16 @@ def calibrate_from_frames( if corners_opt is None: continue corners_found = corners_opt - objpoints.append(objp) + objpoints.append(objp_view) imgpoints.append(corners_found.astype(np.float32)) if not objpoints: raise ValueError("Chessboard not found in any frame.") - _calibrate = cast("Callable[..., Any]", cv2.calibrateCamera) - rms, camera_matrix, dist_coeffs, _rvecs, _tvecs = _calibrate( - objpoints, - imgpoints, - (w0, h0), - None, - None, - ) - K = np.asarray(camera_matrix, dtype=np.float64) - D = np.asarray(dist_coeffs, dtype=np.float64).reshape(-1) + if model is DistortionModel.fisheye: + rms, K, D = _calibrate_fisheye(objpoints, imgpoints, (w0, h0)) + else: + rms, K, D = _calibrate_pinhole(objpoints, imgpoints, (w0, h0)) return { "K": K, @@ -628,6 +826,8 @@ def run_calibration( source: Source | str, device_index: int, images: Path | None, + topic: str | None, + topic_timeout_sec: float, cols: int, rows: int, square_size_m: float, @@ -636,9 +836,11 @@ def run_calibration( camera_name: str, target_count: int, no_display: bool, + distortion_model: DistortionModel | str = DistortionModel.plumb_bob, ) -> CalibrationRunResultDict: """Run calibration from the requested frame source and write CameraInfo YAML.""" source_value = Source(source) + model = DistortionModel(distortion_model) if cols < 1: raise ValueError("cols must be >= 1") if rows < 1: @@ -652,6 +854,22 @@ def run_calibration( frames = load_frames_from_folder(str(images)) pattern_hint = None image_points_hint = None + elif source_value is Source.topic: + if topic is None: + raise ValueError( + "--topic is required when --source topic (e.g. --topic jpeg_lcm:/color_image)" + ) + capture = _capture_frames_from_topic( + topic, + target_count, + cols, + rows, + no_display=no_display, + timeout_sec=topic_timeout_sec, + ) + frames = capture.frames + pattern_hint = capture.pattern + image_points_hint = capture.image_points else: capture = _capture_frames_from_webcam( device_index, @@ -671,6 +889,7 @@ def run_calibration( square_size_m, pattern_hint=pattern_hint, image_points_hint=image_points_hint, + distortion_model=model, ) result: CalibrationRunResultDict = { "K": cal["K"], @@ -692,25 +911,47 @@ def run_calibration( camera_name=camera_name, K=np.asarray(result["K"], dtype=np.float64), D=np.asarray(result["D"], dtype=np.float64), + distortion_model=model.to_ros_name(), ) result["out_path"] = out if preview_out is not None: preview_out.parent.mkdir(parents=True, exist_ok=True) pattern_cols, pattern_rows = result["pattern_size"] - write_preview_overlay_png(frames, int(pattern_cols), int(pattern_rows), preview_out) - result["preview_path"] = preview_out + # Preview is best-effort: a chessboard-detection failure here must not mask + # the fact that the YAML was already written above. + try: + write_preview_overlay_png(frames, int(pattern_cols), int(pattern_rows), preview_out) + result["preview_path"] = preview_out + except ValueError as exc: + warnings.warn( + f"Preview PNG skipped ({exc}). Camera info YAML was still written to {out}.", + stacklevel=2, + ) return result @app.command() def calibrate( - source: Source = typer.Option(..., "--source", help="Frame source: webcam or folder"), + source: Source = typer.Option(..., "--source", help="Frame source: webcam, folder, or topic"), device_index: int = typer.Option(0, "--device-index", help="Webcam device index"), images: Path | None = typer.Option( None, "--images", help="Directory of calibration images for --source folder" ), + topic: str | None = typer.Option( + None, + "--topic", + help=( + "Pubsub URI for --source topic (proto:channel), " + "e.g. 'jpeg_lcm:/color_image' or 'pshm:color_image'." + ), + ), + topic_timeout_sec: float = typer.Option( + 60.0, + "--topic-timeout-sec", + help="Abort --source topic if no frames arrive within this many seconds.", + ), cols: int = typer.Option(..., "--cols", help="Inner chessboard corner columns"), rows: int = typer.Option(..., "--rows", help="Inner chessboard corner rows"), square_size_m: float = typer.Option( @@ -723,6 +964,15 @@ def calibrate( camera_name: str = typer.Option("webcam", "--camera-name", help="Camera name in YAML"), target_count: int = typer.Option(20, "--target-count", help="Accepted webcam frame count"), no_display: bool = typer.Option(False, "--no-display", help="Disable OpenCV preview windows"), + distortion_model: DistortionModel = typer.Option( + DistortionModel.plumb_bob, + "--distortion-model", + help=( + "Lens model: 'plumb_bob' (cv2.calibrateCamera, 5 coeffs) for near-pinhole " + "lenses, or 'fisheye' (cv2.fisheye.calibrate, 4 coeffs) for wide-angle / " + "fisheye lenses. Fisheye writes ROS 'equidistant' to the YAML." + ), + ), ) -> None: """Calibrate camera intrinsics and write ROS CameraInfo YAML.""" if preview_out is not None and out is None: @@ -733,6 +983,8 @@ def calibrate( source=source, device_index=device_index, images=images, + topic=topic, + topic_timeout_sec=topic_timeout_sec, cols=cols, rows=rows, square_size_m=square_size_m, @@ -741,6 +993,7 @@ def calibrate( camera_name=camera_name, target_count=target_count, no_display=no_display, + distortion_model=distortion_model, ) except (ValueError, RuntimeError) as exc: raise typer.BadParameter(str(exc)) from exc diff --git a/dimos/utils/cli/cameracalibrate/test_cameracalibrate.py b/dimos/utils/cli/cameracalibrate/test_cameracalibrate.py index 0522b44e23..af90c57009 100644 --- a/dimos/utils/cli/cameracalibrate/test_cameracalibrate.py +++ b/dimos/utils/cli/cameracalibrate/test_cameracalibrate.py @@ -25,8 +25,10 @@ from dimos.msgs.sensor_msgs.CameraInfo import CameraInfo as DimosCameraInfo from dimos.perception.common.utils import load_camera_info, load_camera_info_opencv from dimos.utils.cli.cameracalibrate.cameracalibrate import ( + DistortionModel, app, calibrate_from_frames, + capture_frames_from_topic, capture_frames_from_webcam, find_chessboard_corners, load_frames_from_folder, @@ -182,6 +184,8 @@ def test_cli_help_lists_cameracalibrate_flags() -> None: "--source", "--device-index", "--images", + "--topic", + "--topic-timeout-sec", "--cols", "--rows", "--square-size-m", @@ -189,6 +193,7 @@ def test_cli_help_lists_cameracalibrate_flags() -> None: "--camera-name", "--target-count", "--no-display", + "--distortion-model", ]: assert flag in output_plain @@ -434,6 +439,171 @@ def test_opencv_video_capture_device_zero_opens_when_camera_available() -> None: cap.release() +class _FakeTopicTransport: + """Stand-in for a started ``PubSubTransport`` used by topic-source tests.""" + + def __init__(self) -> None: + self.stopped = False + + def stop(self) -> None: + self.stopped = True + + +def _make_subscribe_pubsub_uri_stub( + fire_with: object | None, + *, + record: dict[str, object] | None = None, +): + """Return a fake ``subscribe_pubsub_uri`` that optionally fires the cb once.""" + + def _stub(uri, callback, *, msg_type=None): # type: ignore[no-untyped-def] + if record is not None: + record["uri"] = uri + record["msg_type"] = msg_type + transport = _FakeTopicTransport() + if fire_with is not None: + callback(fire_with) + unsubscribed: dict[str, bool] = {"called": False} + + def _unsub() -> None: + unsubscribed["called"] = True + + if record is not None: + record["unsub_state"] = unsubscribed + return transport, _unsub + + return _stub + + +def test_capture_frames_from_topic_mocked_space_fills_target( + monkeypatch: pytest.MonkeyPatch, +) -> None: + """SPACE accepts frames delivered over a fake pubsub subscription.""" + from dimos.msgs.sensor_msgs.Image import Image + + cols, rows = 9, 6 + gray = _synthetic_chessboard_gray(640, 480, cols, rows, square_px=40) + bgr = cv2.cvtColor(gray, cv2.COLOR_GRAY2BGR) + image_msg = Image.from_opencv(bgr) + + record: dict[str, object] = {} + monkeypatch.setattr( + "dimos.protocol.pubsub.registry.subscribe_pubsub_uri", + _make_subscribe_pubsub_uri_stub(fire_with=image_msg, record=record), + ) + + keys_iter = iter([ord(" ")] * 3) + + def _fake_wait_key(_delay: int = 0) -> int: + try: + return next(keys_iter) + except StopIteration: + return 0 + + monkeypatch.setattr(cv2, "waitKey", _fake_wait_key) + + out = capture_frames_from_topic( + "jpeg_lcm:/color_image", + 3, + cols, + rows, + no_display=True, + ) + assert len(out) == 3 + assert all(np.array_equal(f, bgr) for f in out) + assert record["uri"] == "jpeg_lcm:/color_image" + assert record["msg_type"] is Image + assert record["unsub_state"]["called"] is True # type: ignore[index] + + +def test_capture_frames_from_topic_no_frames_within_timeout_raises( + monkeypatch: pytest.MonkeyPatch, +) -> None: + """Timeout fires if the subscription never delivers a frame.""" + monkeypatch.setattr( + "dimos.protocol.pubsub.registry.subscribe_pubsub_uri", + _make_subscribe_pubsub_uri_stub(fire_with=None), + ) + monkeypatch.setattr(cv2, "waitKey", lambda _delay=0: 0) + + with pytest.raises(RuntimeError, match="No frames received"): + capture_frames_from_topic( + "lcm:/never_published", + 1, + 9, + 6, + no_display=True, + timeout_sec=0.05, + ) + + +def test_cli_topic_source_uri_passes_through( + monkeypatch: pytest.MonkeyPatch, + tmp_path: Path, +) -> None: + """``--source topic --topic `` forwards the URI verbatim to the registry.""" + from dimos.msgs.sensor_msgs.Image import Image + + cols, rows = 9, 6 + gray = _synthetic_chessboard_gray(640, 480, cols, rows, square_px=40) + bgr = cv2.cvtColor(gray, cv2.COLOR_GRAY2BGR) + image_msg = Image.from_opencv(bgr) + + record: dict[str, object] = {} + monkeypatch.setattr( + "dimos.protocol.pubsub.registry.subscribe_pubsub_uri", + _make_subscribe_pubsub_uri_stub(fire_with=image_msg, record=record), + ) + monkeypatch.setattr(cv2, "waitKey", lambda _delay=0: ord(" ")) + + out = tmp_path / "camera_info.yaml" + result = CliRunner().invoke( + app, + [ + "--source", + "topic", + "--topic", + "jpeg_lcm:/color_image", + "--cols", + "9", + "--rows", + "6", + "--square-size-m", + "0.025", + "--target-count", + "1", + "--out", + str(out), + "--no-display", + ], + ) + + assert result.exit_code == 0, result.output + assert record["uri"] == "jpeg_lcm:/color_image" + assert out.exists() + + +def test_cli_topic_source_without_topic_flag_is_rejected() -> None: + """``--source topic`` without ``--topic`` should fail with a helpful message.""" + result = CliRunner().invoke( + app, + [ + "--source", + "topic", + "--cols", + "9", + "--rows", + "6", + "--square-size-m", + "0.025", + "--no-display", + ], + ) + assert result.exit_code != 0 + output_plain = re.sub(r"\x1b\[[0-9;]*m", "", result.output) + assert "--topic is required" in output_plain + + def test_load_frames_from_folder_count_order_and_pixels(tmp_path: Path) -> None: """Sorted ``*.png`` / ``*.jpg`` / ``*.jpeg``; correct count and load order.""" h, w = 24, 32 @@ -497,6 +667,149 @@ def test_calibrate_from_frames_accepts_square_count_request() -> None: assert out["pattern_label"] == "requested square count" +def _synthetic_fisheye_image_points( + *, + cols: int = 9, + rows: int = 6, + width: int = 1280, + height: int = 720, + square_size_m: float = 0.025, + count: int = 15, + K_true: np.ndarray | None = None, + D_true: np.ndarray | None = None, +) -> tuple[list[np.ndarray], list[np.ndarray], np.ndarray, np.ndarray]: + """Project a flat chessboard through a known fisheye model. + + Returns ``(dummy_frames, image_points_hint, K_true, D_true)``: the frames are + just zeros sized correctly so ``calibrate_from_frames`` accepts them; the + image-point hints carry the synthetic projections so the solver can run + without a real corner detector. + """ + if K_true is None: + K_true = np.array( + [[400.0, 0.0, width / 2.0], [0.0, 400.0, height / 2.0], [0.0, 0.0, 1.0]], + dtype=np.float64, + ) + if D_true is None: + D_true = np.array([-0.05, 0.01, 0.0, 0.0], dtype=np.float64) + + objp = np.zeros((rows * cols, 1, 3), dtype=np.float32) + objp[:, 0, :2] = np.mgrid[0:cols, 0:rows].T.reshape(-1, 2).astype(np.float32) + objp *= float(square_size_m) + + rng = np.random.default_rng(0) + dummy_frames: list[np.ndarray] = [] + image_points_hint: list[np.ndarray] = [] + margin_px = 20 # keep projections strictly inside frame so the solver is well-conditioned + while len(dummy_frames) < count: + rvec = rng.uniform(-0.25, 0.25, size=3).astype(np.float64).reshape(1, 1, 3) + tvec = np.array( + [ + rng.uniform(-0.03, 0.03), + rng.uniform(-0.03, 0.03), + rng.uniform(0.45, 0.65), + ], + dtype=np.float64, + ).reshape(1, 1, 3) + imgpts, _ = cv2.fisheye.projectPoints(objp, rvec, tvec, K_true, D_true) + pts = np.asarray(imgpts, dtype=np.float64).reshape(-1, 2) + if ( + pts[:, 0].min() < margin_px + or pts[:, 0].max() > width - margin_px + or pts[:, 1].min() < margin_px + or pts[:, 1].max() > height - margin_px + ): + continue + image_points_hint.append(np.asarray(imgpts, dtype=np.float32).reshape(-1, 1, 2)) + dummy_frames.append(np.zeros((height, width), dtype=np.uint8)) + return dummy_frames, image_points_hint, K_true, D_true + + +def test_calibrate_from_frames_fisheye_recovers_K_near_truth_and_emits_four_coeffs() -> None: + """Synthetic fisheye projections recover ``K`` close to truth and yield 4 dist coeffs.""" + cols, rows = 9, 6 + width, height = 1280, 720 + square_size_m = 0.025 + frames, image_points, K_true, _D_true = _synthetic_fisheye_image_points( + cols=cols, + rows=rows, + width=width, + height=height, + square_size_m=square_size_m, + count=15, + ) + + out = calibrate_from_frames( + frames, + cols, + rows, + square_size_m, + pattern_hint=(cols, rows, "requested inner corners"), + image_points_hint=image_points, + distortion_model=DistortionModel.fisheye, + ) + + assert out["n_used"] == 15 + assert out["image_size"] == (width, height) + + K_est = np.asarray(out["K"], dtype=np.float64).reshape(3, 3) + # Fisheye solve from synthetic projections should land within ~5% on fx/fy + # and within a couple of pixels on the principal point. + rel_focal = max( + abs(K_est[0, 0] - K_true[0, 0]) / K_true[0, 0], + abs(K_est[1, 1] - K_true[1, 1]) / K_true[1, 1], + ) + assert rel_focal < 0.05, f"focal length recovery off by {rel_focal:.3%}" + assert abs(K_est[0, 2] - K_true[0, 2]) < 5.0 + assert abs(K_est[1, 2] - K_true[1, 2]) < 5.0 + + D_est = np.asarray(out["D"], dtype=np.float64).ravel() + assert D_est.shape == (4,), "fisheye writes 4 distortion coefficients" + + +def test_cli_distortion_model_fisheye_writes_equidistant_yaml_and_four_coeffs( + tmp_path: Path, +) -> None: + """``--distortion-model fisheye`` produces a YAML with the ROS-canonical name.""" + cols, rows = 9, 6 + frames, image_points, _K_true, _D_true = _synthetic_fisheye_image_points( + cols=cols, rows=rows, count=15 + ) + images_dir = tmp_path / "fisheye_frames" + images_dir.mkdir() + for i, frame in enumerate(frames): + assert cv2.imwrite(str(images_dir / f"{i:02d}.png"), frame) + + # The folder source has no chessboard corners in the synthetic dummies, so route + # through calibrate_from_frames directly to exercise the YAML emit path. + out_path = tmp_path / "fisheye.yaml" + cal = calibrate_from_frames( + frames, + cols, + rows, + 0.025, + pattern_hint=(cols, rows, "requested inner corners"), + image_points_hint=image_points, + distortion_model=DistortionModel.fisheye, + ) + write_camera_info_yaml( + str(out_path), + image_width=int(cal["image_size"][0]), + image_height=int(cal["image_size"][1]), + camera_name="fisheye_test", + K=np.asarray(cal["K"], dtype=np.float64), + D=np.asarray(cal["D"], dtype=np.float64), + distortion_model=DistortionModel.fisheye.to_ros_name(), + ) + + import yaml as _yaml + + payload = _yaml.safe_load(out_path.read_text(encoding="utf-8")) + assert payload["distortion_model"] == "equidistant" + assert payload["distortion_coefficients"]["cols"] == 4 + assert len(payload["distortion_coefficients"]["data"]) == 4 + + def test_write_camera_info_yaml_round_trip_matches_k_d_size_and_model(tmp_path: Path) -> None: K = np.array([[500.0, 0.0, 320.0], [0.0, 510.0, 240.0], [0.0, 0.0, 1.0]]) D = np.array([-0.1, 0.05, 0.0, 0.0, 0.0]) diff --git a/docs/usage/camera_calibration.md b/docs/usage/camera_calibration.md index 7b79257aed..928f7d4218 100644 --- a/docs/usage/camera_calibration.md +++ b/docs/usage/camera_calibration.md @@ -52,9 +52,43 @@ uv run dimos cameracalibrate --source webcam --device-index 0 --cols 8 --rows 6 uv run dimos cameracalibrate --source folder --images ./capture/ --cols 8 --rows 6 --square-size-m 0.02485 --out ./camera_info.yaml ./camera_info.preview.png ``` +**Topic (live pubsub stream).** Subscribe to a camera that is already publishing over the dimos pubsub bus — for example a robot blueprint that's currently running — instead of opening a local webcam device. The same interactive UX applies: press **Space** to accept a frame, **q** to quit early, stop after `--target-count` (default 20). The publisher must emit `sensor_msgs.Image`; the calibration script normalizes to BGR via `Image.to_opencv()`. + +```bash +uv run dimos cameracalibrate --source topic --topic "jpeg_lcm:/color_image" --cols 8 --rows 6 --square-size-m 0.02485 --out ./camera_info.yaml ./camera_info.preview.png +``` + +`--topic` is a single URI `:` from the pubsub registry (`dimos.protocol.pubsub.registry`). Pick the proto that matches how the publisher transports the image: + +- `lcm:/color_image` — standard typed LCM stream. +- `jpeg_lcm:/color_image` — Go2 `smart` blueprint and other JPEG-LCM publishers. +- `pshm:color_image` — Go2 `basic` blueprint (pickled shared memory). +- `shm` / `jpeg_shm` / `plcm` are also accepted for niche cases. + +The optional `#` URI suffix forwards a fully-qualified message name to the registry (e.g. `lcm:/color_image#sensor_msgs.Image`); when omitted, the calibration CLI passes `sensor_msgs.Image` for typed protos. Pickled / self-describing protos (`plcm`, `pshm`, ...) ignore the type. + +If the topic stays silent, `--topic-timeout-sec` (default 60) aborts the run instead of hanging the terminal. Increase it if your publisher is slow to start. + +## Distortion model: pinhole vs fisheye + +`--distortion-model` selects the lens model the solver uses. Default is `plumb_bob`; pass `--distortion-model fisheye` for genuine wide-angle / fisheye lenses (e.g. the Go2 front camera). + +- `plumb_bob` — `cv2.calibrateCamera` with the 5-coefficient radial-tangential model. Right for near-pinhole lenses (typical webcams, narrow-FOV USB cameras). YAML emits `distortion_model: plumb_bob`. +- `fisheye` — `cv2.fisheye.calibrate` with the 4-coefficient Kannala-Brandt model. YAML emits `distortion_model: equidistant` (the ROS-canonical name). Use this whenever the lens has noticeable barrel distortion or HFOV beyond roughly 100°. + +How to tell you picked the wrong model: solver "succeeds" but the recovered `K` and `D` are nonsense. Plumb-bob fit to a fisheye lens typically produces inflated focal lengths and `k` coefficients far outside the usual `[-0.5, 0.5]` range (you'll see numbers like `k1 ≈ -1.6, k2 ≈ 4.7`). Fisheye fit to a near-pinhole lens just over-parametrises and behaves similarly. When in doubt, look at the printed focal length vs the lens's nominal FOV — `fx ≈ width / (2 · tan(HFOV/2))` is a useful sanity check. + +```bash +uv run dimos cameracalibrate --source topic --topic "lcm:/color_image" \ + --distortion-model fisheye \ + --cols 8 --rows 6 --square-size-m 0.02485 --out ./camera_info.yaml +``` + +Downstream consumers that undistort or project points must branch on `distortion_model`; raw `K` works for either model, but anything that touches `D` (e.g. `cv2.undistort` vs `cv2.fisheye.undistortImage`) needs to pick the matching OpenCV function. + Output files are explicit. Pass `--out ./camera_info.yaml` to write the ROS CameraInfo YAML. Pass a preview PNG path immediately after it to write a corner-overlay preview, for example `--out ./camera_info.yaml ./camera_info.preview.png`. If you omit both output paths, the command still runs calibration and prints RMS, but does not write YAML or PNG files. A preview PNG path without `--out` is rejected. -Optional flags (same for both sources): `--target-count` (webcam only; default 20), `--camera-name` (default `webcam`), `--no-display` (no OpenCV window; for headless or automation), `--debug` (write detailed capture logs to the system temp directory). +Optional flags (shared across sources): `--target-count` (webcam/topic; default 20), `--camera-name` (default `webcam`), `--no-display` (no OpenCV window; for headless or automation), `--debug` (write detailed capture logs to the system temp directory). On success the process prints the calibration RMS, the detected pattern, and any output paths you requested. Example: diff --git a/uv.lock b/uv.lock index 39aa2b2984..80175e4bf3 100644 --- a/uv.lock +++ b/uv.lock @@ -1,5 +1,5 @@ version = 1 -revision = 3 +revision = 2 requires-python = ">=3.10" resolution-markers = [ "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'darwin'", @@ -10713,12 +10713,19 @@ name = "triton" version = "3.6.0" source = { registry = "https://pypi.org/simple" } wheels = [ + { url = "https://files.pythonhosted.org/packages/44/ba/b1b04f4b291a3205d95ebd24465de0e5bf010a2df27a4e58a9b5f039d8f2/triton-3.6.0-cp310-cp310-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:6c723cfb12f6842a0ae94ac307dba7e7a44741d720a40cf0e270ed4a4e3be781", size = 175972180, upload-time = "2026-01-20T16:15:53.664Z" }, { url = "https://files.pythonhosted.org/packages/8c/f7/f1c9d3424ab199ac53c2da567b859bcddbb9c9e7154805119f8bd95ec36f/triton-3.6.0-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a6550fae429e0667e397e5de64b332d1e5695b73650ee75a6146e2e902770bea", size = 188105201, upload-time = "2026-01-20T16:00:29.272Z" }, + { url = "https://files.pythonhosted.org/packages/0f/2c/96f92f3c60387e14cc45aed49487f3486f89ea27106c1b1376913c62abe4/triton-3.6.0-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:49df5ef37379c0c2b5c0012286f80174fcf0e073e5ade1ca9a86c36814553651", size = 176081190, upload-time = "2026-01-20T16:16:00.523Z" }, { url = "https://files.pythonhosted.org/packages/e0/12/b05ba554d2c623bffa59922b94b0775673de251f468a9609bc9e45de95e9/triton-3.6.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:e8e323d608e3a9bfcc2d9efcc90ceefb764a82b99dea12a86d643c72539ad5d3", size = 188214640, upload-time = "2026-01-20T16:00:35.869Z" }, + { url = "https://files.pythonhosted.org/packages/17/5d/08201db32823bdf77a0e2b9039540080b2e5c23a20706ddba942924ebcd6/triton-3.6.0-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:374f52c11a711fd062b4bfbb201fd9ac0a5febd28a96fb41b4a0f51dde3157f4", size = 176128243, upload-time = "2026-01-20T16:16:07.857Z" }, { url = "https://files.pythonhosted.org/packages/ab/a8/cdf8b3e4c98132f965f88c2313a4b493266832ad47fb52f23d14d4f86bb5/triton-3.6.0-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:74caf5e34b66d9f3a429af689c1c7128daba1d8208df60e81106b115c00d6fca", size = 188266850, upload-time = "2026-01-20T16:00:43.041Z" }, + { url = "https://files.pythonhosted.org/packages/3c/12/34d71b350e89a204c2c7777a9bba0dcf2f19a5bfdd70b57c4dbc5ffd7154/triton-3.6.0-cp313-cp313-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:448e02fe6dc898e9e5aa89cf0ee5c371e99df5aa5e8ad976a80b93334f3494fd", size = 176133521, upload-time = "2026-01-20T16:16:13.321Z" }, { url = "https://files.pythonhosted.org/packages/f9/0b/37d991d8c130ce81a8728ae3c25b6e60935838e9be1b58791f5997b24a54/triton-3.6.0-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:10c7f76c6e72d2ef08df639e3d0d30729112f47a56b0c81672edc05ee5116ac9", size = 188289450, upload-time = "2026-01-20T16:00:49.136Z" }, + { url = "https://files.pythonhosted.org/packages/ce/4e/41b0c8033b503fd3cfcd12392cdd256945026a91ff02452bef40ec34bee7/triton-3.6.0-cp313-cp313t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:1722e172d34e32abc3eb7711d0025bb69d7959ebea84e3b7f7a341cd7ed694d6", size = 176276087, upload-time = "2026-01-20T16:16:18.989Z" }, { url = "https://files.pythonhosted.org/packages/35/f8/9c66bfc55361ec6d0e4040a0337fb5924ceb23de4648b8a81ae9d33b2b38/triton-3.6.0-cp313-cp313t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:d002e07d7180fd65e622134fbd980c9a3d4211fb85224b56a0a0efbd422ab72f", size = 188400296, upload-time = "2026-01-20T16:00:56.042Z" }, + { url = "https://files.pythonhosted.org/packages/49/55/5ecf0dcaa0f2fbbd4420f7ef227ee3cb172e91e5fede9d0ecaddc43363b4/triton-3.6.0-cp314-cp314-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:ef5523241e7d1abca00f1d240949eebdd7c673b005edbbce0aca95b8191f1d43", size = 176138577, upload-time = "2026-01-20T16:16:25.426Z" }, { url = "https://files.pythonhosted.org/packages/df/3d/9e7eee57b37c80cec63322c0231bb6da3cfe535a91d7a4d64896fcb89357/triton-3.6.0-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a17a5d5985f0ac494ed8a8e54568f092f7057ef60e1b0fa09d3fd1512064e803", size = 188273063, upload-time = "2026-01-20T16:01:07.278Z" }, + { url = "https://files.pythonhosted.org/packages/48/db/56ee649cab5eaff4757541325aca81f52d02d4a7cd3506776cad2451e060/triton-3.6.0-cp314-cp314t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0b3a97e8ed304dfa9bd23bb41ca04cdf6b2e617d5e782a8653d616037a5d537d", size = 176274804, upload-time = "2026-01-20T16:16:31.528Z" }, { url = "https://files.pythonhosted.org/packages/f6/56/6113c23ff46c00aae423333eb58b3e60bdfe9179d542781955a5e1514cb3/triton-3.6.0-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:46bd1c1af4b6704e554cad2eeb3b0a6513a980d470ccfa63189737340c7746a7", size = 188397994, upload-time = "2026-01-20T16:01:14.236Z" }, ]