From 9ae0b86428c19ac33748c4e112d53376ccfc4fa6 Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Sat, 3 Jan 2026 20:55:40 -0800 Subject: [PATCH 01/19] added rate limiting and backpressure to pointcloud publishing CI code cleanup updated ZED module to the same standard as realsense CI code cleanup fixed stash's comments CI code cleanup mypy fixes + comments removed property of camera_info should pass CI now added detection3d pointcloud types from depth image added yoloe support and 3D object segmentation CI code cleanup use yoloe-s instead for nuc CI code cleanup removed deprecated perception code some pointcloud color changes major refactor and added object class for object scene registration CI code cleanup refactored, added objectDB for persistent object memory CI code cleanup made objectDB a normal class instead of a module CI code cleanup revert to dev reverted more files CI code cleanup completely refactored object scene registration to work natively in dimos instead of using ROS as transport. Made everything super clean and working CI code cleanup bug fixed + use yoloe-l by default added yolo object exlusion list CI code cleanup added zed camera to the object registration demo CI code cleanup added image and pointclou2 fixes and as_numpy function working promptable object scene registration CI code cleanup bug fixes bug fix + remove ros imports should not fail CI now CI code cleanup more CI fixes, somehow local CI did not catch changed prompt fixed bug CI code cleanup reverted some changes Cleanup very dead code and fixed mypy errors CI code cleanup fixed more mypy CI code cleanup --- data/.lfs/models_edgetam.tar.gz | 3 + data/.lfs/models_yoloe.tar.gz | 3 + dimos/manipulation/manip_aio_pipeline.py | 592 --------- dimos/manipulation/manip_aio_processer.py | 422 ------- dimos/manipulation/manipulation_interface.py | 3 +- .../visual_servoing/detection3d.py | 302 ----- .../visual_servoing/manipulation_module.py | 951 -------------- dimos/manipulation/visual_servoing/pbvs.py | 488 -------- dimos/manipulation/visual_servoing/utils.py | 801 ------------ dimos/models/vl/base.py | 2 +- dimos/models/vl/moondream.py | 2 +- dimos/models/vl/moondream_hosted.py | 2 +- dimos/msgs/geometry_msgs/Quaternion.py | 14 + dimos/msgs/sensor_msgs/Image.py | 27 + dimos/msgs/vision_msgs/Detection2D.py | 27 + dimos/msgs/vision_msgs/Detection3D.py | 117 ++ dimos/msgs/vision_msgs/Detection3DArray.py | 57 +- dimos/msgs/vision_msgs/__init__.py | 11 +- dimos/perception/common/__init__.py | 2 - .../perception/common/detection2d_tracker.py | 396 ------ dimos/perception/common/export_tensorrt.py | 58 - dimos/perception/common/ibvs.py | 280 ----- .../demo_object_scene_registration.py | 41 + dimos/perception/detection/detectors/detic.py | 426 ------- .../detection/detectors/person/yolo.py | 6 +- dimos/perception/detection/detectors/types.py | 3 +- dimos/perception/detection/detectors/yolo.py | 4 +- dimos/perception/detection/detectors/yoloe.py | 177 +++ dimos/perception/detection/module2D.py | 8 +- dimos/perception/detection/module3D.py | 8 +- dimos/perception/detection/objectDB.py | 306 +++++ dimos/perception/detection/person_tracker.py | 9 +- dimos/perception/detection/reid/module.py | 8 +- dimos/perception/detection/reid/type.py | 3 +- .../detection/type/detection2d/__init__.py | 2 + .../type/detection2d/imageDetections2D.py | 103 +- .../detection/type/detection2d/seg.py | 204 +++ .../detection/type/detection3d/base.py | 9 +- .../detection/type/detection3d/bbox.py | 44 +- .../type/detection3d/imageDetections3DPC.py | 165 ++- .../detection/type/detection3d/object.py | 377 ++++++ .../detection/type/detection3d/pointcloud.py | 4 +- dimos/perception/detection2d/utils.py | 309 ----- dimos/perception/grasp_generation/__init__.py | 1 - .../grasp_generation/grasp_generation.py | 233 ---- dimos/perception/grasp_generation/utils.py | 529 -------- dimos/perception/object_detection_stream.py | 322 ----- dimos/perception/object_scene_registration.py | 259 ++++ dimos/perception/object_tracker.py | 12 +- dimos/perception/object_tracker_3d.py | 13 +- dimos/perception/person_tracker.py | 262 ---- dimos/perception/pointcloud/__init__.py | 3 - dimos/perception/pointcloud/cuboid_fit.py | 420 ------- .../pointcloud/pointcloud_filtering.py | 370 ------ .../pointcloud/test_pointcloud_filtering.py | 263 ---- dimos/perception/pointcloud/utils.py | 1113 ----------------- dimos/perception/segmentation/__init__.py | 2 - .../segmentation/config/custom_tracker.yaml | 21 - .../perception/segmentation/image_analyzer.py | 162 --- dimos/perception/segmentation/sam_2d_seg.py | 366 ------ .../segmentation/test_sam_2d_seg.py | 210 ---- dimos/perception/segmentation/utils.py | 343 ----- dimos/robot/agilex/README.md | 371 ------ dimos/robot/agilex/README_CN.md | 465 ------- dimos/robot/agilex/piper_arm.py | 181 --- dimos/robot/agilex/run.py | 190 --- dimos/robot/all_blueprints.py | 7 +- 67 files changed, 1971 insertions(+), 10923 deletions(-) create mode 100644 data/.lfs/models_edgetam.tar.gz create mode 100644 data/.lfs/models_yoloe.tar.gz delete mode 100644 dimos/manipulation/manip_aio_pipeline.py delete mode 100644 dimos/manipulation/manip_aio_processer.py delete mode 100644 dimos/manipulation/visual_servoing/detection3d.py delete mode 100644 dimos/manipulation/visual_servoing/manipulation_module.py delete mode 100644 dimos/manipulation/visual_servoing/pbvs.py delete mode 100644 dimos/manipulation/visual_servoing/utils.py create mode 100644 dimos/msgs/vision_msgs/Detection2D.py create mode 100644 dimos/msgs/vision_msgs/Detection3D.py delete mode 100644 dimos/perception/common/detection2d_tracker.py delete mode 100644 dimos/perception/common/export_tensorrt.py delete mode 100644 dimos/perception/common/ibvs.py create mode 100644 dimos/perception/demo_object_scene_registration.py delete mode 100644 dimos/perception/detection/detectors/detic.py create mode 100644 dimos/perception/detection/detectors/yoloe.py create mode 100644 dimos/perception/detection/objectDB.py create mode 100644 dimos/perception/detection/type/detection2d/seg.py create mode 100644 dimos/perception/detection/type/detection3d/object.py delete mode 100644 dimos/perception/detection2d/utils.py delete mode 100644 dimos/perception/grasp_generation/__init__.py delete mode 100644 dimos/perception/grasp_generation/grasp_generation.py delete mode 100644 dimos/perception/grasp_generation/utils.py delete mode 100644 dimos/perception/object_detection_stream.py create mode 100644 dimos/perception/object_scene_registration.py delete mode 100644 dimos/perception/person_tracker.py delete mode 100644 dimos/perception/pointcloud/__init__.py delete mode 100644 dimos/perception/pointcloud/cuboid_fit.py delete mode 100644 dimos/perception/pointcloud/pointcloud_filtering.py delete mode 100644 dimos/perception/pointcloud/test_pointcloud_filtering.py delete mode 100644 dimos/perception/pointcloud/utils.py delete mode 100644 dimos/perception/segmentation/__init__.py delete mode 100644 dimos/perception/segmentation/config/custom_tracker.yaml delete mode 100644 dimos/perception/segmentation/image_analyzer.py delete mode 100644 dimos/perception/segmentation/sam_2d_seg.py delete mode 100644 dimos/perception/segmentation/test_sam_2d_seg.py delete mode 100644 dimos/perception/segmentation/utils.py delete mode 100644 dimos/robot/agilex/README.md delete mode 100644 dimos/robot/agilex/README_CN.md delete mode 100644 dimos/robot/agilex/piper_arm.py delete mode 100644 dimos/robot/agilex/run.py diff --git a/data/.lfs/models_edgetam.tar.gz b/data/.lfs/models_edgetam.tar.gz new file mode 100644 index 0000000000..64baa5d139 --- /dev/null +++ b/data/.lfs/models_edgetam.tar.gz @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:cd452096f91415ce7ca90548a06a87354ccdb19a66925c0242413c80b08f5c57 +size 51988780 diff --git a/data/.lfs/models_yoloe.tar.gz b/data/.lfs/models_yoloe.tar.gz new file mode 100644 index 0000000000..a0870d71d2 --- /dev/null +++ b/data/.lfs/models_yoloe.tar.gz @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7a78e39477667b25c9454f846cd66dc044dd05981b2f7ebb0d331ef3626de9bc +size 184892540 diff --git a/dimos/manipulation/manip_aio_pipeline.py b/dimos/manipulation/manip_aio_pipeline.py deleted file mode 100644 index fe3598ab1e..0000000000 --- a/dimos/manipulation/manip_aio_pipeline.py +++ /dev/null @@ -1,592 +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. - -""" -Asynchronous, reactive manipulation pipeline for realtime detection, filtering, and grasp generation. -""" - -import asyncio -import json -import threading -import time - -import cv2 -import numpy as np -import reactivex as rx -import reactivex.operators as ops -import websockets - -from dimos.perception.common.utils import colorize_depth -from dimos.perception.detection2d.detic_2d_det import ( # type: ignore[import-not-found, import-untyped] - Detic2DDetector, -) -from dimos.perception.grasp_generation.utils import draw_grasps_on_image -from dimos.perception.object_detection_stream import ObjectDetectionStream -from dimos.perception.pointcloud.pointcloud_filtering import PointcloudFiltering -from dimos.perception.pointcloud.utils import create_point_cloud_overlay_visualization -from dimos.utils.logging_config import setup_logger - -logger = setup_logger() - - -class ManipulationPipeline: - """ - Clean separated stream pipeline with frame buffering. - - - Object detection runs independently on RGB stream - - Point cloud processing subscribes to both detection and ZED streams separately - - Simple frame buffering to match RGB+depth+objects - """ - - def __init__( - self, - camera_intrinsics: list[float], # [fx, fy, cx, cy] - min_confidence: float = 0.6, - max_objects: int = 10, - vocabulary: str | None = None, - grasp_server_url: str | None = None, - enable_grasp_generation: bool = False, - ) -> None: - """ - Initialize the manipulation pipeline. - - Args: - camera_intrinsics: [fx, fy, cx, cy] camera parameters - min_confidence: Minimum detection confidence threshold - max_objects: Maximum number of objects to process - vocabulary: Optional vocabulary for Detic detector - grasp_server_url: Optional WebSocket URL for Dimensional Grasp server - enable_grasp_generation: Whether to enable async grasp generation - """ - self.camera_intrinsics = camera_intrinsics - self.min_confidence = min_confidence - - # Grasp generation settings - self.grasp_server_url = grasp_server_url - self.enable_grasp_generation = enable_grasp_generation - - # Asyncio event loop for WebSocket communication - self.grasp_loop = None - self.grasp_loop_thread = None - - # Storage for grasp results and filtered objects - self.latest_grasps: list[dict] = [] # type: ignore[type-arg] # Simplified: just a list of grasps - self.grasps_consumed = False - self.latest_filtered_objects = [] # type: ignore[var-annotated] - self.latest_rgb_for_grasps = None # Store RGB image for grasp overlay - self.grasp_lock = threading.Lock() - - # Track pending requests - simplified to single task - self.grasp_task: asyncio.Task | None = None # type: ignore[type-arg] - - # Reactive subjects for streaming filtered objects and grasps - self.filtered_objects_subject = rx.subject.Subject() # type: ignore[var-annotated] - self.grasps_subject = rx.subject.Subject() # type: ignore[var-annotated] - self.grasp_overlay_subject = rx.subject.Subject() # type: ignore[var-annotated] # Add grasp overlay subject - - # Initialize grasp client if enabled - if self.enable_grasp_generation and self.grasp_server_url: - self._start_grasp_loop() - - # Initialize object detector - self.detector = Detic2DDetector(vocabulary=vocabulary, threshold=min_confidence) - - # Initialize point cloud processor - self.pointcloud_filter = PointcloudFiltering( - color_intrinsics=camera_intrinsics, - depth_intrinsics=camera_intrinsics, # ZED uses same intrinsics - max_num_objects=max_objects, - ) - - logger.info(f"Initialized ManipulationPipeline with confidence={min_confidence}") - - def create_streams(self, zed_stream: rx.Observable) -> dict[str, rx.Observable]: # type: ignore[type-arg] - """ - Create streams using exact old main logic. - """ - # Create ZED streams (from old main) - zed_frame_stream = zed_stream.pipe(ops.share()) - - # RGB stream for object detection (from old main) - video_stream = zed_frame_stream.pipe( - ops.map(lambda x: x.get("rgb") if x is not None else None), # type: ignore[attr-defined] - ops.filter(lambda x: x is not None), - ops.share(), - ) - object_detector = ObjectDetectionStream( - camera_intrinsics=self.camera_intrinsics, - min_confidence=self.min_confidence, - class_filter=None, - detector=self.detector, - video_stream=video_stream, - disable_depth=True, - ) - - # Store latest frames for point cloud processing (from old main) - latest_rgb = None - latest_depth = None - latest_point_cloud_overlay = None - frame_lock = threading.Lock() - - # Subscribe to combined ZED frames (from old main) - def on_zed_frame(zed_data) -> None: # type: ignore[no-untyped-def] - nonlocal latest_rgb, latest_depth - if zed_data is not None: - with frame_lock: - latest_rgb = zed_data.get("rgb") - latest_depth = zed_data.get("depth") - - # Depth stream for point cloud filtering (from old main) - def get_depth_or_overlay(zed_data): # type: ignore[no-untyped-def] - if zed_data is None: - return None - - # Check if we have a point cloud overlay available - with frame_lock: - overlay = latest_point_cloud_overlay - - if overlay is not None: - return overlay - else: - # Return regular colorized depth - return colorize_depth(zed_data.get("depth"), max_depth=10.0) - - depth_stream = zed_frame_stream.pipe( - ops.map(get_depth_or_overlay), ops.filter(lambda x: x is not None), ops.share() - ) - - # Process object detection results with point cloud filtering (from old main) - def on_detection_next(result) -> None: # type: ignore[no-untyped-def] - nonlocal latest_point_cloud_overlay - if result.get("objects"): - # Get latest RGB and depth frames - with frame_lock: - rgb = latest_rgb - depth = latest_depth - - if rgb is not None and depth is not None: - try: - filtered_objects = self.pointcloud_filter.process_images( - rgb, depth, result["objects"] - ) - - if filtered_objects: - # Store filtered objects - with self.grasp_lock: - self.latest_filtered_objects = filtered_objects - self.filtered_objects_subject.on_next(filtered_objects) - - # Create base image (colorized depth) - base_image = colorize_depth(depth, max_depth=10.0) - - # Create point cloud overlay visualization - overlay_viz = create_point_cloud_overlay_visualization( - base_image=base_image, # type: ignore[arg-type] - objects=filtered_objects, # type: ignore[arg-type] - intrinsics=self.camera_intrinsics, # type: ignore[arg-type] - ) - - # Store the overlay for the stream - with frame_lock: - latest_point_cloud_overlay = overlay_viz - - # Request grasps if enabled - if self.enable_grasp_generation and len(filtered_objects) > 0: - # Save RGB image for later grasp overlay - with frame_lock: - self.latest_rgb_for_grasps = rgb.copy() - - task = self.request_scene_grasps(filtered_objects) # type: ignore[arg-type] - if task: - # Check for results after a delay - def check_grasps_later() -> None: - time.sleep(2.0) # Wait for grasp processing - # Wait for task to complete - if hasattr(self, "grasp_task") and self.grasp_task: - try: - self.grasp_task.result( # type: ignore[call-arg] - timeout=3.0 - ) # Get result with timeout - except Exception as e: - logger.warning(f"Grasp task failed or timeout: {e}") - - # Try to get latest grasps and create overlay - with self.grasp_lock: - grasps = self.latest_grasps - - if grasps and hasattr(self, "latest_rgb_for_grasps"): - # Create grasp overlay on the saved RGB image - try: - bgr_image = cv2.cvtColor( # type: ignore[call-overload] - self.latest_rgb_for_grasps, cv2.COLOR_RGB2BGR - ) - result_bgr = draw_grasps_on_image( - bgr_image, - grasps, - self.camera_intrinsics, - max_grasps=-1, # Show all grasps - ) - result_rgb = cv2.cvtColor( - result_bgr, cv2.COLOR_BGR2RGB - ) - - # Emit grasp overlay immediately - self.grasp_overlay_subject.on_next(result_rgb) - - except Exception as e: - logger.error(f"Error creating grasp overlay: {e}") - - # Emit grasps to stream - self.grasps_subject.on_next(grasps) - - threading.Thread(target=check_grasps_later, daemon=True).start() - else: - logger.warning("Failed to create grasp task") - except Exception as e: - logger.error(f"Error in point cloud filtering: {e}") - with frame_lock: - latest_point_cloud_overlay = None - - def on_error(error) -> None: # type: ignore[no-untyped-def] - logger.error(f"Error in stream: {error}") - - def on_completed() -> None: - logger.info("Stream completed") - - def start_subscriptions() -> None: - """Start subscriptions in background thread (from old main)""" - # Subscribe to combined ZED frames - zed_frame_stream.subscribe(on_next=on_zed_frame) - - # Start subscriptions in background thread (from old main) - subscription_thread = threading.Thread(target=start_subscriptions, daemon=True) - subscription_thread.start() - time.sleep(2) # Give subscriptions time to start - - # Subscribe to object detection stream (from old main) - object_detector.get_stream().subscribe( # type: ignore[no-untyped-call] - on_next=on_detection_next, on_error=on_error, on_completed=on_completed - ) - - # Create visualization stream for web interface (from old main) - viz_stream = object_detector.get_stream().pipe( # type: ignore[no-untyped-call] - ops.map(lambda x: x["viz_frame"] if x is not None else None), # type: ignore[index] - ops.filter(lambda x: x is not None), - ) - - # Create filtered objects stream - filtered_objects_stream = self.filtered_objects_subject - - # Create grasps stream - grasps_stream = self.grasps_subject - - # Create grasp overlay subject for immediate emission - grasp_overlay_stream = self.grasp_overlay_subject - - return { - "detection_viz": viz_stream, - "pointcloud_viz": depth_stream, - "objects": object_detector.get_stream().pipe(ops.map(lambda x: x.get("objects", []))), # type: ignore[attr-defined, no-untyped-call] - "filtered_objects": filtered_objects_stream, - "grasps": grasps_stream, - "grasp_overlay": grasp_overlay_stream, - } - - def _start_grasp_loop(self) -> None: - """Start asyncio event loop in a background thread for WebSocket communication.""" - - def run_loop() -> None: - self.grasp_loop = asyncio.new_event_loop() # type: ignore[assignment] - asyncio.set_event_loop(self.grasp_loop) - self.grasp_loop.run_forever() # type: ignore[attr-defined] - - self.grasp_loop_thread = threading.Thread(target=run_loop, daemon=True) # type: ignore[assignment] - self.grasp_loop_thread.start() # type: ignore[attr-defined] - - # Wait for loop to start - while self.grasp_loop is None: - time.sleep(0.01) - - async def _send_grasp_request( - self, - points: np.ndarray, # type: ignore[type-arg] - colors: np.ndarray | None, # type: ignore[type-arg] - ) -> list[dict] | None: # type: ignore[type-arg] - """Send grasp request to Dimensional Grasp server.""" - try: - # Comprehensive client-side validation to prevent server errors - - # Validate points array - if points is None: - logger.error("Points array is None") - return None - if not isinstance(points, np.ndarray): - logger.error(f"Points is not numpy array: {type(points)}") - return None - if points.size == 0: - logger.error("Points array is empty") - return None - if len(points.shape) != 2 or points.shape[1] != 3: - logger.error(f"Points has invalid shape {points.shape}, expected (N, 3)") - return None - if points.shape[0] < 100: # Minimum points for stable grasp detection - logger.error(f"Insufficient points for grasp detection: {points.shape[0]} < 100") - return None - - # Validate and prepare colors - if colors is not None: - if not isinstance(colors, np.ndarray): - colors = None - elif colors.size == 0: - colors = None - elif len(colors.shape) != 2 or colors.shape[1] != 3: - colors = None - elif colors.shape[0] != points.shape[0]: - colors = None - - # If no valid colors, create default colors (required by server) - if colors is None: - # Create default white colors for all points - colors = np.ones((points.shape[0], 3), dtype=np.float32) * 0.5 - - # Ensure data types are correct (server expects float32) - points = points.astype(np.float32) - colors = colors.astype(np.float32) - - # Validate ranges (basic sanity checks) - if np.any(np.isnan(points)) or np.any(np.isinf(points)): - logger.error("Points contain NaN or Inf values") - return None - if np.any(np.isnan(colors)) or np.any(np.isinf(colors)): - logger.error("Colors contain NaN or Inf values") - return None - - # Clamp color values to valid range [0, 1] - colors = np.clip(colors, 0.0, 1.0) - - async with websockets.connect(self.grasp_server_url) as websocket: # type: ignore[arg-type] - request = { - "points": points.tolist(), - "colors": colors.tolist(), # Always send colors array - "lims": [-0.19, 0.12, 0.02, 0.15, 0.0, 1.0], # Default workspace limits - } - - await websocket.send(json.dumps(request)) - - response = await websocket.recv() - grasps = json.loads(response) - - # Handle server response validation - if isinstance(grasps, dict) and "error" in grasps: - logger.error(f"Server returned error: {grasps['error']}") - return None - elif isinstance(grasps, int | float) and grasps == 0: - return None - elif not isinstance(grasps, list): - logger.error( - f"Server returned unexpected response type: {type(grasps)}, value: {grasps}" - ) - return None - elif len(grasps) == 0: - return None - - converted_grasps = self._convert_grasp_format(grasps) - with self.grasp_lock: - self.latest_grasps = converted_grasps - self.grasps_consumed = False # Reset consumed flag - - # Emit to reactive stream - self.grasps_subject.on_next(self.latest_grasps) - - return converted_grasps - except websockets.exceptions.ConnectionClosed as e: - logger.error(f"WebSocket connection closed: {e}") - except websockets.exceptions.WebSocketException as e: - logger.error(f"WebSocket error: {e}") - except json.JSONDecodeError as e: - logger.error(f"Failed to parse server response as JSON: {e}") - except Exception as e: - logger.error(f"Error requesting grasps: {e}") - - return None - - def request_scene_grasps(self, objects: list[dict]) -> asyncio.Task | None: # type: ignore[type-arg] - """Request grasps for entire scene by combining all object point clouds.""" - if not self.grasp_loop or not objects: - return None - - all_points = [] - all_colors = [] - valid_objects = 0 - - for _i, obj in enumerate(objects): - # Validate point cloud data - if "point_cloud_numpy" not in obj or obj["point_cloud_numpy"] is None: - continue - - points = obj["point_cloud_numpy"] - if not isinstance(points, np.ndarray) or points.size == 0: - continue - - # Ensure points have correct shape (N, 3) - if len(points.shape) != 2 or points.shape[1] != 3: - continue - - # Validate colors if present - colors = None - if "colors_numpy" in obj and obj["colors_numpy"] is not None: - colors = obj["colors_numpy"] - if isinstance(colors, np.ndarray) and colors.size > 0: - # Ensure colors match points count and have correct shape - if colors.shape[0] != points.shape[0]: - colors = None # Ignore colors for this object - elif len(colors.shape) != 2 or colors.shape[1] != 3: - colors = None # Ignore colors for this object - - all_points.append(points) - if colors is not None: - all_colors.append(colors) - valid_objects += 1 - - if not all_points: - return None - - try: - combined_points = np.vstack(all_points) - - # Only combine colors if ALL objects have valid colors - combined_colors = None - if len(all_colors) == valid_objects and len(all_colors) > 0: - combined_colors = np.vstack(all_colors) - - # Validate final combined data - if combined_points.size == 0: - logger.warning("Combined point cloud is empty") - return None - - if combined_colors is not None and combined_colors.shape[0] != combined_points.shape[0]: - logger.warning( - f"Color/point count mismatch: {combined_colors.shape[0]} colors vs {combined_points.shape[0]} points, dropping colors" - ) - combined_colors = None - - except Exception as e: - logger.error(f"Failed to combine point clouds: {e}") - return None - - try: - # Check if there's already a grasp task running - if hasattr(self, "grasp_task") and self.grasp_task and not self.grasp_task.done(): - return self.grasp_task - - task = asyncio.run_coroutine_threadsafe( - self._send_grasp_request(combined_points, combined_colors), self.grasp_loop - ) - - self.grasp_task = task - return task - except Exception: - logger.warning("Failed to create grasp task") - return None - - def get_latest_grasps(self, timeout: float = 5.0) -> list[dict] | None: # type: ignore[type-arg] - """Get latest grasp results, waiting for new ones if current ones have been consumed.""" - # Mark current grasps as consumed and get a reference - with self.grasp_lock: - current_grasps = self.latest_grasps - self.grasps_consumed = True - - # If we already have grasps and they haven't been consumed, return them - if current_grasps is not None and not getattr(self, "grasps_consumed", False): - return current_grasps - - # Wait for new grasps - start_time = time.time() - while time.time() - start_time < timeout: - with self.grasp_lock: - # Check if we have new grasps (different from what we marked as consumed) - if self.latest_grasps is not None and not getattr(self, "grasps_consumed", False): - return self.latest_grasps - time.sleep(0.1) # Check every 100ms - - return None # Timeout reached - - def clear_grasps(self) -> None: - """Clear all stored grasp results.""" - with self.grasp_lock: - self.latest_grasps = [] - - def _prepare_colors(self, colors: np.ndarray | None) -> np.ndarray | None: # type: ignore[type-arg] - """Prepare colors array, converting from various formats if needed.""" - if colors is None: - return None - - if colors.max() > 1.0: - colors = colors / 255.0 - - return colors - - def _convert_grasp_format(self, grasps: list[dict]) -> list[dict]: # type: ignore[type-arg] - """Convert Grasp format to our visualization format.""" - converted = [] - - for i, grasp in enumerate(grasps): - rotation_matrix = np.array(grasp.get("rotation_matrix", np.eye(3))) - euler_angles = self._rotation_matrix_to_euler(rotation_matrix) - - converted_grasp = { - "id": f"grasp_{i}", - "score": grasp.get("score", 0.0), - "width": grasp.get("width", 0.0), - "height": grasp.get("height", 0.0), - "depth": grasp.get("depth", 0.0), - "translation": grasp.get("translation", [0, 0, 0]), - "rotation_matrix": rotation_matrix.tolist(), - "euler_angles": euler_angles, - } - converted.append(converted_grasp) - - converted.sort(key=lambda x: x["score"], reverse=True) - - return converted - - def _rotation_matrix_to_euler(self, rotation_matrix: np.ndarray) -> dict[str, float]: # type: ignore[type-arg] - """Convert rotation matrix to Euler angles (in radians).""" - sy = np.sqrt(rotation_matrix[0, 0] ** 2 + rotation_matrix[1, 0] ** 2) - - singular = sy < 1e-6 - - if not singular: - x = np.arctan2(rotation_matrix[2, 1], rotation_matrix[2, 2]) - y = np.arctan2(-rotation_matrix[2, 0], sy) - z = np.arctan2(rotation_matrix[1, 0], rotation_matrix[0, 0]) - else: - x = np.arctan2(-rotation_matrix[1, 2], rotation_matrix[1, 1]) - y = np.arctan2(-rotation_matrix[2, 0], sy) - z = 0 - - return {"roll": x, "pitch": y, "yaw": z} - - def cleanup(self) -> None: - """Clean up resources.""" - if hasattr(self.detector, "cleanup"): - self.detector.cleanup() - - if self.grasp_loop and self.grasp_loop_thread: - self.grasp_loop.call_soon_threadsafe(self.grasp_loop.stop) - self.grasp_loop_thread.join(timeout=1.0) - - if hasattr(self.pointcloud_filter, "cleanup"): - self.pointcloud_filter.cleanup() - logger.info("ManipulationPipeline cleaned up") diff --git a/dimos/manipulation/manip_aio_processer.py b/dimos/manipulation/manip_aio_processer.py deleted file mode 100644 index 71ed42bff3..0000000000 --- a/dimos/manipulation/manip_aio_processer.py +++ /dev/null @@ -1,422 +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. - -""" -Sequential manipulation processor for single-frame processing without reactive streams. -""" - -import time -from typing import Any - -import cv2 -import numpy as np - -from dimos.perception.common.utils import ( - colorize_depth, - combine_object_data, - detection_results_to_object_data, -) -from dimos.perception.detection2d.detic_2d_det import ( # type: ignore[import-not-found, import-untyped] - Detic2DDetector, -) -from dimos.perception.grasp_generation.grasp_generation import HostedGraspGenerator -from dimos.perception.grasp_generation.utils import create_grasp_overlay -from dimos.perception.pointcloud.pointcloud_filtering import PointcloudFiltering -from dimos.perception.pointcloud.utils import ( - create_point_cloud_overlay_visualization, - extract_and_cluster_misc_points, - overlay_point_clouds_on_image, -) -from dimos.perception.segmentation.sam_2d_seg import Sam2DSegmenter -from dimos.utils.logging_config import setup_logger - -logger = setup_logger() - - -class ManipulationProcessor: - """ - Sequential manipulation processor for single-frame processing. - - Processes RGB-D frames through object detection, point cloud filtering, - and grasp generation in a single thread without reactive streams. - """ - - def __init__( - self, - camera_intrinsics: list[float], # [fx, fy, cx, cy] - min_confidence: float = 0.6, - max_objects: int = 20, - vocabulary: str | None = None, - enable_grasp_generation: bool = False, - grasp_server_url: str | None = None, # Required when enable_grasp_generation=True - enable_segmentation: bool = True, - ) -> None: - """ - Initialize the manipulation processor. - - Args: - camera_intrinsics: [fx, fy, cx, cy] camera parameters - min_confidence: Minimum detection confidence threshold - max_objects: Maximum number of objects to process - vocabulary: Optional vocabulary for Detic detector - enable_grasp_generation: Whether to enable grasp generation - grasp_server_url: WebSocket URL for Dimensional Grasp server (required when enable_grasp_generation=True) - enable_segmentation: Whether to enable semantic segmentation - segmentation_model: Segmentation model to use (SAM 2 or FastSAM) - """ - self.camera_intrinsics = camera_intrinsics - self.min_confidence = min_confidence - self.max_objects = max_objects - self.enable_grasp_generation = enable_grasp_generation - self.grasp_server_url = grasp_server_url - self.enable_segmentation = enable_segmentation - - # Validate grasp generation requirements - if enable_grasp_generation and not grasp_server_url: - raise ValueError("grasp_server_url is required when enable_grasp_generation=True") - - # Initialize object detector - self.detector = Detic2DDetector(vocabulary=vocabulary, threshold=min_confidence) - - # Initialize point cloud processor - self.pointcloud_filter = PointcloudFiltering( - color_intrinsics=camera_intrinsics, - depth_intrinsics=camera_intrinsics, # ZED uses same intrinsics - max_num_objects=max_objects, - ) - - # Initialize semantic segmentation - self.segmenter = None - if self.enable_segmentation: - self.segmenter = Sam2DSegmenter( - use_tracker=False, # Disable tracker for simple segmentation - use_analyzer=False, # Disable analyzer for simple segmentation - ) - - # Initialize grasp generator if enabled - self.grasp_generator = None - if self.enable_grasp_generation: - try: - self.grasp_generator = HostedGraspGenerator(server_url=grasp_server_url) # type: ignore[arg-type] - logger.info("Hosted grasp generator initialized successfully") - except Exception as e: - logger.error(f"Failed to initialize hosted grasp generator: {e}") - self.grasp_generator = None - self.enable_grasp_generation = False - - logger.info( - f"Initialized ManipulationProcessor with confidence={min_confidence}, " - f"grasp_generation={enable_grasp_generation}" - ) - - def process_frame( - self, - rgb_image: np.ndarray, # type: ignore[type-arg] - depth_image: np.ndarray, # type: ignore[type-arg] - generate_grasps: bool | None = None, - ) -> dict[str, Any]: - """ - Process a single RGB-D frame through the complete pipeline. - - Args: - rgb_image: RGB image (H, W, 3) - depth_image: Depth image (H, W) in meters - generate_grasps: Override grasp generation setting for this frame - - Returns: - Dictionary containing: - - detection_viz: Visualization of object detection - - pointcloud_viz: Visualization of point cloud overlay - - segmentation_viz: Visualization of semantic segmentation (if enabled) - - detection2d_objects: Raw detection results as ObjectData - - segmentation2d_objects: Raw segmentation results as ObjectData (if enabled) - - detected_objects: Detection (Object Detection) objects with point clouds filtered - - all_objects: Combined objects with intelligent duplicate removal - - full_pointcloud: Complete scene point cloud (if point cloud processing enabled) - - misc_clusters: List of clustered background/miscellaneous point clouds (DBSCAN) - - misc_voxel_grid: Open3D voxel grid approximating all misc/background points - - misc_pointcloud_viz: Visualization of misc/background cluster overlay - - grasps: Grasp results (list of dictionaries, if enabled) - - grasp_overlay: Grasp visualization overlay (if enabled) - - processing_time: Total processing time - """ - start_time = time.time() - results = {} - - try: - # Step 1: Object Detection - step_start = time.time() - detection_results = self.run_object_detection(rgb_image) - results["detection2d_objects"] = detection_results.get("objects", []) - results["detection_viz"] = detection_results.get("viz_frame") - detection_time = time.time() - step_start - - # Step 2: Semantic Segmentation (if enabled) - segmentation_time = 0 - if self.enable_segmentation: - step_start = time.time() - segmentation_results = self.run_segmentation(rgb_image) - results["segmentation2d_objects"] = segmentation_results.get("objects", []) - results["segmentation_viz"] = segmentation_results.get("viz_frame") - segmentation_time = time.time() - step_start # type: ignore[assignment] - - # Step 3: Point Cloud Processing - pointcloud_time = 0 - detection2d_objects = results.get("detection2d_objects", []) - segmentation2d_objects = results.get("segmentation2d_objects", []) - - # Process detection objects if available - detected_objects = [] - if detection2d_objects: - step_start = time.time() - detected_objects = self.run_pointcloud_filtering( - rgb_image, depth_image, detection2d_objects - ) - pointcloud_time += time.time() - step_start # type: ignore[assignment] - - # Process segmentation objects if available - segmentation_filtered_objects = [] - if segmentation2d_objects: - step_start = time.time() - segmentation_filtered_objects = self.run_pointcloud_filtering( - rgb_image, depth_image, segmentation2d_objects - ) - pointcloud_time += time.time() - step_start # type: ignore[assignment] - - # Combine all objects using intelligent duplicate removal - all_objects = combine_object_data( - detected_objects, # type: ignore[arg-type] - segmentation_filtered_objects, # type: ignore[arg-type] - overlap_threshold=0.8, - ) - - # Get full point cloud - full_pcd = self.pointcloud_filter.get_full_point_cloud() - - # Extract misc/background points and create voxel grid - misc_start = time.time() - misc_clusters, misc_voxel_grid = extract_and_cluster_misc_points( - full_pcd, - all_objects, # type: ignore[arg-type] - eps=0.03, - min_points=100, - enable_filtering=True, - voxel_size=0.02, - ) - misc_time = time.time() - misc_start - - # Store results - results.update( - { - "detected_objects": detected_objects, - "all_objects": all_objects, - "full_pointcloud": full_pcd, - "misc_clusters": misc_clusters, - "misc_voxel_grid": misc_voxel_grid, - } - ) - - # Create point cloud visualizations - base_image = colorize_depth(depth_image, max_depth=10.0) - - # Create visualizations - results["pointcloud_viz"] = ( - create_point_cloud_overlay_visualization( - base_image=base_image, # type: ignore[arg-type] - objects=all_objects, # type: ignore[arg-type] - intrinsics=self.camera_intrinsics, # type: ignore[arg-type] - ) - if all_objects - else base_image - ) - - results["detected_pointcloud_viz"] = ( - create_point_cloud_overlay_visualization( - base_image=base_image, # type: ignore[arg-type] - objects=detected_objects, - intrinsics=self.camera_intrinsics, # type: ignore[arg-type] - ) - if detected_objects - else base_image - ) - - if misc_clusters: - # Generate consistent colors for clusters - cluster_colors = [ - tuple((np.random.RandomState(i + 100).rand(3) * 255).astype(int)) - for i in range(len(misc_clusters)) - ] - results["misc_pointcloud_viz"] = overlay_point_clouds_on_image( - base_image=base_image, # type: ignore[arg-type] - point_clouds=misc_clusters, - camera_intrinsics=self.camera_intrinsics, - colors=cluster_colors, - point_size=2, - alpha=0.6, - ) - else: - results["misc_pointcloud_viz"] = base_image - - # Step 4: Grasp Generation (if enabled) - should_generate_grasps = ( - generate_grasps if generate_grasps is not None else self.enable_grasp_generation - ) - - if should_generate_grasps and all_objects and full_pcd: - grasps = self.run_grasp_generation(all_objects, full_pcd) # type: ignore[arg-type] - results["grasps"] = grasps - if grasps: - results["grasp_overlay"] = create_grasp_overlay( - rgb_image, grasps, self.camera_intrinsics - ) - - except Exception as e: - logger.error(f"Error processing frame: {e}") - results["error"] = str(e) - - # Add timing information - total_time = time.time() - start_time - results.update( - { - "processing_time": total_time, - "timing_breakdown": { - "detection": detection_time if "detection_time" in locals() else 0, - "segmentation": segmentation_time if "segmentation_time" in locals() else 0, - "pointcloud": pointcloud_time if "pointcloud_time" in locals() else 0, - "misc_extraction": misc_time if "misc_time" in locals() else 0, - "total": total_time, - }, - } - ) - - return results - - def run_object_detection(self, rgb_image: np.ndarray) -> dict[str, Any]: # type: ignore[type-arg] - """Run object detection on RGB image.""" - try: - # Convert RGB to BGR for Detic detector - bgr_image = cv2.cvtColor(rgb_image, cv2.COLOR_RGB2BGR) - - # Use process_image method from Detic detector - bboxes, track_ids, class_ids, confidences, names, masks = self.detector.process_image( - bgr_image - ) - - # Convert to ObjectData format using utility function - objects = detection_results_to_object_data( - bboxes=bboxes, - track_ids=track_ids, - class_ids=class_ids, - confidences=confidences, - names=names, - masks=masks, - source="detection", - ) - - # Create visualization using detector's built-in method - viz_frame = self.detector.visualize_results( - rgb_image, bboxes, track_ids, class_ids, confidences, names - ) - - return {"objects": objects, "viz_frame": viz_frame} - - except Exception as e: - logger.error(f"Object detection failed: {e}") - return {"objects": [], "viz_frame": rgb_image.copy()} - - def run_pointcloud_filtering( - self, - rgb_image: np.ndarray, # type: ignore[type-arg] - depth_image: np.ndarray, # type: ignore[type-arg] - objects: list[dict], # type: ignore[type-arg] - ) -> list[dict]: # type: ignore[type-arg] - """Run point cloud filtering on detected objects.""" - try: - filtered_objects = self.pointcloud_filter.process_images( - rgb_image, - depth_image, - objects, # type: ignore[arg-type] - ) - return filtered_objects if filtered_objects else [] # type: ignore[return-value] - except Exception as e: - logger.error(f"Point cloud filtering failed: {e}") - return [] - - def run_segmentation(self, rgb_image: np.ndarray) -> dict[str, Any]: # type: ignore[type-arg] - """Run semantic segmentation on RGB image.""" - if not self.segmenter: - return {"objects": [], "viz_frame": rgb_image.copy()} - - try: - # Convert RGB to BGR for segmenter - bgr_image = cv2.cvtColor(rgb_image, cv2.COLOR_RGB2BGR) - - # Get segmentation results - masks, bboxes, track_ids, probs, names = self.segmenter.process_image(bgr_image) # type: ignore[no-untyped-call] - - # Convert to ObjectData format using utility function - objects = detection_results_to_object_data( - bboxes=bboxes, - track_ids=track_ids, - class_ids=list(range(len(bboxes))), # Use indices as class IDs for segmentation - confidences=probs, - names=names, - masks=masks, - source="segmentation", - ) - - # Create visualization - if masks: - viz_bgr = self.segmenter.visualize_results( - bgr_image, masks, bboxes, track_ids, probs, names - ) - # Convert back to RGB - viz_frame = cv2.cvtColor(viz_bgr, cv2.COLOR_BGR2RGB) - else: - viz_frame = rgb_image.copy() - - return {"objects": objects, "viz_frame": viz_frame} - - except Exception as e: - logger.error(f"Segmentation failed: {e}") - return {"objects": [], "viz_frame": rgb_image.copy()} - - def run_grasp_generation(self, filtered_objects: list[dict], full_pcd) -> list[dict] | None: # type: ignore[no-untyped-def, type-arg] - """Run grasp generation using the configured generator.""" - if not self.grasp_generator: - logger.warning("Grasp generation requested but no generator available") - return None - - try: - # Generate grasps using the configured generator - grasps = self.grasp_generator.generate_grasps_from_objects(filtered_objects, full_pcd) # type: ignore[arg-type] - - # Return parsed results directly (list of grasp dictionaries) - return grasps - - except Exception as e: - logger.error(f"Grasp generation failed: {e}") - return None - - def cleanup(self) -> None: - """Clean up resources.""" - if hasattr(self.detector, "cleanup"): - self.detector.cleanup() - if hasattr(self.pointcloud_filter, "cleanup"): - self.pointcloud_filter.cleanup() - if self.segmenter and hasattr(self.segmenter, "cleanup"): - self.segmenter.cleanup() - if self.grasp_generator and hasattr(self.grasp_generator, "cleanup"): - self.grasp_generator.cleanup() - logger.info("ManipulationProcessor cleaned up") diff --git a/dimos/manipulation/manipulation_interface.py b/dimos/manipulation/manipulation_interface.py index edeb99c0f0..10e71fbc66 100644 --- a/dimos/manipulation/manipulation_interface.py +++ b/dimos/manipulation/manipulation_interface.py @@ -26,7 +26,6 @@ from dimos.manipulation.manipulation_history import ( ManipulationHistory, ) -from dimos.perception.object_detection_stream import ObjectDetectionStream from dimos.types.manipulation import ( AbstractConstraint, ManipulationTask, @@ -53,7 +52,7 @@ def __init__( self, output_dir: str, new_memory: bool = False, - perception_stream: ObjectDetectionStream = None, # type: ignore[assignment] + perception_stream: Any = None, ) -> None: """ Initialize a new ManipulationInterface instance. diff --git a/dimos/manipulation/visual_servoing/detection3d.py b/dimos/manipulation/visual_servoing/detection3d.py deleted file mode 100644 index fca085df8c..0000000000 --- a/dimos/manipulation/visual_servoing/detection3d.py +++ /dev/null @@ -1,302 +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. - -""" -Real-time 3D object detection processor that extracts object poses from RGB-D data. -""" - -import cv2 -from dimos_lcm.vision_msgs import ( - BoundingBox2D, - BoundingBox3D, - Detection2D, - Detection3D, - ObjectHypothesis, - ObjectHypothesisWithPose, - Point2D, - Pose2D, -) -import numpy as np - -from dimos.manipulation.visual_servoing.utils import ( - estimate_object_depth, - transform_pose, - visualize_detections_3d, -) -from dimos.msgs.geometry_msgs import Pose, Quaternion, Vector3 -from dimos.msgs.std_msgs import Header -from dimos.msgs.vision_msgs import Detection2DArray, Detection3DArray -from dimos.perception.common.utils import bbox2d_to_corners -from dimos.perception.detection2d.utils import calculate_object_size_from_bbox -from dimos.perception.pointcloud.utils import extract_centroids_from_masks -from dimos.perception.segmentation.sam_2d_seg import Sam2DSegmenter -from dimos.utils.logging_config import setup_logger - -logger = setup_logger() - - -class Detection3DProcessor: - """ - Real-time 3D detection processor optimized for speed. - - Uses Sam (FastSAM) for segmentation and mask generation, then extracts - 3D centroids from depth data. - """ - - def __init__( - self, - camera_intrinsics: list[float], # [fx, fy, cx, cy] - min_confidence: float = 0.6, - min_points: int = 30, - max_depth: float = 1.0, - max_object_size: float = 0.15, - ) -> None: - """ - Initialize the real-time 3D detection processor. - - Args: - camera_intrinsics: [fx, fy, cx, cy] camera parameters - min_confidence: Minimum detection confidence threshold - min_points: Minimum 3D points required for valid detection - max_depth: Maximum valid depth in meters - """ - self.camera_intrinsics = camera_intrinsics - self.min_points = min_points - self.max_depth = max_depth - self.max_object_size = max_object_size - - # Initialize Sam segmenter with tracking enabled but analysis disabled - self.detector = Sam2DSegmenter( - use_tracker=False, - use_analyzer=False, - use_filtering=True, - ) - - self.min_confidence = min_confidence - - logger.info( - f"Initialized Detection3DProcessor with Sam segmenter, confidence={min_confidence}, " - f"min_points={min_points}, max_depth={max_depth}m, max_object_size={max_object_size}m" - ) - - def process_frame( - self, - rgb_image: np.ndarray, # type: ignore[type-arg] - depth_image: np.ndarray, # type: ignore[type-arg] - transform: np.ndarray | None = None, # type: ignore[type-arg] - ) -> tuple[Detection3DArray, Detection2DArray]: - """ - Process a single RGB-D frame to extract 3D object detections. - - Args: - rgb_image: RGB image (H, W, 3) - depth_image: Depth image (H, W) in meters - transform: Optional 4x4 transformation matrix to transform objects from camera frame to desired frame - - Returns: - Tuple of (Detection3DArray, Detection2DArray) with 3D and 2D information - """ - - # Convert RGB to BGR for Sam (OpenCV format) - bgr_image = cv2.cvtColor(rgb_image, cv2.COLOR_RGB2BGR) - - # Run Sam segmentation with tracking - masks, bboxes, track_ids, probs, names = self.detector.process_image(bgr_image) # type: ignore[no-untyped-call] - - if not masks or len(masks) == 0: - return Detection3DArray( - detections_length=0, header=Header(), detections=[] - ), Detection2DArray(detections_length=0, header=Header(), detections=[]) - - # Convert CUDA tensors to numpy arrays if needed - numpy_masks = [] - for mask in masks: - if hasattr(mask, "cpu"): # PyTorch tensor - numpy_masks.append(mask.cpu().numpy()) - else: # Already numpy array - numpy_masks.append(mask) - - # Extract 3D centroids from masks - poses = extract_centroids_from_masks( - rgb_image=rgb_image, - depth_image=depth_image, - masks=numpy_masks, - camera_intrinsics=self.camera_intrinsics, - ) - - detections_3d = [] - detections_2d = [] - pose_dict = {p["mask_idx"]: p for p in poses if p["centroid"][2] < self.max_depth} - - for i, (bbox, name, prob, track_id) in enumerate( - zip(bboxes, names, probs, track_ids, strict=False) - ): - if i not in pose_dict: - continue - - pose = pose_dict[i] - obj_cam_pos = pose["centroid"] - - if obj_cam_pos[2] > self.max_depth: - continue - - # Calculate object size from bbox and depth - width_m, height_m = calculate_object_size_from_bbox( - bbox, obj_cam_pos[2], self.camera_intrinsics - ) - - # Calculate depth dimension using segmentation mask - depth_m = estimate_object_depth( - depth_image, numpy_masks[i] if i < len(numpy_masks) else None, bbox - ) - - size_x = max(width_m, 0.01) # Minimum 1cm width - size_y = max(height_m, 0.01) # Minimum 1cm height - size_z = max(depth_m, 0.01) # Minimum 1cm depth - - if min(size_x, size_y, size_z) > self.max_object_size: - continue - - # Transform to desired frame if transform matrix is provided - if transform is not None: - # Get orientation as euler angles, default to no rotation if not available - obj_cam_orientation = pose.get( - "rotation", np.array([0.0, 0.0, 0.0]) - ) # Default to no rotation - transformed_pose = transform_pose( - obj_cam_pos, obj_cam_orientation, transform, to_robot=True - ) - center_pose = transformed_pose - else: - # If no transform, use camera coordinates - center_pose = Pose( - position=Vector3(obj_cam_pos[0], obj_cam_pos[1], obj_cam_pos[2]), - orientation=Quaternion(0.0, 0.0, 0.0, 1.0), # Default orientation - ) - - # Create Detection3D object - detection = Detection3D( - results_length=1, - header=Header(), # Empty header - results=[ - ObjectHypothesisWithPose( - hypothesis=ObjectHypothesis(class_id=name, score=float(prob)) - ) - ], - bbox=BoundingBox3D(center=center_pose, size=Vector3(size_x, size_y, size_z)), - id=str(track_id), - ) - - detections_3d.append(detection) - - # Create corresponding Detection2D - x1, y1, x2, y2 = bbox - center_x = (x1 + x2) / 2.0 - center_y = (y1 + y2) / 2.0 - width = x2 - x1 - height = y2 - y1 - - detection_2d = Detection2D( - results_length=1, - header=Header(), - results=[ - ObjectHypothesisWithPose( - hypothesis=ObjectHypothesis(class_id=name, score=float(prob)) - ) - ], - bbox=BoundingBox2D( - center=Pose2D(position=Point2D(center_x, center_y), theta=0.0), - size_x=float(width), - size_y=float(height), - ), - id=str(track_id), - ) - detections_2d.append(detection_2d) - - # Create and return both arrays - return ( - Detection3DArray( - detections_length=len(detections_3d), header=Header(), detections=detections_3d - ), - Detection2DArray( - detections_length=len(detections_2d), header=Header(), detections=detections_2d - ), - ) - - def visualize_detections( - self, - rgb_image: np.ndarray, # type: ignore[type-arg] - detections_3d: list[Detection3D], - detections_2d: list[Detection2D], - show_coordinates: bool = True, - ) -> np.ndarray: # type: ignore[type-arg] - """ - Visualize detections with 3D position overlay next to bounding boxes. - - Args: - rgb_image: Original RGB image - detections_3d: List of Detection3D objects - detections_2d: List of Detection2D objects (must be 1:1 correspondence) - show_coordinates: Whether to show 3D coordinates - - Returns: - Visualization image - """ - # Extract 2D bboxes from Detection2D objects - - bboxes_2d = [] - for det_2d in detections_2d: - if det_2d.bbox: - x1, y1, x2, y2 = bbox2d_to_corners(det_2d.bbox) - bboxes_2d.append([x1, y1, x2, y2]) - - return visualize_detections_3d(rgb_image, detections_3d, show_coordinates, bboxes_2d) - - def get_closest_detection( - self, detections: list[Detection3D], class_filter: str | None = None - ) -> Detection3D | None: - """ - Get the closest detection with valid 3D data. - - Args: - detections: List of Detection3D objects - class_filter: Optional class name to filter by - - Returns: - Closest Detection3D or None - """ - valid_detections = [] - for d in detections: - # Check if has valid bbox center position - if d.bbox and d.bbox.center and d.bbox.center.position: - # Check class filter if specified - if class_filter is None or ( - d.results_length > 0 and d.results[0].hypothesis.class_id == class_filter - ): - valid_detections.append(d) - - if not valid_detections: - return None - - # Sort by depth (Z coordinate) - def get_z_coord(d): # type: ignore[no-untyped-def] - return abs(d.bbox.center.position.z) - - return min(valid_detections, key=get_z_coord) - - def cleanup(self) -> None: - """Clean up resources.""" - if hasattr(self.detector, "cleanup"): - self.detector.cleanup() - logger.info("Detection3DProcessor cleaned up") diff --git a/dimos/manipulation/visual_servoing/manipulation_module.py b/dimos/manipulation/visual_servoing/manipulation_module.py deleted file mode 100644 index 088db9eb26..0000000000 --- a/dimos/manipulation/visual_servoing/manipulation_module.py +++ /dev/null @@ -1,951 +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. - -""" -Manipulation module for robotic grasping with visual servoing. -Handles grasping logic, state machine, and hardware coordination as a Dimos module. -""" - -from collections import deque -from enum import Enum -import threading -import time -from typing import Any - -import cv2 -from dimos_lcm.sensor_msgs import CameraInfo -import numpy as np -from reactivex.disposable import Disposable - -from dimos.core import In, Module, Out, rpc -from dimos.hardware.manipulators.piper.piper_arm import ( # type: ignore[import-not-found, import-untyped] - PiperArm, -) -from dimos.manipulation.visual_servoing.detection3d import Detection3DProcessor -from dimos.manipulation.visual_servoing.pbvs import PBVS -from dimos.manipulation.visual_servoing.utils import ( - create_manipulation_visualization, - is_target_reached, - select_points_from_depth, - transform_points_3d, - update_target_grasp_pose, -) -from dimos.msgs.geometry_msgs import Pose, Quaternion, Vector3 -from dimos.msgs.sensor_msgs import Image -from dimos.msgs.vision_msgs import Detection2DArray, Detection3DArray -from dimos.perception.common.utils import find_clicked_detection -from dimos.utils.logging_config import setup_logger -from dimos.utils.transform_utils import ( - compose_transforms, - create_transform_from_6dof, - matrix_to_pose, - pose_to_matrix, -) - -logger = setup_logger() - - -class GraspStage(Enum): - """Enum for different grasp stages.""" - - IDLE = "idle" - PRE_GRASP = "pre_grasp" - GRASP = "grasp" - CLOSE_AND_RETRACT = "close_and_retract" - PLACE = "place" - RETRACT = "retract" - - -class Feedback: - """Feedback data containing state information about the manipulation process.""" - - def __init__( - self, - grasp_stage: GraspStage, - target_tracked: bool, - current_executed_pose: Pose | None = None, - current_ee_pose: Pose | None = None, - current_camera_pose: Pose | None = None, - target_pose: Pose | None = None, - waiting_for_reach: bool = False, - success: bool | None = None, - ) -> None: - self.grasp_stage = grasp_stage - self.target_tracked = target_tracked - self.current_executed_pose = current_executed_pose - self.current_ee_pose = current_ee_pose - self.current_camera_pose = current_camera_pose - self.target_pose = target_pose - self.waiting_for_reach = waiting_for_reach - self.success = success - - -class ManipulationModule(Module): - """ - Manipulation module for visual servoing and grasping. - - Subscribes to: - - ZED RGB images - - ZED depth images - - ZED camera info - - Publishes: - - Visualization images - - RPC methods: - - handle_keyboard_command: Process keyboard input - - pick_and_place: Execute pick and place task - """ - - # LCM inputs - rgb_image: In[Image] - depth_image: In[Image] - camera_info: In[CameraInfo] - - # LCM outputs - viz_image: Out[Image] - - def __init__( # type: ignore[no-untyped-def] - self, - ee_to_camera_6dof: list | None = None, # type: ignore[type-arg] - **kwargs, - ) -> None: - """ - Initialize manipulation module. - - Args: - ee_to_camera_6dof: EE to camera transform [x, y, z, rx, ry, rz] in meters and radians - workspace_min_radius: Minimum workspace radius in meters - workspace_max_radius: Maximum workspace radius in meters - min_grasp_pitch_degrees: Minimum grasp pitch angle (at max radius) - max_grasp_pitch_degrees: Maximum grasp pitch angle (at min radius) - """ - super().__init__(**kwargs) - - self.arm = PiperArm() - - if ee_to_camera_6dof is None: - ee_to_camera_6dof = [-0.065, 0.03, -0.095, 0.0, -1.57, 0.0] - pos = Vector3(ee_to_camera_6dof[0], ee_to_camera_6dof[1], ee_to_camera_6dof[2]) - rot = Vector3(ee_to_camera_6dof[3], ee_to_camera_6dof[4], ee_to_camera_6dof[5]) - self.T_ee_to_camera = create_transform_from_6dof(pos, rot) - - self.camera_intrinsics = None - self.detector = None - self.pbvs = None - - # Control state - self.last_valid_target = None - self.waiting_for_reach = False - self.current_executed_pose = None # Track the actual pose sent to arm - self.target_updated = False - self.waiting_start_time = None - self.reach_pose_timeout = 20.0 - - # Grasp parameters - self.grasp_width_offset = 0.03 - self.pregrasp_distance = 0.25 - self.grasp_distance_range = 0.03 - self.grasp_close_delay = 2.0 - self.grasp_reached_time = None - self.gripper_max_opening = 0.07 - - # Workspace limits and dynamic pitch parameters - self.workspace_min_radius = 0.2 - self.workspace_max_radius = 0.75 - self.min_grasp_pitch_degrees = 5.0 - self.max_grasp_pitch_degrees = 60.0 - - # Grasp stage tracking - self.grasp_stage = GraspStage.IDLE - - # Pose stabilization tracking - self.pose_history_size = 4 - self.pose_stabilization_threshold = 0.01 - self.stabilization_timeout = 25.0 - self.stabilization_start_time = None - self.reached_poses = deque(maxlen=self.pose_history_size) # type: ignore[var-annotated] - self.adjustment_count = 0 - - # Pose reachability tracking - self.ee_pose_history = deque(maxlen=20) # type: ignore[var-annotated] # Keep history of EE poses - self.stuck_pose_threshold = 0.001 # 1mm movement threshold - self.stuck_pose_adjustment_degrees = 5.0 - self.stuck_count = 0 - self.max_stuck_reattempts = 7 - - # State for visualization - self.current_visualization = None - self.last_detection_3d_array = None - self.last_detection_2d_array = None - - # Grasp result and task tracking - self.pick_success = None - self.final_pregrasp_pose = None - self.task_failed = False - self.overall_success = None - - # Task control - self.task_running = False - self.task_thread = None - self.stop_event = threading.Event() - - # Latest sensor data - self.latest_rgb = None - self.latest_depth = None - self.latest_camera_info = None - - # Target selection - self.target_click = None - - # Place target position and object info - self.home_pose = Pose( - position=Vector3(0.0, 0.0, 0.0), orientation=Quaternion(0.0, 0.0, 0.0, 1.0) - ) - self.place_target_position = None - self.target_object_height = None - self.retract_distance = 0.12 - self.place_pose = None - self.retract_pose = None - self.arm.gotoObserve() - - @rpc - def start(self) -> None: - """Start the manipulation module.""" - - unsub = self.rgb_image.subscribe(self._on_rgb_image) - self._disposables.add(Disposable(unsub)) - - unsub = self.depth_image.subscribe(self._on_depth_image) - self._disposables.add(Disposable(unsub)) - - unsub = self.camera_info.subscribe(self._on_camera_info) - self._disposables.add(Disposable(unsub)) - - logger.info("Manipulation module started") - - @rpc - def stop(self) -> None: - """Stop the manipulation module.""" - # Stop any running task - self.stop_event.set() - if self.task_thread and self.task_thread.is_alive(): - self.task_thread.join(timeout=5.0) - - self.reset_to_idle() - - if self.detector and hasattr(self.detector, "cleanup"): - self.detector.cleanup() - self.arm.disable() - - logger.info("Manipulation module stopped") - - def _on_rgb_image(self, msg: Image) -> None: - """Handle RGB image messages.""" - try: - self.latest_rgb = msg.data - except Exception as e: - logger.error(f"Error processing RGB image: {e}") - - def _on_depth_image(self, msg: Image) -> None: - """Handle depth image messages.""" - try: - self.latest_depth = msg.data - except Exception as e: - logger.error(f"Error processing depth image: {e}") - - def _on_camera_info(self, msg: CameraInfo) -> None: - """Handle camera info messages.""" - try: - self.camera_intrinsics = [msg.K[0], msg.K[4], msg.K[2], msg.K[5]] # type: ignore[assignment] - - if self.detector is None: - self.detector = Detection3DProcessor(self.camera_intrinsics) # type: ignore[arg-type, assignment] - self.pbvs = PBVS() # type: ignore[assignment] - logger.info("Initialized detection and PBVS processors") - - self.latest_camera_info = msg - except Exception as e: - logger.error(f"Error processing camera info: {e}") - - @rpc - def get_single_rgb_frame(self) -> np.ndarray | None: # type: ignore[type-arg] - """ - get the latest rgb frame from the camera - """ - return self.latest_rgb - - @rpc - def handle_keyboard_command(self, key: str) -> str: - """ - Handle keyboard commands for robot control. - - Args: - key: Keyboard key as string - - Returns: - Action taken as string, or empty string if no action - """ - key_code = ord(key) if len(key) == 1 else int(key) - - if key_code == ord("r"): - self.stop_event.set() - self.task_running = False - self.reset_to_idle() - return "reset" - elif key_code == ord("s"): - logger.info("SOFT STOP - Emergency stopping robot!") - self.arm.softStop() - self.stop_event.set() - self.task_running = False - return "stop" - elif key_code == ord(" ") and self.pbvs and self.pbvs.target_grasp_pose: - if self.grasp_stage == GraspStage.PRE_GRASP: - self.set_grasp_stage(GraspStage.GRASP) - logger.info("Executing target pose") - return "execute" - elif key_code == ord("g"): - logger.info("Opening gripper") - self.arm.release_gripper() - return "release" - - return "" - - @rpc - def pick_and_place( - self, - target_x: int | None = None, - target_y: int | None = None, - place_x: int | None = None, - place_y: int | None = None, - ) -> dict[str, Any]: - """ - Start a pick and place task. - - Args: - target_x: Optional X coordinate of target object - target_y: Optional Y coordinate of target object - place_x: Optional X coordinate of place location - place_y: Optional Y coordinate of place location - - Returns: - Dict with status and message - """ - if self.task_running: - return {"status": "error", "message": "Task already running"} - - if self.camera_intrinsics is None: - return {"status": "error", "message": "Camera not initialized"} - - if target_x is not None and target_y is not None: - self.target_click = (target_x, target_y) - if place_x is not None and self.latest_depth is not None: - points_3d_camera = select_points_from_depth( - self.latest_depth, - (place_x, place_y), - self.camera_intrinsics, - radius=10, - ) - - if points_3d_camera.size > 0: - ee_pose = self.arm.get_ee_pose() - ee_transform = pose_to_matrix(ee_pose) - camera_transform = compose_transforms(ee_transform, self.T_ee_to_camera) - - points_3d_world = transform_points_3d( - points_3d_camera, - camera_transform, - to_robot=True, - ) - - place_position = np.mean(points_3d_world, axis=0) - self.place_target_position = place_position - logger.info( - f"Place target set at position: ({place_position[0]:.3f}, {place_position[1]:.3f}, {place_position[2]:.3f})" - ) - else: - logger.warning("No valid depth points found at place location") - self.place_target_position = None - else: - self.place_target_position = None - - self.task_failed = False - self.stop_event.clear() - - if self.task_thread and self.task_thread.is_alive(): - self.stop_event.set() - self.task_thread.join(timeout=1.0) - self.task_thread = threading.Thread(target=self._run_pick_and_place, daemon=True) - self.task_thread.start() - - return {"status": "started", "message": "Pick and place task started"} - - def _run_pick_and_place(self) -> None: - """Run the pick and place task loop.""" - self.task_running = True - logger.info("Starting pick and place task") - - try: - while not self.stop_event.is_set(): - if self.task_failed: - logger.error("Task failed, terminating pick and place") - self.stop_event.set() - break - - feedback = self.update() - if feedback is None: - time.sleep(0.01) - continue - - if feedback.success is not None: # type: ignore[attr-defined] - if feedback.success: # type: ignore[attr-defined] - logger.info("Pick and place completed successfully!") - else: - logger.warning("Pick and place failed") - self.reset_to_idle() - self.stop_event.set() - break - - time.sleep(0.01) - - except Exception as e: - logger.error(f"Error in pick and place task: {e}") - self.task_failed = True - finally: - self.task_running = False - logger.info("Pick and place task ended") - - def set_grasp_stage(self, stage: GraspStage) -> None: - """Set the grasp stage.""" - self.grasp_stage = stage - logger.info(f"Grasp stage: {stage.value}") - - def calculate_dynamic_grasp_pitch(self, target_pose: Pose) -> float: - """ - Calculate grasp pitch dynamically based on distance from robot base. - Maps workspace radius to grasp pitch angle. - - Args: - target_pose: Target pose - - Returns: - Grasp pitch angle in degrees - """ - # Calculate 3D distance from robot base (assumes robot at origin) - position = target_pose.position - distance = np.sqrt(position.x**2 + position.y**2 + position.z**2) - - # Clamp distance to workspace limits - distance = np.clip(distance, self.workspace_min_radius, self.workspace_max_radius) - - # Linear interpolation: min_radius -> max_pitch, max_radius -> min_pitch - # Normalized distance (0 to 1) - normalized_dist = (distance - self.workspace_min_radius) / ( - self.workspace_max_radius - self.workspace_min_radius - ) - - # Inverse mapping: closer objects need higher pitch - pitch_degrees = self.max_grasp_pitch_degrees - ( - normalized_dist * (self.max_grasp_pitch_degrees - self.min_grasp_pitch_degrees) - ) - - return pitch_degrees # type: ignore[no-any-return] - - def check_within_workspace(self, target_pose: Pose) -> bool: - """ - Check if pose is within workspace limits and log error if not. - - Args: - target_pose: Target pose to validate - - Returns: - True if within workspace, False otherwise - """ - # Calculate 3D distance from robot base - position = target_pose.position - distance = np.sqrt(position.x**2 + position.y**2 + position.z**2) - - if not (self.workspace_min_radius <= distance <= self.workspace_max_radius): - logger.error( - f"Target outside workspace limits: distance {distance:.3f}m not in [{self.workspace_min_radius:.2f}, {self.workspace_max_radius:.2f}]" - ) - return False - - return True - - def _check_reach_timeout(self) -> tuple[bool, float]: - """Check if robot has exceeded timeout while reaching pose. - - Returns: - Tuple of (timed_out, time_elapsed) - """ - if self.waiting_start_time: - time_elapsed = time.time() - self.waiting_start_time - if time_elapsed > self.reach_pose_timeout: - logger.warning( - f"Robot failed to reach pose within {self.reach_pose_timeout}s timeout" - ) - self.task_failed = True - self.reset_to_idle() - return True, time_elapsed - return False, time_elapsed - return False, 0.0 - - def _check_if_stuck(self) -> bool: - """ - Check if robot is stuck by analyzing pose history. - - Returns: - Tuple of (is_stuck, max_std_dev_mm) - """ - if len(self.ee_pose_history) < self.ee_pose_history.maxlen: # type: ignore[operator] - return False - - # Extract positions from pose history - positions = np.array( - [[p.position.x, p.position.y, p.position.z] for p in self.ee_pose_history] - ) - - # Calculate standard deviation of positions - std_devs = np.std(positions, axis=0) - # Check if all standard deviations are below stuck threshold - is_stuck = np.all(std_devs < self.stuck_pose_threshold) - - return is_stuck # type: ignore[return-value] - - def check_reach_and_adjust(self) -> bool: - """ - Check if robot has reached the current executed pose while waiting. - Handles timeout internally by failing the task. - Also detects if the robot is stuck (not moving towards target). - - Returns: - True if reached, False if still waiting or not in waiting state - """ - if not self.waiting_for_reach or not self.current_executed_pose: - return False - - # Get current end-effector pose - ee_pose = self.arm.get_ee_pose() - target_pose = self.current_executed_pose - - # Check for timeout - this will fail task and reset if timeout occurred - timed_out, _time_elapsed = self._check_reach_timeout() - if timed_out: - return False - - self.ee_pose_history.append(ee_pose) - - # Check if robot is stuck - is_stuck = self._check_if_stuck() - if is_stuck: - if self.grasp_stage == GraspStage.RETRACT or self.grasp_stage == GraspStage.PLACE: - self.waiting_for_reach = False - self.waiting_start_time = None - self.stuck_count = 0 - self.ee_pose_history.clear() - return True - self.stuck_count += 1 - pitch_degrees = self.calculate_dynamic_grasp_pitch(target_pose) - if self.stuck_count % 2 == 0: - pitch_degrees += self.stuck_pose_adjustment_degrees * (1 + self.stuck_count // 2) - else: - pitch_degrees -= self.stuck_pose_adjustment_degrees * (1 + self.stuck_count // 2) - - pitch_degrees = max( - self.min_grasp_pitch_degrees, min(self.max_grasp_pitch_degrees, pitch_degrees) - ) - updated_target_pose = update_target_grasp_pose(target_pose, ee_pose, 0.0, pitch_degrees) - self.arm.cmd_ee_pose(updated_target_pose) - self.current_executed_pose = updated_target_pose - self.ee_pose_history.clear() - self.waiting_for_reach = True - self.waiting_start_time = time.time() - return False - - if self.stuck_count >= self.max_stuck_reattempts: - self.task_failed = True - self.reset_to_idle() - return False - - if is_target_reached(target_pose, ee_pose, self.pbvs.target_tolerance): - self.waiting_for_reach = False - self.waiting_start_time = None - self.stuck_count = 0 - self.ee_pose_history.clear() - return True - return False - - def _update_tracking(self, detection_3d_array: Detection3DArray | None) -> bool: - """Update tracking with new detections.""" - if not detection_3d_array or not self.pbvs: - return False - - target_tracked = self.pbvs.update_tracking(detection_3d_array) - if target_tracked: - self.target_updated = True - self.last_valid_target = self.pbvs.get_current_target() - return target_tracked - - def reset_to_idle(self) -> None: - """Reset the manipulation system to IDLE state.""" - if self.pbvs: - self.pbvs.clear_target() - self.grasp_stage = GraspStage.IDLE - self.reached_poses.clear() - self.ee_pose_history.clear() - self.adjustment_count = 0 - self.waiting_for_reach = False - self.current_executed_pose = None - self.target_updated = False - self.stabilization_start_time = None - self.grasp_reached_time = None - self.waiting_start_time = None - self.pick_success = None - self.final_pregrasp_pose = None - self.overall_success = None - self.place_pose = None - self.retract_pose = None - self.stuck_count = 0 - - self.arm.gotoObserve() - - def execute_idle(self) -> None: - """Execute idle stage.""" - pass - - def execute_pre_grasp(self) -> None: - """Execute pre-grasp stage: visual servoing to pre-grasp position.""" - if self.waiting_for_reach: - if self.check_reach_and_adjust(): - self.reached_poses.append(self.current_executed_pose) - self.target_updated = False - time.sleep(0.2) - return - if ( - self.stabilization_start_time - and (time.time() - self.stabilization_start_time) > self.stabilization_timeout - ): - logger.warning( - f"Failed to get stable grasp after {self.stabilization_timeout} seconds, resetting" - ) - self.task_failed = True - self.reset_to_idle() - return - - ee_pose = self.arm.get_ee_pose() - dynamic_pitch = self.calculate_dynamic_grasp_pitch(self.pbvs.current_target.bbox.center) # type: ignore[attr-defined] - - _, _, _, has_target, target_pose = self.pbvs.compute_control( # type: ignore[attr-defined] - ee_pose, self.pregrasp_distance, dynamic_pitch - ) - if target_pose and has_target: - # Validate target pose is within workspace - if not self.check_within_workspace(target_pose): - self.task_failed = True - self.reset_to_idle() - return - - if self.check_target_stabilized(): - logger.info("Target stabilized, transitioning to GRASP") - self.final_pregrasp_pose = self.current_executed_pose - self.grasp_stage = GraspStage.GRASP - self.adjustment_count = 0 - self.waiting_for_reach = False - elif not self.waiting_for_reach and self.target_updated: - self.arm.cmd_ee_pose(target_pose) - self.current_executed_pose = target_pose - self.waiting_for_reach = True - self.waiting_start_time = time.time() # type: ignore[assignment] - self.target_updated = False - self.adjustment_count += 1 - time.sleep(0.2) - - def execute_grasp(self) -> None: - """Execute grasp stage: move to final grasp position.""" - if self.waiting_for_reach: - if self.check_reach_and_adjust() and not self.grasp_reached_time: - self.grasp_reached_time = time.time() # type: ignore[assignment] - return - - if self.grasp_reached_time: - if (time.time() - self.grasp_reached_time) >= self.grasp_close_delay: - logger.info("Grasp delay completed, closing gripper") - self.grasp_stage = GraspStage.CLOSE_AND_RETRACT - return - - if self.last_valid_target: - # Calculate dynamic pitch for current target - dynamic_pitch = self.calculate_dynamic_grasp_pitch(self.last_valid_target.bbox.center) - normalized_pitch = dynamic_pitch / 90.0 - grasp_distance = -self.grasp_distance_range + ( - 2 * self.grasp_distance_range * normalized_pitch - ) - - ee_pose = self.arm.get_ee_pose() - _, _, _, has_target, target_pose = self.pbvs.compute_control( - ee_pose, grasp_distance, dynamic_pitch - ) - - if target_pose and has_target: - # Validate grasp pose is within workspace - if not self.check_within_workspace(target_pose): - self.task_failed = True - self.reset_to_idle() - return - - object_width = self.last_valid_target.bbox.size.x - gripper_opening = max( - 0.005, min(object_width + self.grasp_width_offset, self.gripper_max_opening) - ) - - logger.info(f"Executing grasp: gripper={gripper_opening * 1000:.1f}mm") - self.arm.cmd_gripper_ctrl(gripper_opening) - self.arm.cmd_ee_pose(target_pose, line_mode=True) - self.current_executed_pose = target_pose - self.waiting_for_reach = True - self.waiting_start_time = time.time() - - def execute_close_and_retract(self) -> None: - """Execute the retraction sequence after gripper has been closed.""" - if self.waiting_for_reach and self.final_pregrasp_pose: - if self.check_reach_and_adjust(): - logger.info("Reached pre-grasp retraction position") - self.pick_success = self.arm.gripper_object_detected() - if self.pick_success: - logger.info("Object successfully grasped!") - if self.place_target_position is not None: - logger.info("Transitioning to PLACE stage") - self.grasp_stage = GraspStage.PLACE - else: - self.overall_success = True - else: - logger.warning("No object detected in gripper") - self.task_failed = True - self.overall_success = False - return - if not self.waiting_for_reach: - logger.info("Retracting to pre-grasp position") - self.arm.cmd_ee_pose(self.final_pregrasp_pose, line_mode=True) - self.current_executed_pose = self.final_pregrasp_pose - self.arm.close_gripper() - self.waiting_for_reach = True - self.waiting_start_time = time.time() # type: ignore[assignment] - - def execute_place(self) -> None: - """Execute place stage: move to place position and release object.""" - if self.waiting_for_reach: - # Use the already executed pose instead of recalculating - if self.check_reach_and_adjust(): - logger.info("Reached place position, releasing gripper") - self.arm.release_gripper() - time.sleep(1.0) - self.place_pose = self.current_executed_pose - logger.info("Transitioning to RETRACT stage") - self.grasp_stage = GraspStage.RETRACT - return - - if not self.waiting_for_reach: - place_pose = self.get_place_target_pose() - if place_pose: - logger.info("Moving to place position") - self.arm.cmd_ee_pose(place_pose, line_mode=True) - self.current_executed_pose = place_pose # type: ignore[assignment] - self.waiting_for_reach = True - self.waiting_start_time = time.time() # type: ignore[assignment] - else: - logger.error("Failed to get place target pose") - self.task_failed = True - self.overall_success = False # type: ignore[assignment] - - def execute_retract(self) -> None: - """Execute retract stage: retract from place position.""" - if self.waiting_for_reach and self.retract_pose: - if self.check_reach_and_adjust(): - logger.info("Reached retract position") - logger.info("Returning to observe position") - self.arm.gotoObserve() - self.arm.close_gripper() - self.overall_success = True - logger.info("Pick and place completed successfully!") - return - - if not self.waiting_for_reach: - if self.place_pose: - pose_pitch = self.calculate_dynamic_grasp_pitch(self.place_pose) - self.retract_pose = update_target_grasp_pose( - self.place_pose, self.home_pose, self.retract_distance, pose_pitch - ) - logger.info("Retracting from place position") - self.arm.cmd_ee_pose(self.retract_pose, line_mode=True) - self.current_executed_pose = self.retract_pose - self.waiting_for_reach = True - self.waiting_start_time = time.time() - else: - logger.error("No place pose stored for retraction") - self.task_failed = True - self.overall_success = False # type: ignore[assignment] - - def capture_and_process( - self, - ) -> tuple[np.ndarray | None, Detection3DArray | None, Detection2DArray | None, Pose | None]: # type: ignore[type-arg] - """Capture frame from camera data and process detections.""" - if self.latest_rgb is None or self.latest_depth is None or self.detector is None: - return None, None, None, None - - ee_pose = self.arm.get_ee_pose() - ee_transform = pose_to_matrix(ee_pose) - camera_transform = compose_transforms(ee_transform, self.T_ee_to_camera) - camera_pose = matrix_to_pose(camera_transform) - detection_3d_array, detection_2d_array = self.detector.process_frame( - self.latest_rgb, self.latest_depth, camera_transform - ) - - return self.latest_rgb, detection_3d_array, detection_2d_array, camera_pose - - def pick_target(self, x: int, y: int) -> bool: - """Select a target object at the given pixel coordinates.""" - if not self.last_detection_2d_array or not self.last_detection_3d_array: - logger.warning("No detections available for target selection") - return False - - clicked_3d = find_clicked_detection( - (x, y), self.last_detection_2d_array.detections, self.last_detection_3d_array.detections - ) - if clicked_3d and self.pbvs: - # Validate workspace - if not self.check_within_workspace(clicked_3d.bbox.center): - self.task_failed = True - return False - - self.pbvs.set_target(clicked_3d) - - if clicked_3d.bbox and clicked_3d.bbox.size: - self.target_object_height = clicked_3d.bbox.size.z - logger.info(f"Target object height: {self.target_object_height:.3f}m") - - position = clicked_3d.bbox.center.position - logger.info( - f"Target selected: ID={clicked_3d.id}, pos=({position.x:.3f}, {position.y:.3f}, {position.z:.3f})" - ) - self.grasp_stage = GraspStage.PRE_GRASP - self.reached_poses.clear() - self.adjustment_count = 0 - self.waiting_for_reach = False - self.current_executed_pose = None - self.stabilization_start_time = time.time() - return True - return False - - def update(self) -> dict[str, Any] | None: - """Main update function that handles capture, processing, control, and visualization.""" - rgb, detection_3d_array, detection_2d_array, camera_pose = self.capture_and_process() - if rgb is None: - return None - - self.last_detection_3d_array = detection_3d_array # type: ignore[assignment] - self.last_detection_2d_array = detection_2d_array # type: ignore[assignment] - if self.target_click: - x, y = self.target_click - if self.pick_target(x, y): - self.target_click = None - - if ( - detection_3d_array - and self.grasp_stage in [GraspStage.PRE_GRASP, GraspStage.GRASP] - and not self.waiting_for_reach - ): - self._update_tracking(detection_3d_array) - stage_handlers = { - GraspStage.IDLE: self.execute_idle, - GraspStage.PRE_GRASP: self.execute_pre_grasp, - GraspStage.GRASP: self.execute_grasp, - GraspStage.CLOSE_AND_RETRACT: self.execute_close_and_retract, - GraspStage.PLACE: self.execute_place, - GraspStage.RETRACT: self.execute_retract, - } - if self.grasp_stage in stage_handlers: - stage_handlers[self.grasp_stage]() - - target_tracked = self.pbvs.get_current_target() is not None if self.pbvs else False - ee_pose = self.arm.get_ee_pose() - feedback = Feedback( - grasp_stage=self.grasp_stage, - target_tracked=target_tracked, - current_executed_pose=self.current_executed_pose, - current_ee_pose=ee_pose, - current_camera_pose=camera_pose, - target_pose=self.pbvs.target_grasp_pose if self.pbvs else None, - waiting_for_reach=self.waiting_for_reach, - success=self.overall_success, - ) - - if self.task_running: - self.current_visualization = create_manipulation_visualization( # type: ignore[assignment] - rgb, feedback, detection_3d_array, detection_2d_array - ) - - if self.current_visualization is not None: - self._publish_visualization(self.current_visualization) - - return feedback # type: ignore[return-value] - - def _publish_visualization(self, viz_image: np.ndarray) -> None: # type: ignore[type-arg] - """Publish visualization image to LCM.""" - try: - viz_rgb = cv2.cvtColor(viz_image, cv2.COLOR_BGR2RGB) - msg = Image.from_numpy(viz_rgb) - self.viz_image.publish(msg) - except Exception as e: - logger.error(f"Error publishing visualization: {e}") - - def check_target_stabilized(self) -> bool: - """Check if the commanded poses have stabilized.""" - if len(self.reached_poses) < self.reached_poses.maxlen: # type: ignore[operator] - return False - - positions = np.array( - [[p.position.x, p.position.y, p.position.z] for p in self.reached_poses] - ) - std_devs = np.std(positions, axis=0) - return np.all(std_devs < self.pose_stabilization_threshold) # type: ignore[return-value] - - def get_place_target_pose(self) -> Pose | None: - """Get the place target pose with z-offset applied based on object height.""" - if self.place_target_position is None: - return None - - place_pos = self.place_target_position.copy() - if self.target_object_height is not None: - z_offset = self.target_object_height / 2.0 - place_pos[2] += z_offset + 0.1 - - place_center_pose = Pose( - position=Vector3(place_pos[0], place_pos[1], place_pos[2]), - orientation=Quaternion(0.0, 0.0, 0.0, 1.0), - ) - - ee_pose = self.arm.get_ee_pose() - - # Calculate dynamic pitch for place position - dynamic_pitch = self.calculate_dynamic_grasp_pitch(place_center_pose) - - place_pose = update_target_grasp_pose( - place_center_pose, - ee_pose, - grasp_distance=0.0, - grasp_pitch_degrees=dynamic_pitch, - ) - - return place_pose diff --git a/dimos/manipulation/visual_servoing/pbvs.py b/dimos/manipulation/visual_servoing/pbvs.py deleted file mode 100644 index f94c233834..0000000000 --- a/dimos/manipulation/visual_servoing/pbvs.py +++ /dev/null @@ -1,488 +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. - -""" -Position-Based Visual Servoing (PBVS) system for robotic manipulation. -Supports both eye-in-hand and eye-to-hand configurations. -""" - -from collections import deque - -from dimos_lcm.vision_msgs import Detection3D -import numpy as np -from scipy.spatial.transform import Rotation as R # type: ignore[import-untyped] - -from dimos.manipulation.visual_servoing.utils import ( - create_pbvs_visualization, - find_best_object_match, - is_target_reached, - update_target_grasp_pose, -) -from dimos.msgs.geometry_msgs import Pose, Quaternion, Vector3 -from dimos.msgs.vision_msgs import Detection3DArray -from dimos.utils.logging_config import setup_logger - -logger = setup_logger() - - -class PBVS: - """ - High-level Position-Based Visual Servoing orchestrator. - - Handles: - - Object tracking and target management - - Pregrasp distance computation - - Grasp pose generation - - Coordination with low-level controller - - Note: This class is agnostic to camera mounting (eye-in-hand vs eye-to-hand). - The caller is responsible for providing appropriate camera and EE poses. - """ - - def __init__( - self, - position_gain: float = 0.5, - rotation_gain: float = 0.3, - max_velocity: float = 0.1, # m/s - max_angular_velocity: float = 0.5, # rad/s - target_tolerance: float = 0.01, # 1cm - max_tracking_distance_threshold: float = 0.12, # Max distance for target tracking (m) - min_size_similarity: float = 0.6, # Min size similarity threshold (0.0-1.0) - direct_ee_control: bool = True, # If True, output target poses instead of velocities - ) -> None: - """ - Initialize PBVS system. - - Args: - position_gain: Proportional gain for position control - rotation_gain: Proportional gain for rotation control - max_velocity: Maximum linear velocity command magnitude (m/s) - max_angular_velocity: Maximum angular velocity command magnitude (rad/s) - target_tolerance: Distance threshold for considering target reached (m) - max_tracking_distance: Maximum distance for valid target tracking (m) - min_size_similarity: Minimum size similarity for valid target tracking (0.0-1.0) - direct_ee_control: If True, output target poses instead of velocity commands - """ - # Initialize low-level controller only if not in direct control mode - if not direct_ee_control: - self.controller = PBVSController( - position_gain=position_gain, - rotation_gain=rotation_gain, - max_velocity=max_velocity, - max_angular_velocity=max_angular_velocity, - target_tolerance=target_tolerance, - ) - else: - self.controller = None # type: ignore[assignment] - - # Store parameters for direct mode error computation - self.target_tolerance = target_tolerance - - # Target tracking parameters - self.max_tracking_distance_threshold = max_tracking_distance_threshold - self.min_size_similarity = min_size_similarity - self.direct_ee_control = direct_ee_control - - # Target state - self.current_target = None - self.target_grasp_pose = None - - # Detection history for robust tracking - self.detection_history_size = 3 - self.detection_history = deque(maxlen=self.detection_history_size) # type: ignore[var-annotated] - - # For direct control mode visualization - self.last_position_error = None - self.last_target_reached = False - - logger.info( - f"Initialized PBVS system with controller gains: pos={position_gain}, rot={rotation_gain}, " - f"tracking_thresholds: distance={max_tracking_distance_threshold}m, size={min_size_similarity:.2f}" - ) - - def set_target(self, target_object: Detection3D) -> bool: - """ - Set a new target object for servoing. - - Args: - target_object: Detection3D object - - Returns: - True if target was set successfully - """ - if target_object and target_object.bbox and target_object.bbox.center: - self.current_target = target_object - self.target_grasp_pose = None # Will be computed when needed - logger.info(f"New target set: ID {target_object.id}") - return True - return False - - def clear_target(self) -> None: - """Clear the current target.""" - self.current_target = None - self.target_grasp_pose = None - self.last_position_error = None - self.last_target_reached = False - self.detection_history.clear() - if self.controller: - self.controller.clear_state() - logger.info("Target cleared") - - def get_current_target(self) -> Detection3D | None: - """ - Get the current target object. - - Returns: - Current target Detection3D or None if no target selected - """ - return self.current_target - - def update_tracking(self, new_detections: Detection3DArray | None = None) -> bool: - """ - Update target tracking with new detections using a rolling window. - If tracking is lost, keeps the old target pose. - - Args: - new_detections: Optional new detections for target tracking - - Returns: - True if target was successfully tracked, False if lost (but target is kept) - """ - # Check if we have a current target - if not self.current_target: - return False - - # Add new detections to history if provided - if new_detections is not None and new_detections.detections_length > 0: - self.detection_history.append(new_detections) - - # If no detection history, can't track - if not self.detection_history: - logger.debug("No detection history for target tracking - using last known pose") - return False - - # Collect all candidates from detection history - all_candidates = [] - for detection_array in self.detection_history: - all_candidates.extend(detection_array.detections) - - if not all_candidates: - logger.debug("No candidates in detection history") - return False - - # Use stage-dependent distance threshold - max_distance = self.max_tracking_distance_threshold - - # Find best match across all recent detections - match_result = find_best_object_match( - target_obj=self.current_target, - candidates=all_candidates, - max_distance=max_distance, - min_size_similarity=self.min_size_similarity, - ) - - if match_result.is_valid_match: - self.current_target = match_result.matched_object - self.target_grasp_pose = None # Recompute grasp pose - logger.debug( - f"Target tracking successful: distance={match_result.distance:.3f}m, " - f"size_similarity={match_result.size_similarity:.2f}, " - f"confidence={match_result.confidence:.2f}" - ) - return True - - logger.debug( - f"Target tracking lost across {len(self.detection_history)} frames: " - f"distance={match_result.distance:.3f}m, " - f"size_similarity={match_result.size_similarity:.2f}, " - f"thresholds: distance={max_distance:.3f}m, size={self.min_size_similarity:.2f}" - ) - return False - - def compute_control( - self, - ee_pose: Pose, - grasp_distance: float = 0.15, - grasp_pitch_degrees: float = 45.0, - ) -> tuple[Vector3 | None, Vector3 | None, bool, bool, Pose | None]: - """ - Compute PBVS control with position and orientation servoing. - - Args: - ee_pose: Current end-effector pose - grasp_distance: Distance to maintain from target (meters) - - Returns: - Tuple of (velocity_command, angular_velocity_command, target_reached, has_target, target_pose) - - velocity_command: Linear velocity vector or None if no target (None in direct_ee_control mode) - - angular_velocity_command: Angular velocity vector or None if no target (None in direct_ee_control mode) - - target_reached: True if within target tolerance - - has_target: True if currently tracking a target - - target_pose: Target EE pose (only in direct_ee_control mode, otherwise None) - """ - # Check if we have a target - if not self.current_target: - return None, None, False, False, None - - # Update target grasp pose with provided distance and pitch - self.target_grasp_pose = update_target_grasp_pose( - self.current_target.bbox.center, ee_pose, grasp_distance, grasp_pitch_degrees - ) - - if self.target_grasp_pose is None: - logger.warning("Failed to compute grasp pose") - return None, None, False, False, None - - # Compute errors for visualization before checking if reached (in case pose gets cleared) - if self.direct_ee_control and self.target_grasp_pose: - self.last_position_error = Vector3( - self.target_grasp_pose.position.x - ee_pose.position.x, - self.target_grasp_pose.position.y - ee_pose.position.y, - self.target_grasp_pose.position.z - ee_pose.position.z, - ) - - # Check if target reached using our separate function - target_reached = is_target_reached(self.target_grasp_pose, ee_pose, self.target_tolerance) - - # Return appropriate values based on control mode - if self.direct_ee_control: - # Direct control mode - if self.target_grasp_pose: - self.last_target_reached = target_reached - # Return has_target=True since we have a target - return None, None, target_reached, True, self.target_grasp_pose - else: - return None, None, False, True, None - else: - # Velocity control mode - use controller - velocity_cmd, angular_velocity_cmd, _controller_reached = ( - self.controller.compute_control(ee_pose, self.target_grasp_pose) - ) - # Return has_target=True since we have a target, regardless of tracking status - return velocity_cmd, angular_velocity_cmd, target_reached, True, None - - def create_status_overlay( # type: ignore[no-untyped-def] - self, - image: np.ndarray, # type: ignore[type-arg] - grasp_stage=None, - ) -> np.ndarray: # type: ignore[type-arg] - """ - Create PBVS status overlay on image. - - Args: - image: Input image - grasp_stage: Current grasp stage (optional) - - Returns: - Image with PBVS status overlay - """ - stage_value = grasp_stage.value if grasp_stage else "idle" - return create_pbvs_visualization( - image, - self.current_target, - self.last_position_error, - self.last_target_reached, - stage_value, - ) - - -class PBVSController: - """ - Low-level Position-Based Visual Servoing controller. - Pure control logic that computes velocity commands from poses. - - Handles: - - Position and orientation error computation - - Velocity command generation with gain control - - Target reached detection - """ - - def __init__( - self, - position_gain: float = 0.5, - rotation_gain: float = 0.3, - max_velocity: float = 0.1, # m/s - max_angular_velocity: float = 0.5, # rad/s - target_tolerance: float = 0.01, # 1cm - ) -> None: - """ - Initialize PBVS controller. - - Args: - position_gain: Proportional gain for position control - rotation_gain: Proportional gain for rotation control - max_velocity: Maximum linear velocity command magnitude (m/s) - max_angular_velocity: Maximum angular velocity command magnitude (rad/s) - target_tolerance: Distance threshold for considering target reached (m) - """ - self.position_gain = position_gain - self.rotation_gain = rotation_gain - self.max_velocity = max_velocity - self.max_angular_velocity = max_angular_velocity - self.target_tolerance = target_tolerance - - self.last_position_error = None - self.last_rotation_error = None - self.last_velocity_cmd = None - self.last_angular_velocity_cmd = None - self.last_target_reached = False - - logger.info( - f"Initialized PBVS controller: pos_gain={position_gain}, rot_gain={rotation_gain}, " - f"max_vel={max_velocity}m/s, max_ang_vel={max_angular_velocity}rad/s, " - f"target_tolerance={target_tolerance}m" - ) - - def clear_state(self) -> None: - """Clear controller state.""" - self.last_position_error = None - self.last_rotation_error = None - self.last_velocity_cmd = None - self.last_angular_velocity_cmd = None - self.last_target_reached = False - - def compute_control( - self, ee_pose: Pose, grasp_pose: Pose - ) -> tuple[Vector3 | None, Vector3 | None, bool]: - """ - Compute PBVS control with position and orientation servoing. - - Args: - ee_pose: Current end-effector pose - grasp_pose: Target grasp pose - - Returns: - Tuple of (velocity_command, angular_velocity_command, target_reached) - - velocity_command: Linear velocity vector - - angular_velocity_command: Angular velocity vector - - target_reached: True if within target tolerance - """ - # Calculate position error (target - EE position) - error = Vector3( - grasp_pose.position.x - ee_pose.position.x, - grasp_pose.position.y - ee_pose.position.y, - grasp_pose.position.z - ee_pose.position.z, - ) - self.last_position_error = error # type: ignore[assignment] - - # Compute velocity command with proportional control - velocity_cmd = Vector3( - error.x * self.position_gain, - error.y * self.position_gain, - error.z * self.position_gain, - ) - - # Limit velocity magnitude - vel_magnitude = np.linalg.norm([velocity_cmd.x, velocity_cmd.y, velocity_cmd.z]) - if vel_magnitude > self.max_velocity: - scale = self.max_velocity / vel_magnitude - velocity_cmd = Vector3( - float(velocity_cmd.x * scale), - float(velocity_cmd.y * scale), - float(velocity_cmd.z * scale), - ) - - self.last_velocity_cmd = velocity_cmd # type: ignore[assignment] - - # Compute angular velocity for orientation control - angular_velocity_cmd = self._compute_angular_velocity(grasp_pose.orientation, ee_pose) - - # Check if target reached - error_magnitude = np.linalg.norm([error.x, error.y, error.z]) - target_reached = bool(error_magnitude < self.target_tolerance) - self.last_target_reached = target_reached - - return velocity_cmd, angular_velocity_cmd, target_reached - - def _compute_angular_velocity(self, target_rot: Quaternion, current_pose: Pose) -> Vector3: - """ - Compute angular velocity commands for orientation control. - Uses quaternion error computation for better numerical stability. - - Args: - target_rot: Target orientation (quaternion) - current_pose: Current EE pose - - Returns: - Angular velocity command as Vector3 - """ - # Use quaternion error for better numerical stability - - # Convert to scipy Rotation objects - target_rot_scipy = R.from_quat([target_rot.x, target_rot.y, target_rot.z, target_rot.w]) - current_rot_scipy = R.from_quat( - [ - current_pose.orientation.x, - current_pose.orientation.y, - current_pose.orientation.z, - current_pose.orientation.w, - ] - ) - - # Compute rotation error: error = target * current^(-1) - error_rot = target_rot_scipy * current_rot_scipy.inv() - - # Convert to axis-angle representation for control - error_axis_angle = error_rot.as_rotvec() - - # Use axis-angle directly as angular velocity error (small angle approximation) - roll_error = error_axis_angle[0] - pitch_error = error_axis_angle[1] - yaw_error = error_axis_angle[2] - - self.last_rotation_error = Vector3(roll_error, pitch_error, yaw_error) # type: ignore[assignment] - - # Apply proportional control - angular_velocity = Vector3( - roll_error * self.rotation_gain, - pitch_error * self.rotation_gain, - yaw_error * self.rotation_gain, - ) - - # Limit angular velocity magnitude - ang_vel_magnitude = np.sqrt( - angular_velocity.x**2 + angular_velocity.y**2 + angular_velocity.z**2 - ) - if ang_vel_magnitude > self.max_angular_velocity: - scale = self.max_angular_velocity / ang_vel_magnitude - angular_velocity = Vector3( - angular_velocity.x * scale, angular_velocity.y * scale, angular_velocity.z * scale - ) - - self.last_angular_velocity_cmd = angular_velocity # type: ignore[assignment] - - return angular_velocity - - def create_status_overlay( - self, - image: np.ndarray, # type: ignore[type-arg] - current_target: Detection3D | None = None, - ) -> np.ndarray: # type: ignore[type-arg] - """ - Create PBVS status overlay on image. - - Args: - image: Input image - current_target: Current target object Detection3D (for display) - - Returns: - Image with PBVS status overlay - """ - return create_pbvs_visualization( - image, - current_target, - self.last_position_error, - self.last_target_reached, - "velocity_control", - ) diff --git a/dimos/manipulation/visual_servoing/utils.py b/dimos/manipulation/visual_servoing/utils.py deleted file mode 100644 index 5922739429..0000000000 --- a/dimos/manipulation/visual_servoing/utils.py +++ /dev/null @@ -1,801 +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. - -from dataclasses import dataclass -from typing import Any - -import cv2 -from dimos_lcm.vision_msgs import Detection2D, Detection3D -import numpy as np - -from dimos.msgs.geometry_msgs import Pose, Quaternion, Vector3 -from dimos.perception.common.utils import project_2d_points_to_3d -from dimos.perception.detection2d.utils import plot_results -from dimos.utils.transform_utils import ( - compose_transforms, - euler_to_quaternion, - get_distance, - matrix_to_pose, - offset_distance, - optical_to_robot_frame, - pose_to_matrix, - robot_to_optical_frame, - yaw_towards_point, -) - - -def match_detection_by_id( - detection_3d: Detection3D, detections_3d: list[Detection3D], detections_2d: list[Detection2D] -) -> Detection2D | None: - """ - Find the corresponding Detection2D for a given Detection3D. - - Args: - detection_3d: The Detection3D to match - detections_3d: List of all Detection3D objects - detections_2d: List of all Detection2D objects (must be 1:1 correspondence) - - Returns: - Corresponding Detection2D if found, None otherwise - """ - for i, det_3d in enumerate(detections_3d): - if det_3d.id == detection_3d.id and i < len(detections_2d): - return detections_2d[i] - return None - - -def transform_pose( - obj_pos: np.ndarray, # type: ignore[type-arg] - obj_orientation: np.ndarray, # type: ignore[type-arg] - transform_matrix: np.ndarray, # type: ignore[type-arg] - to_optical: bool = False, - to_robot: bool = False, -) -> Pose: - """ - Transform object pose with optional frame convention conversion. - - Args: - obj_pos: Object position [x, y, z] - obj_orientation: Object orientation [roll, pitch, yaw] in radians - transform_matrix: 4x4 transformation matrix from camera frame to desired frame - to_optical: If True, input is in robot frame → convert result to optical frame - to_robot: If True, input is in optical frame → convert to robot frame first - - Returns: - Object pose in desired frame as Pose - """ - # Convert euler angles to quaternion using utility function - euler_vector = Vector3(obj_orientation[0], obj_orientation[1], obj_orientation[2]) - obj_orientation_quat = euler_to_quaternion(euler_vector) - - input_pose = Pose( - position=Vector3(obj_pos[0], obj_pos[1], obj_pos[2]), orientation=obj_orientation_quat - ) - - # Apply input frame conversion based on flags - if to_robot: - # Input is in optical frame → convert to robot frame first - pose_for_transform = optical_to_robot_frame(input_pose) - else: - # Default or to_optical: use input pose as-is - pose_for_transform = input_pose - - # Create transformation matrix from pose (relative to camera) - T_camera_object = pose_to_matrix(pose_for_transform) - - # Use compose_transforms to combine transformations - T_desired_object = compose_transforms(transform_matrix, T_camera_object) - - # Convert back to pose - result_pose = matrix_to_pose(T_desired_object) - - # Apply output frame conversion based on flags - if to_optical: - # Input was robot frame → convert result to optical frame - desired_pose = robot_to_optical_frame(result_pose) - else: - # Default or to_robot: use result as-is - desired_pose = result_pose - - return desired_pose - - -def transform_points_3d( - points_3d: np.ndarray, # type: ignore[type-arg] - transform_matrix: np.ndarray, # type: ignore[type-arg] - to_optical: bool = False, - to_robot: bool = False, -) -> np.ndarray: # type: ignore[type-arg] - """ - Transform 3D points with optional frame convention conversion. - Applies the same transformation pipeline as transform_pose but for multiple points. - - Args: - points_3d: Nx3 array of 3D points [x, y, z] - transform_matrix: 4x4 transformation matrix from camera frame to desired frame - to_optical: If True, input is in robot frame → convert result to optical frame - to_robot: If True, input is in optical frame → convert to robot frame first - - Returns: - Nx3 array of transformed 3D points in desired frame - """ - if points_3d.size == 0: - return np.zeros((0, 3), dtype=np.float32) - - points_3d = np.asarray(points_3d) - if points_3d.ndim == 1: - points_3d = points_3d.reshape(1, -1) - - transformed_points = [] - - for point in points_3d: - input_point_pose = Pose( - position=Vector3(point[0], point[1], point[2]), - orientation=Quaternion(0.0, 0.0, 0.0, 1.0), # Identity quaternion - ) - - # Apply input frame conversion based on flags - if to_robot: - # Input is in optical frame → convert to robot frame first - pose_for_transform = optical_to_robot_frame(input_point_pose) - else: - # Default or to_optical: use input pose as-is - pose_for_transform = input_point_pose - - # Create transformation matrix from point pose (relative to camera) - T_camera_point = pose_to_matrix(pose_for_transform) - - # Use compose_transforms to combine transformations - T_desired_point = compose_transforms(transform_matrix, T_camera_point) - - # Convert back to pose - result_pose = matrix_to_pose(T_desired_point) - - # Apply output frame conversion based on flags - if to_optical: - # Input was robot frame → convert result to optical frame - desired_pose = robot_to_optical_frame(result_pose) - else: - # Default or to_robot: use result as-is - desired_pose = result_pose - - transformed_point = [ - desired_pose.position.x, - desired_pose.position.y, - desired_pose.position.z, - ] - transformed_points.append(transformed_point) - - return np.array(transformed_points, dtype=np.float32) - - -def select_points_from_depth( - depth_image: np.ndarray, # type: ignore[type-arg] - target_point: tuple[int, int], - camera_intrinsics: list[float] | np.ndarray, # type: ignore[type-arg] - radius: int = 5, -) -> np.ndarray: # type: ignore[type-arg] - """ - Select points around a target point within a bounding box and project them to 3D. - - Args: - depth_image: Depth image in meters (H, W) - target_point: (x, y) target point coordinates - radius: Half-width of the bounding box (so bbox size is radius*2 x radius*2) - camera_intrinsics: Camera parameters as [fx, fy, cx, cy] list or 3x3 matrix - - Returns: - Nx3 array of 3D points (X, Y, Z) in camera frame - """ - x_target, y_target = target_point - height, width = depth_image.shape - - x_min = max(0, x_target - radius) - x_max = min(width, x_target + radius) - y_min = max(0, y_target - radius) - y_max = min(height, y_target + radius) - - # Create coordinate grids for the bounding box (vectorized) - y_coords, x_coords = np.meshgrid(range(y_min, y_max), range(x_min, x_max), indexing="ij") - - # Flatten to get all coordinate pairs - x_flat = x_coords.flatten() - y_flat = y_coords.flatten() - - # Extract corresponding depth values using advanced indexing - depth_flat = depth_image[y_flat, x_flat] - - valid_mask = (depth_flat > 0) & np.isfinite(depth_flat) - - if not np.any(valid_mask): - return np.zeros((0, 3), dtype=np.float32) - - points_2d = np.column_stack([x_flat[valid_mask], y_flat[valid_mask]]).astype(np.float32) - depth_values = depth_flat[valid_mask].astype(np.float32) - - points_3d = project_2d_points_to_3d(points_2d, depth_values, camera_intrinsics) - - return points_3d - - -def update_target_grasp_pose( - target_pose: Pose, ee_pose: Pose, grasp_distance: float = 0.0, grasp_pitch_degrees: float = 45.0 -) -> Pose | None: - """ - Update target grasp pose based on current target pose and EE pose. - - Args: - target_pose: Target pose to grasp - ee_pose: Current end-effector pose - grasp_distance: Distance to maintain from target (pregrasp or grasp distance) - grasp_pitch_degrees: Grasp pitch angle in degrees (default 90° for top-down) - - Returns: - Target grasp pose or None if target is invalid - """ - - target_pos = target_pose.position - - # Calculate orientation pointing from target towards EE - yaw_to_ee = yaw_towards_point(target_pos, ee_pose.position) - - # Create target pose with proper orientation - # Convert grasp pitch from degrees to radians with mapping: - # 0° (level) -> π/2 (1.57 rad), 90° (top-down) -> π (3.14 rad) - pitch_radians = 1.57 + np.radians(grasp_pitch_degrees) - - # Convert euler angles to quaternion using utility function - euler = Vector3(0.0, pitch_radians, yaw_to_ee) # roll=0, pitch=mapped, yaw=calculated - target_orientation = euler_to_quaternion(euler) - - updated_pose = Pose(target_pos, target_orientation) - - if grasp_distance > 0.0: - return offset_distance(updated_pose, grasp_distance) - else: - return updated_pose - - -def is_target_reached(target_pose: Pose, current_pose: Pose, tolerance: float = 0.01) -> bool: - """ - Check if the target pose has been reached within tolerance. - - Args: - target_pose: Target pose to reach - current_pose: Current pose (e.g., end-effector pose) - tolerance: Distance threshold for considering target reached (meters, default 0.01 = 1cm) - - Returns: - True if target is reached within tolerance, False otherwise - """ - # Calculate position error using distance utility - error_magnitude = get_distance(target_pose, current_pose) - return error_magnitude < tolerance - - -@dataclass -class ObjectMatchResult: - """Result of object matching with confidence metrics.""" - - matched_object: Detection3D | None - confidence: float - distance: float - size_similarity: float - is_valid_match: bool - - -def calculate_object_similarity( - target_obj: Detection3D, - candidate_obj: Detection3D, - distance_weight: float = 0.6, - size_weight: float = 0.4, -) -> tuple[float, float, float]: - """ - Calculate comprehensive similarity between two objects. - - Args: - target_obj: Target Detection3D object - candidate_obj: Candidate Detection3D object - distance_weight: Weight for distance component (0-1) - size_weight: Weight for size component (0-1) - - Returns: - Tuple of (total_similarity, distance_m, size_similarity) - """ - # Extract positions - target_pos = target_obj.bbox.center.position - candidate_pos = candidate_obj.bbox.center.position - - target_xyz = np.array([target_pos.x, target_pos.y, target_pos.z]) - candidate_xyz = np.array([candidate_pos.x, candidate_pos.y, candidate_pos.z]) - - # Calculate Euclidean distance - distance = np.linalg.norm(target_xyz - candidate_xyz) - distance_similarity = 1.0 / (1.0 + distance) # Exponential decay - - # Calculate size similarity by comparing each dimension individually - size_similarity = 1.0 # Default if no size info - target_size = target_obj.bbox.size - candidate_size = candidate_obj.bbox.size - - if target_size and candidate_size: - # Extract dimensions - target_dims = [target_size.x, target_size.y, target_size.z] - candidate_dims = [candidate_size.x, candidate_size.y, candidate_size.z] - - # Calculate similarity for each dimension pair - dim_similarities = [] - for target_dim, candidate_dim in zip(target_dims, candidate_dims, strict=False): - if target_dim == 0.0 and candidate_dim == 0.0: - dim_similarities.append(1.0) # Both dimensions are zero - elif target_dim == 0.0 or candidate_dim == 0.0: - dim_similarities.append(0.0) # One dimension is zero, other is not - else: - # Calculate similarity as min/max ratio - max_dim = max(target_dim, candidate_dim) - min_dim = min(target_dim, candidate_dim) - dim_similarity = min_dim / max_dim if max_dim > 0 else 0.0 - dim_similarities.append(dim_similarity) - - # Return average similarity across all dimensions - size_similarity = np.mean(dim_similarities) if dim_similarities else 0.0 # type: ignore[assignment] - - # Weighted combination - total_similarity = distance_weight * distance_similarity + size_weight * size_similarity - - return total_similarity, distance, size_similarity # type: ignore[return-value] - - -def find_best_object_match( - target_obj: Detection3D, - candidates: list[Detection3D], - max_distance: float = 0.1, - min_size_similarity: float = 0.4, - distance_weight: float = 0.7, - size_weight: float = 0.3, -) -> ObjectMatchResult: - """ - Find the best matching object from candidates using distance and size criteria. - - Args: - target_obj: Target Detection3D to match against - candidates: List of candidate Detection3D objects - max_distance: Maximum allowed distance for valid match (meters) - min_size_similarity: Minimum size similarity for valid match (0-1) - distance_weight: Weight for distance in similarity calculation - size_weight: Weight for size in similarity calculation - - Returns: - ObjectMatchResult with best match and confidence metrics - """ - if not candidates or not target_obj.bbox or not target_obj.bbox.center: - return ObjectMatchResult(None, 0.0, float("inf"), 0.0, False) - - best_match = None - best_confidence = 0.0 - best_distance = float("inf") - best_size_sim = 0.0 - - for candidate in candidates: - if not candidate.bbox or not candidate.bbox.center: - continue - - similarity, distance, size_sim = calculate_object_similarity( - target_obj, candidate, distance_weight, size_weight - ) - - # Check validity constraints - is_valid = distance <= max_distance and size_sim >= min_size_similarity - - if is_valid and similarity > best_confidence: - best_match = candidate - best_confidence = similarity - best_distance = distance - best_size_sim = size_sim - - return ObjectMatchResult( - matched_object=best_match, - confidence=best_confidence, - distance=best_distance, - size_similarity=best_size_sim, - is_valid_match=best_match is not None, - ) - - -def parse_zed_pose(zed_pose_data: dict[str, Any]) -> Pose | None: - """ - Parse ZED pose data dictionary into a Pose object. - - Args: - zed_pose_data: Dictionary from ZEDCamera.get_pose() containing: - - position: [x, y, z] in meters - - rotation: [x, y, z, w] quaternion - - euler_angles: [roll, pitch, yaw] in radians - - valid: Whether pose is valid - - Returns: - Pose object with position and orientation, or None if invalid - """ - if not zed_pose_data or not zed_pose_data.get("valid", False): - return None - - # Extract position - position = zed_pose_data.get("position", [0, 0, 0]) - pos_vector = Vector3(position[0], position[1], position[2]) - - quat = zed_pose_data["rotation"] - orientation = Quaternion(quat[0], quat[1], quat[2], quat[3]) - return Pose(position=pos_vector, orientation=orientation) - - -def estimate_object_depth( - depth_image: np.ndarray, # type: ignore[type-arg] - segmentation_mask: np.ndarray | None, # type: ignore[type-arg] - bbox: list[float], -) -> float: - """ - Estimate object depth dimension using segmentation mask and depth data. - Optimized for real-time performance. - - Args: - depth_image: Depth image in meters - segmentation_mask: Binary segmentation mask for the object - bbox: Bounding box [x1, y1, x2, y2] - - Returns: - Estimated object depth in meters - """ - x1, y1, x2, y2 = int(bbox[0]), int(bbox[1]), int(bbox[2]), int(bbox[3]) - - # Extract depth ROI once - roi_depth = depth_image[y1:y2, x1:x2] - - if segmentation_mask is not None and segmentation_mask.size > 0: - # Extract mask ROI efficiently - mask_roi = ( - segmentation_mask[y1:y2, x1:x2] - if segmentation_mask.shape != roi_depth.shape - else segmentation_mask - ) - - # Fast mask application using boolean indexing - valid_mask = mask_roi > 0 - if np.sum(valid_mask) > 10: # Early exit if not enough points - masked_depths = roi_depth[valid_mask] - - # Fast percentile calculation using numpy's optimized functions - depth_90 = np.percentile(masked_depths, 90) - depth_10 = np.percentile(masked_depths, 10) - depth_range = depth_90 - depth_10 - - # Clamp to reasonable bounds with single operation - return np.clip(depth_range, 0.02, 0.5) # type: ignore[no-any-return] - - # Fast fallback using area calculation - bbox_area = (x2 - x1) * (y2 - y1) - - # Vectorized area-based estimation - if bbox_area > 10000: - return 0.15 - elif bbox_area > 5000: - return 0.10 - else: - return 0.05 - - -# ============= Visualization Functions ============= - - -def create_manipulation_visualization( # type: ignore[no-untyped-def] - rgb_image: np.ndarray, # type: ignore[type-arg] - feedback, - detection_3d_array=None, - detection_2d_array=None, -) -> np.ndarray: # type: ignore[type-arg] - """ - Create simple visualization for manipulation class using feedback. - - Args: - rgb_image: RGB image array - feedback: Feedback object containing all state information - detection_3d_array: Optional 3D detections for object visualization - detection_2d_array: Optional 2D detections for object visualization - - Returns: - BGR image with visualization overlays - """ - # Convert to BGR for OpenCV - viz = cv2.cvtColor(rgb_image, cv2.COLOR_RGB2BGR) - - # Draw detections if available - if detection_3d_array and detection_2d_array: - # Extract 2D bboxes - bboxes_2d = [] - for det_2d in detection_2d_array.detections: - if det_2d.bbox: - x1 = det_2d.bbox.center.position.x - det_2d.bbox.size_x / 2 - y1 = det_2d.bbox.center.position.y - det_2d.bbox.size_y / 2 - x2 = det_2d.bbox.center.position.x + det_2d.bbox.size_x / 2 - y2 = det_2d.bbox.center.position.y + det_2d.bbox.size_y / 2 - bboxes_2d.append([x1, y1, x2, y2]) - - # Draw basic detections - rgb_with_detections = visualize_detections_3d( - rgb_image, detection_3d_array.detections, show_coordinates=True, bboxes_2d=bboxes_2d - ) - viz = cv2.cvtColor(rgb_with_detections, cv2.COLOR_RGB2BGR) - - # Add manipulation status overlay - status_y = 30 - cv2.putText( - viz, - "Eye-in-Hand Visual Servoing", - (10, status_y), - cv2.FONT_HERSHEY_SIMPLEX, - 0.6, - (0, 255, 255), - 2, - ) - - # Stage information - stage_text = f"Stage: {feedback.grasp_stage.value.upper()}" - stage_color = { - "idle": (100, 100, 100), - "pre_grasp": (0, 255, 255), - "grasp": (0, 255, 0), - "close_and_retract": (255, 0, 255), - "place": (0, 150, 255), - "retract": (255, 150, 0), - }.get(feedback.grasp_stage.value, (255, 255, 255)) - - cv2.putText( - viz, - stage_text, - (10, status_y + 25), - cv2.FONT_HERSHEY_SIMPLEX, - 0.5, - stage_color, - 1, - ) - - # Target tracking status - if feedback.target_tracked: - cv2.putText( - viz, - "Target: TRACKED", - (10, status_y + 45), - cv2.FONT_HERSHEY_SIMPLEX, - 0.5, - (0, 255, 0), - 1, - ) - elif feedback.grasp_stage.value != "idle": - cv2.putText( - viz, - "Target: LOST", - (10, status_y + 45), - cv2.FONT_HERSHEY_SIMPLEX, - 0.5, - (0, 0, 255), - 1, - ) - - # Waiting status - if feedback.waiting_for_reach: - cv2.putText( - viz, - "Status: WAITING FOR ROBOT", - (10, status_y + 65), - cv2.FONT_HERSHEY_SIMPLEX, - 0.5, - (255, 255, 0), - 1, - ) - - # Overall result - if feedback.success is not None: - result_text = "Pick & Place: SUCCESS" if feedback.success else "Pick & Place: FAILED" - result_color = (0, 255, 0) if feedback.success else (0, 0, 255) - cv2.putText( - viz, - result_text, - (10, status_y + 85), - cv2.FONT_HERSHEY_SIMPLEX, - 0.5, - result_color, - 2, - ) - - # Control hints (bottom of image) - hint_text = "Click object to grasp | s=STOP | r=RESET | g=RELEASE" - cv2.putText( - viz, - hint_text, - (10, viz.shape[0] - 10), - cv2.FONT_HERSHEY_SIMPLEX, - 0.4, - (200, 200, 200), - 1, - ) - - return viz - - -def create_pbvs_visualization( # type: ignore[no-untyped-def] - image: np.ndarray, # type: ignore[type-arg] - current_target=None, - position_error=None, - target_reached: bool = False, - grasp_stage: str = "idle", -) -> np.ndarray: # type: ignore[type-arg] - """ - Create simple PBVS visualization overlay. - - Args: - image: Input image (RGB or BGR) - current_target: Current target Detection3D - position_error: Position error Vector3 - target_reached: Whether target is reached - grasp_stage: Current grasp stage string - - Returns: - Image with PBVS overlay - """ - viz = image.copy() - - # Only show PBVS info if we have a target - if current_target is None: - return viz - - # Create status panel at bottom - height, width = viz.shape[:2] - panel_height = 100 - panel_y = height - panel_height - - # Semi-transparent overlay - overlay = viz.copy() - cv2.rectangle(overlay, (0, panel_y), (width, height), (0, 0, 0), -1) - viz = cv2.addWeighted(viz, 0.7, overlay, 0.3, 0) - - # PBVS Status - y_offset = panel_y + 20 - cv2.putText( - viz, - "PBVS Control", - (10, y_offset), - cv2.FONT_HERSHEY_SIMPLEX, - 0.6, - (0, 255, 255), - 2, - ) - - # Position error - if position_error: - error_mag = np.linalg.norm([position_error.x, position_error.y, position_error.z]) - error_text = f"Error: {error_mag * 100:.1f}cm" - error_color = (0, 255, 0) if target_reached else (0, 255, 255) - cv2.putText( - viz, - error_text, - (10, y_offset + 25), - cv2.FONT_HERSHEY_SIMPLEX, - 0.5, - error_color, - 1, - ) - - # Stage - cv2.putText( - viz, - f"Stage: {grasp_stage}", - (10, y_offset + 45), - cv2.FONT_HERSHEY_SIMPLEX, - 0.5, - (255, 150, 255), - 1, - ) - - # Target reached indicator - if target_reached: - cv2.putText( - viz, - "TARGET REACHED", - (width - 150, y_offset + 25), - cv2.FONT_HERSHEY_SIMPLEX, - 0.6, - (0, 255, 0), - 2, - ) - - return viz - - -def visualize_detections_3d( - rgb_image: np.ndarray, # type: ignore[type-arg] - detections: list[Detection3D], - show_coordinates: bool = True, - bboxes_2d: list[list[float]] | None = None, -) -> np.ndarray: # type: ignore[type-arg] - """ - Visualize detections with 3D position overlay next to bounding boxes. - - Args: - rgb_image: Original RGB image - detections: List of Detection3D objects - show_coordinates: Whether to show 3D coordinates next to bounding boxes - bboxes_2d: Optional list of 2D bounding boxes corresponding to detections - - Returns: - Visualization image - """ - if not detections: - return rgb_image.copy() - - # If no 2D bboxes provided, skip visualization - if bboxes_2d is None: - return rgb_image.copy() - - # Extract data for plot_results function - bboxes = bboxes_2d - track_ids = [int(det.id) if det.id.isdigit() else i for i, det in enumerate(detections)] - class_ids = [i for i in range(len(detections))] - confidences = [ - det.results[0].hypothesis.score if det.results_length > 0 else 0.0 for det in detections - ] - names = [ - det.results[0].hypothesis.class_id if det.results_length > 0 else "unknown" - for det in detections - ] - - # Use plot_results for basic visualization - viz = plot_results(rgb_image, bboxes, track_ids, class_ids, confidences, names) - - # Add 3D position coordinates if requested - if show_coordinates and bboxes_2d is not None: - for i, det in enumerate(detections): - if det.bbox and det.bbox.center and i < len(bboxes_2d): - position = det.bbox.center.position - bbox = bboxes_2d[i] - - pos_xyz = np.array([position.x, position.y, position.z]) - - # Get bounding box coordinates - _x1, y1, x2, _y2 = map(int, bbox) - - # Add position text next to bounding box (top-right corner) - pos_text = f"({pos_xyz[0]:.2f}, {pos_xyz[1]:.2f}, {pos_xyz[2]:.2f})" - text_x = x2 + 5 # Right edge of bbox + small offset - text_y = y1 + 15 # Top edge of bbox + small offset - - # Add background rectangle for better readability - text_size = cv2.getTextSize(pos_text, cv2.FONT_HERSHEY_SIMPLEX, 0.4, 1)[0] - cv2.rectangle( - viz, - (text_x - 2, text_y - text_size[1] - 2), - (text_x + text_size[0] + 2, text_y + 2), - (0, 0, 0), - -1, - ) - - cv2.putText( - viz, - pos_text, - (text_x, text_y), - cv2.FONT_HERSHEY_SIMPLEX, - 0.4, - (255, 255, 255), - 1, - ) - - return viz # type: ignore[no-any-return] diff --git a/dimos/models/vl/base.py b/dimos/models/vl/base.py index 93caba4de7..b2bd10480f 100644 --- a/dimos/models/vl/base.py +++ b/dimos/models/vl/base.py @@ -261,7 +261,7 @@ def query_detections( Only respond with JSON, no other text. """ - image_detections = ImageDetections2D(image) + image_detections: ImageDetections2D[Detection2DBBox] = ImageDetections2D(image) # Get scaled image and scale factor for coordinate rescaling scaled_image, scale = self._prepare_image(image) diff --git a/dimos/models/vl/moondream.py b/dimos/models/vl/moondream.py index f31611e867..60a38c0df8 100644 --- a/dimos/models/vl/moondream.py +++ b/dimos/models/vl/moondream.py @@ -144,7 +144,7 @@ def query_detections( result = self._model.detect(pil_image, query, settings=settings) # Convert to ImageDetections2D - image_detections = ImageDetections2D(image) + image_detections: ImageDetections2D[Detection2DBBox] = ImageDetections2D(image) # Get image dimensions for converting normalized coords to pixels height, width = image.height, image.width diff --git a/dimos/models/vl/moondream_hosted.py b/dimos/models/vl/moondream_hosted.py index c28a12363f..093c55441f 100644 --- a/dimos/models/vl/moondream_hosted.py +++ b/dimos/models/vl/moondream_hosted.py @@ -74,7 +74,7 @@ def query_detections(self, image: Image, query: str, **kwargs) -> ImageDetection objects = result.get("objects", []) # Convert to ImageDetections2D - image_detections = ImageDetections2D(image) + image_detections: ImageDetections2D[Detection2DBBox] = ImageDetections2D(image) height, width = image.height, image.width for track_id, obj in enumerate(objects): diff --git a/dimos/msgs/geometry_msgs/Quaternion.py b/dimos/msgs/geometry_msgs/Quaternion.py index d19436d441..02c9592ea6 100644 --- a/dimos/msgs/geometry_msgs/Quaternion.py +++ b/dimos/msgs/geometry_msgs/Quaternion.py @@ -138,6 +138,20 @@ def from_euler(cls, vector: Vector3) -> Quaternion: return cls(x, y, z, w) + @classmethod + def from_rotation_matrix(cls, matrix: np.ndarray) -> Quaternion: # type: ignore[type-arg] + """Convert a 3x3 rotation matrix to quaternion. + + Args: + matrix: 3x3 rotation matrix (numpy array) + + Returns: + Quaternion representation + """ + rotation = R.from_matrix(matrix) + quat = rotation.as_quat() # Returns [x, y, z, w] + return cls(quat[0], quat[1], quat[2], quat[3]) + def to_euler(self) -> Vector3: """Convert quaternion to Euler angles (roll, pitch, yaw) in radians. diff --git a/dimos/msgs/sensor_msgs/Image.py b/dimos/msgs/sensor_msgs/Image.py index 26ed141867..a4a71d3565 100644 --- a/dimos/msgs/sensor_msgs/Image.py +++ b/dimos/msgs/sensor_msgs/Image.py @@ -252,6 +252,15 @@ def frame_id(self) -> str: def frame_id(self, value: str) -> None: self._impl.frame_id = str(value) + def from_ros_header(self, header) -> None: # type: ignore[no-untyped-def] + """Set the image timestamp and frame_id from a ROS header. + + Args: + header: ROS std_msgs/Header message with stamp and frame_id fields + """ + self.ts = header.stamp.sec + (header.stamp.nanosec / 1_000_000_000) + self.frame_id = header.frame_id + @property def ts(self) -> float: return self._impl.ts @@ -310,6 +319,10 @@ def to_cupy(self) -> Image: def to_opencv(self) -> np.ndarray: # type: ignore[type-arg] return self._impl.to_opencv() + def as_numpy(self) -> np.ndarray: # type: ignore[type-arg] + """Get image data as numpy array in RGB format.""" + return np.asarray(self.data) + def to_rgb(self) -> Image: return Image(self._impl.to_rgb()) @@ -352,6 +365,20 @@ def sharpness(self) -> float: """Return sharpness score.""" return self._impl.sharpness() + def to_depth_meters(self) -> Image: + """Return a depth image normalized to meters as float32.""" + depth_cv = self.to_opencv() + fmt = self.format + + if fmt == ImageFormat.DEPTH16: + depth_cv = depth_cv.astype(np.float32) / 1000.0 + fmt = ImageFormat.DEPTH + elif depth_cv.dtype != np.float32: + depth_cv = depth_cv.astype(np.float32) + fmt = ImageFormat.DEPTH if fmt == ImageFormat.DEPTH else fmt + + return Image.from_numpy(depth_cv, format=fmt, frame_id=self.frame_id, ts=self.ts) + def save(self, filepath: str) -> bool: return self._impl.save(filepath) diff --git a/dimos/msgs/vision_msgs/Detection2D.py b/dimos/msgs/vision_msgs/Detection2D.py new file mode 100644 index 0000000000..aa957f8061 --- /dev/null +++ b/dimos/msgs/vision_msgs/Detection2D.py @@ -0,0 +1,27 @@ +# 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 dimos_lcm.vision_msgs.Detection2D import Detection2D as LCMDetection2D + +from dimos.types.timestamped import to_timestamp + + +class Detection2D(LCMDetection2D): # type: ignore[misc] + msg_name = "vision_msgs.Detection2D" + + # for _get_field_type() to work when decoding in _decode_one() + __annotations__ = LCMDetection2D.__annotations__ + + @property + def ts(self) -> float: + return to_timestamp(self.header.stamp) diff --git a/dimos/msgs/vision_msgs/Detection3D.py b/dimos/msgs/vision_msgs/Detection3D.py new file mode 100644 index 0000000000..57e8f686fc --- /dev/null +++ b/dimos/msgs/vision_msgs/Detection3D.py @@ -0,0 +1,117 @@ +# Copyright 2025-2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +from __future__ import annotations + +from dimos_lcm.vision_msgs.Detection3D import Detection3D as LCMDetection3D + +try: + from geometry_msgs.msg import ( # type: ignore[attr-defined] + Point as ROSPoint, + Pose as ROSPose, + Quaternion as ROSQuaternion, + Vector3 as ROSVector3, + ) + from std_msgs.msg import Header as ROSHeader # type: ignore[attr-defined] + from vision_msgs.msg import ( # type: ignore[attr-defined, import-untyped] + BoundingBox3D as ROSBoundingBox3D, + Detection3D as ROSDetection3D, + ObjectHypothesis as ROSObjectHypothesis, + ObjectHypothesisWithPose as ROSObjectHypothesisWithPose, + ) +except ImportError: + ROSPoint = None # type: ignore[assignment, misc] + ROSPose = None # type: ignore[assignment, misc] + ROSQuaternion = None # type: ignore[assignment, misc] + ROSVector3 = None # type: ignore[assignment, misc] + ROSHeader = None # type: ignore[assignment, misc] + ROSBoundingBox3D = None # type: ignore[assignment, misc] + ROSDetection3D = None # type: ignore[assignment, misc] + ROSObjectHypothesis = None # type: ignore[assignment, misc] + ROSObjectHypothesisWithPose = None # type: ignore[assignment, misc] + +from dimos.types.timestamped import to_timestamp + + +class Detection3D(LCMDetection3D): # type: ignore[misc] + msg_name = "vision_msgs.Detection3D" + + # for _get_field_type() to work when decoding in _decode_one() + __annotations__ = LCMDetection3D.__annotations__ + + def __init__(self, **kwargs) -> None: # type: ignore[no-untyped-def] + """Initialize with fresh mutable objects to avoid shared state.""" + super().__init__() + # Create fresh instances to avoid shared mutable state from LCM class defaults + from dimos_lcm.std_msgs import Header + from dimos_lcm.vision_msgs import BoundingBox3D + + self.header = Header() + from dimos_lcm.vision_msgs import ObjectHypothesisWithPose + + self.results: list[ObjectHypothesisWithPose] = [] + self.bbox = BoundingBox3D() + self.id = "" + + # Apply any kwargs + for key, value in kwargs.items(): + setattr(self, key, value) + + @property + def ts(self) -> float: + return to_timestamp(self.header.stamp) + + def to_ros_msg(self) -> ROSDetection3D: + """Convert to ROS vision_msgs/Detection3D message. + + Returns: + ROS Detection3D message + """ + ros_msg = ROSDetection3D() + + # Set header + ros_msg.header = ROSHeader() + ros_msg.header.frame_id = self.header.frame_id + ros_msg.header.stamp.sec = self.header.stamp.sec + ros_msg.header.stamp.nanosec = self.header.stamp.nsec + + # Set bounding box + ros_msg.bbox = ROSBoundingBox3D() + ros_msg.bbox.center = ROSPose() + ros_msg.bbox.center.position = ROSPoint() + ros_msg.bbox.center.position.x = float(self.bbox.center.position.x) + ros_msg.bbox.center.position.y = float(self.bbox.center.position.y) + ros_msg.bbox.center.position.z = float(self.bbox.center.position.z) + ros_msg.bbox.center.orientation = ROSQuaternion() + ros_msg.bbox.center.orientation.x = float(self.bbox.center.orientation.x) + ros_msg.bbox.center.orientation.y = float(self.bbox.center.orientation.y) + ros_msg.bbox.center.orientation.z = float(self.bbox.center.orientation.z) + ros_msg.bbox.center.orientation.w = float(self.bbox.center.orientation.w) + ros_msg.bbox.size = ROSVector3() + ros_msg.bbox.size.x = float(self.bbox.size.x) + ros_msg.bbox.size.y = float(self.bbox.size.y) + ros_msg.bbox.size.z = float(self.bbox.size.z) + + # Set results (object hypotheses) + for result in self.results: + ros_result = ROSObjectHypothesisWithPose() + ros_result.hypothesis = ROSObjectHypothesis() + ros_result.hypothesis.class_id = str(result.hypothesis.class_id) + ros_result.hypothesis.score = float(result.hypothesis.score) + ros_msg.results.append(ros_result) + + # Set ID if available + if hasattr(self, "id"): + ros_msg.id = str(self.id) + + return ros_msg diff --git a/dimos/msgs/vision_msgs/Detection3DArray.py b/dimos/msgs/vision_msgs/Detection3DArray.py index 59905cad4c..75826d75b2 100644 --- a/dimos/msgs/vision_msgs/Detection3DArray.py +++ b/dimos/msgs/vision_msgs/Detection3DArray.py @@ -11,11 +11,66 @@ # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and # limitations under the License. +from __future__ import annotations -from dimos_lcm.vision_msgs.Detection3DArray import ( +from dimos_lcm.vision_msgs.Detection3DArray import ( # type: ignore[import-untyped] Detection3DArray as LCMDetection3DArray, ) +try: + from std_msgs.msg import Header as ROSHeader # type: ignore[attr-defined] + from vision_msgs.msg import ( # type: ignore[import-untyped] + Detection3DArray as ROSDetection3DArray, # type: ignore[attr-defined] + ) +except ImportError: + ROSHeader = None # type: ignore[assignment, misc] + ROSDetection3DArray = None # type: ignore[assignment, misc] + +from dimos.msgs.vision_msgs.Detection3D import Detection3D + class Detection3DArray(LCMDetection3DArray): # type: ignore[misc] msg_name = "vision_msgs.Detection3DArray" + + def __init__(self, **kwargs) -> None: # type: ignore[no-untyped-def] + """Initialize with fresh mutable objects to avoid shared state.""" + super().__init__() + # Create fresh instances to avoid shared mutable state from LCM class defaults + from dimos_lcm.std_msgs import Header + + self.header = Header() + from dimos.msgs.vision_msgs import Detection3D + + self.detections: list[Detection3D] = [] + + # Apply any kwargs + for key, value in kwargs.items(): + setattr(self, key, value) + + def to_ros_msg(self) -> ROSDetection3DArray: + """Convert to ROS vision_msgs/Detection3DArray message. + + Returns: + ROS Detection3DArray message + """ + ros_msg = ROSDetection3DArray() + + # Set header + ros_msg.header = ROSHeader() + ros_msg.header.frame_id = self.header.frame_id + ros_msg.header.stamp.sec = self.header.stamp.sec + ros_msg.header.stamp.nanosec = self.header.stamp.nsec + + # Convert each detection + for det in self.detections: + # Wrap in our Detection3D class if needed to get to_ros_msg + if not isinstance(det, Detection3D): + det = Detection3D( + header=det.header, + results=det.results, + bbox=det.bbox, + id=getattr(det, "id", ""), + ) + ros_msg.detections.append(det.to_ros_msg()) + + return ros_msg diff --git a/dimos/msgs/vision_msgs/__init__.py b/dimos/msgs/vision_msgs/__init__.py index af170cbfab..0f1c9c8dc1 100644 --- a/dimos/msgs/vision_msgs/__init__.py +++ b/dimos/msgs/vision_msgs/__init__.py @@ -1,6 +1,15 @@ from .BoundingBox2DArray import BoundingBox2DArray from .BoundingBox3DArray import BoundingBox3DArray +from .Detection2D import Detection2D from .Detection2DArray import Detection2DArray +from .Detection3D import Detection3D from .Detection3DArray import Detection3DArray -__all__ = ["BoundingBox2DArray", "BoundingBox3DArray", "Detection2DArray", "Detection3DArray"] +__all__ = [ + "BoundingBox2DArray", + "BoundingBox3DArray", + "Detection2D", + "Detection2DArray", + "Detection3D", + "Detection3DArray", +] diff --git a/dimos/perception/common/__init__.py b/dimos/perception/common/__init__.py index 67481bc449..16281fe0b6 100644 --- a/dimos/perception/common/__init__.py +++ b/dimos/perception/common/__init__.py @@ -1,3 +1 @@ -from .detection2d_tracker import get_tracked_results, target2dTracker -from .ibvs import * from .utils import * diff --git a/dimos/perception/common/detection2d_tracker.py b/dimos/perception/common/detection2d_tracker.py deleted file mode 100644 index 9ff36be8a1..0000000000 --- a/dimos/perception/common/detection2d_tracker.py +++ /dev/null @@ -1,396 +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. - -from collections import deque -from collections.abc import Sequence - -import numpy as np - - -def compute_iou(bbox1, bbox2): # type: ignore[no-untyped-def] - """ - Compute Intersection over Union (IoU) of two bounding boxes. - Each bbox is [x1, y1, x2, y2]. - """ - x1 = max(bbox1[0], bbox2[0]) - y1 = max(bbox1[1], bbox2[1]) - x2 = min(bbox1[2], bbox2[2]) - y2 = min(bbox1[3], bbox2[3]) - - inter_area = max(0, x2 - x1) * max(0, y2 - y1) - area1 = (bbox1[2] - bbox1[0]) * (bbox1[3] - bbox1[1]) - area2 = (bbox2[2] - bbox2[0]) * (bbox2[3] - bbox2[1]) - - union_area = area1 + area2 - inter_area - if union_area == 0: - return 0 - return inter_area / union_area - - -def get_tracked_results(tracked_targets): # type: ignore[no-untyped-def] - """ - Extract tracked results from a list of target2d objects. - - Args: - tracked_targets (list[target2d]): List of target2d objects (published targets) - returned by the tracker's update() function. - - Returns: - tuple: (tracked_masks, tracked_bboxes, tracked_track_ids, tracked_probs, tracked_names) - where each is a list of the corresponding attribute from each target. - """ - tracked_masks = [] - tracked_bboxes = [] - tracked_track_ids = [] - tracked_probs = [] - tracked_names = [] - - for target in tracked_targets: - # Extract the latest values stored in each target. - tracked_masks.append(target.latest_mask) - tracked_bboxes.append(target.latest_bbox) - # Here we use the most recent detection's track ID. - tracked_track_ids.append(target.target_id) - # Use the latest probability from the history. - tracked_probs.append(target.score) - # Use the stored name (if any). If not available, you can use a default value. - tracked_names.append(target.name) - - return tracked_masks, tracked_bboxes, tracked_track_ids, tracked_probs, tracked_names - - -class target2d: - """ - Represents a tracked 2D target. - Stores the latest bounding box and mask along with a short history of track IDs, - detection probabilities, and computed texture values. - """ - - def __init__( # type: ignore[no-untyped-def] - self, - initial_mask, - initial_bbox, - track_id, - prob: float, - name: str, - texture_value, - target_id, - history_size: int = 10, - ) -> None: - """ - Args: - initial_mask (torch.Tensor): Latest segmentation mask. - initial_bbox (list): Bounding box in [x1, y1, x2, y2] format. - track_id (int): Detection’s track ID (may be -1 if not provided). - prob (float): Detection probability. - name (str): Object class name. - texture_value (float): Computed average texture value for this detection. - target_id (int): Unique identifier assigned by the tracker. - history_size (int): Maximum number of frames to keep in the history. - """ - self.target_id = target_id - self.latest_mask = initial_mask - self.latest_bbox = initial_bbox - self.name = name - self.score = 1.0 - - self.track_id = track_id - self.probs_history = deque(maxlen=history_size) # type: ignore[var-annotated] - self.texture_history = deque(maxlen=history_size) # type: ignore[var-annotated] - - self.frame_count = deque(maxlen=history_size) # type: ignore[var-annotated] # Total frames this target has been seen. - self.missed_frames = 0 # Consecutive frames when no detection was assigned. - self.history_size = history_size - - def update(self, mask, bbox, track_id, prob: float, name: str, texture_value) -> None: # type: ignore[no-untyped-def] - """ - Update the target with a new detection. - """ - self.latest_mask = mask - self.latest_bbox = bbox - self.name = name - - self.track_id = track_id - self.probs_history.append(prob) - self.texture_history.append(texture_value) - - self.frame_count.append(1) - self.missed_frames = 0 - - def mark_missed(self) -> None: - """ - Increment the count of consecutive frames where this target was not updated. - """ - self.missed_frames += 1 - self.frame_count.append(0) - - def compute_score( # type: ignore[no-untyped-def] - self, - frame_shape, - min_area_ratio, - max_area_ratio, - texture_range=(0.0, 1.0), - border_safe_distance: int = 50, - weights=None, - ): - """ - Compute a combined score for the target based on several factors. - - Factors: - - **Detection probability:** Average over recent frames. - - **Temporal stability:** How consistently the target has appeared. - - **Texture quality:** Normalized using the provided min and max values. - - **Border proximity:** Computed from the minimum distance from the bbox to the frame edges. - - **Size:** How the object's area (relative to the frame) compares to acceptable bounds. - - Args: - frame_shape (tuple): (height, width) of the frame. - min_area_ratio (float): Minimum acceptable ratio (bbox area / frame area). - max_area_ratio (float): Maximum acceptable ratio. - texture_range (tuple): (min_texture, max_texture) expected values. - border_safe_distance (float): Distance (in pixels) considered safe from the border. - weights (dict): Weights for each component. Expected keys: - 'prob', 'temporal', 'texture', 'border', and 'size'. - - Returns: - float: The combined (normalized) score in the range [0, 1]. - """ - # Default weights if none provided. - if weights is None: - weights = {"prob": 1.0, "temporal": 1.0, "texture": 1.0, "border": 1.0, "size": 1.0} - - h, w = frame_shape - x1, y1, x2, y2 = self.latest_bbox - bbox_area = (x2 - x1) * (y2 - y1) - frame_area = w * h - area_ratio = bbox_area / frame_area - - # Detection probability factor. - avg_prob = np.mean(self.probs_history) - # Temporal stability factor: normalized by history size. - temporal_stability = np.mean(self.frame_count) - # Texture factor: normalize average texture using the provided range. - avg_texture = np.mean(self.texture_history) if self.texture_history else 0.0 - min_texture, max_texture = texture_range - if max_texture == min_texture: - normalized_texture = avg_texture - else: - normalized_texture = (avg_texture - min_texture) / (max_texture - min_texture) - normalized_texture = max(0.0, min(normalized_texture, 1.0)) - - # Border factor: compute the minimum distance from the bbox to any frame edge. - left_dist = x1 - top_dist = y1 - right_dist = w - x2 - min_border_dist = min(left_dist, top_dist, right_dist) - # Normalize the border distance: full score (1.0) if at least border_safe_distance away. - border_factor = min(1.0, min_border_dist / border_safe_distance) - - # Size factor: penalize objects that are too small or too big. - if area_ratio < min_area_ratio: - size_factor = area_ratio / min_area_ratio - elif area_ratio > max_area_ratio: - # Here we compute a linear penalty if the area exceeds max_area_ratio. - if 1 - max_area_ratio > 0: - size_factor = max(0, (1 - area_ratio) / (1 - max_area_ratio)) - else: - size_factor = 0.0 - else: - size_factor = 1.0 - - # Combine factors using a weighted sum (each factor is assumed in [0, 1]). - w_prob = weights.get("prob", 1.0) - w_temporal = weights.get("temporal", 1.0) - w_texture = weights.get("texture", 1.0) - w_border = weights.get("border", 1.0) - w_size = weights.get("size", 1.0) - total_weight = w_prob + w_temporal + w_texture + w_border + w_size - - # print(f"track_id: {self.target_id}, avg_prob: {avg_prob:.2f}, temporal_stability: {temporal_stability:.2f}, normalized_texture: {normalized_texture:.2f}, border_factor: {border_factor:.2f}, size_factor: {size_factor:.2f}") - - final_score = ( - w_prob * avg_prob - + w_temporal * temporal_stability - + w_texture * normalized_texture - + w_border * border_factor - + w_size * size_factor - ) / total_weight - - self.score = final_score - - return final_score - - -class target2dTracker: - """ - Tracker that maintains a history of targets across frames. - New segmentation detections (frame, masks, bboxes, track_ids, probabilities, - and computed texture values) are matched to existing targets or used to create new ones. - - The tracker uses a scoring system that incorporates: - - **Detection probability** - - **Temporal stability** - - **Texture quality** (normalized within a specified range) - - **Proximity to image borders** (a continuous penalty based on the distance) - - **Object size** relative to the frame - - Targets are published if their score exceeds the start threshold and are removed if their score - falls below the stop threshold or if they are missed for too many consecutive frames. - """ - - def __init__( # type: ignore[no-untyped-def] - self, - history_size: int = 10, - score_threshold_start: float = 0.5, - score_threshold_stop: float = 0.3, - min_frame_count: int = 10, - max_missed_frames: int = 3, - min_area_ratio: float = 0.001, - max_area_ratio: float = 0.1, - texture_range=(0.0, 1.0), - border_safe_distance: int = 50, - weights=None, - ) -> None: - """ - Args: - history_size (int): Maximum history length (number of frames) per target. - score_threshold_start (float): Minimum score for a target to be published. - score_threshold_stop (float): If a target’s score falls below this, it is removed. - min_frame_count (int): Minimum number of frames a target must be seen to be published. - max_missed_frames (int): Maximum consecutive frames a target can be missing before deletion. - min_area_ratio (float): Minimum acceptable bbox area relative to the frame. - max_area_ratio (float): Maximum acceptable bbox area relative to the frame. - texture_range (tuple): (min_texture, max_texture) expected values. - border_safe_distance (float): Distance (in pixels) considered safe from the border. - weights (dict): Weights for the scoring components (keys: 'prob', 'temporal', - 'texture', 'border', 'size'). - """ - self.history_size = history_size - self.score_threshold_start = score_threshold_start - self.score_threshold_stop = score_threshold_stop - self.min_frame_count = min_frame_count - self.max_missed_frames = max_missed_frames - self.min_area_ratio = min_area_ratio - self.max_area_ratio = max_area_ratio - self.texture_range = texture_range - self.border_safe_distance = border_safe_distance - # Default weights if none are provided. - if weights is None: - weights = {"prob": 1.0, "temporal": 1.0, "texture": 1.0, "border": 1.0, "size": 1.0} - self.weights = weights - - self.targets = {} # type: ignore[var-annotated] # Dictionary mapping target_id -> target2d instance. - self.next_target_id = 0 - - def update( # type: ignore[no-untyped-def] - self, - frame, - masks, - bboxes, - track_ids, - probs: Sequence[float], - names: Sequence[str], - texture_values, - ): - """ - Update the tracker with new detections from the current frame. - - Args: - frame (np.ndarray): Current BGR frame. - masks (list[torch.Tensor]): List of segmentation masks. - bboxes (list): List of bounding boxes [x1, y1, x2, y2]. - track_ids (list): List of detection track IDs. - probs (list): List of detection probabilities. - names (list): List of class names. - texture_values (list): List of computed texture values. - - Returns: - published_targets (list[target2d]): Targets that are active and have scores above - the start threshold. - """ - updated_target_ids = set() - frame_shape = frame.shape[:2] # (height, width) - - # For each detection, try to match with an existing target. - for mask, bbox, det_tid, prob, name, texture in zip( - masks, bboxes, track_ids, probs, names, texture_values, strict=False - ): - matched_target = None - - # First, try matching by detection track ID if valid. - if det_tid != -1: - for target in self.targets.values(): - if target.track_id == det_tid: - matched_target = target - break - - # Otherwise, try matching using IoU. - if matched_target is None: - best_iou = 0 - for target in self.targets.values(): - iou = compute_iou(bbox, target.latest_bbox) # type: ignore[no-untyped-call] - if iou > 0.5 and iou > best_iou: - best_iou = iou - matched_target = target - - # Update existing target or create a new one. - if matched_target is not None: - matched_target.update(mask, bbox, det_tid, prob, name, texture) - updated_target_ids.add(matched_target.target_id) - else: - new_target = target2d( - mask, bbox, det_tid, prob, name, texture, self.next_target_id, self.history_size - ) - self.targets[self.next_target_id] = new_target - updated_target_ids.add(self.next_target_id) - self.next_target_id += 1 - - # Mark targets that were not updated. - for target_id, target in list(self.targets.items()): - if target_id not in updated_target_ids: - target.mark_missed() - if target.missed_frames > self.max_missed_frames: - del self.targets[target_id] - continue # Skip further checks for this target. - # Remove targets whose score falls below the stop threshold. - score = target.compute_score( - frame_shape, - self.min_area_ratio, - self.max_area_ratio, - texture_range=self.texture_range, - border_safe_distance=self.border_safe_distance, - weights=self.weights, - ) - if score < self.score_threshold_stop: - del self.targets[target_id] - - # Publish targets with scores above the start threshold. - published_targets = [] - for target in self.targets.values(): - score = target.compute_score( - frame_shape, - self.min_area_ratio, - self.max_area_ratio, - texture_range=self.texture_range, - border_safe_distance=self.border_safe_distance, - weights=self.weights, - ) - if ( - score >= self.score_threshold_start - and sum(target.frame_count) >= self.min_frame_count - and target.missed_frames <= 5 - ): - published_targets.append(target) - - return published_targets diff --git a/dimos/perception/common/export_tensorrt.py b/dimos/perception/common/export_tensorrt.py deleted file mode 100644 index ca671e36f2..0000000000 --- a/dimos/perception/common/export_tensorrt.py +++ /dev/null @@ -1,58 +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 argparse - -from ultralytics import YOLO, FastSAM # type: ignore[attr-defined, import-not-found] - - -def parse_args(): # type: ignore[no-untyped-def] - parser = argparse.ArgumentParser(description="Export YOLO/FastSAM models to different formats") - parser.add_argument("--model_path", type=str, required=True, help="Path to the model weights") - parser.add_argument( - "--model_type", - type=str, - choices=["yolo", "fastsam"], - required=True, - help="Type of model to export", - ) - parser.add_argument( - "--precision", - type=str, - choices=["fp32", "fp16", "int8"], - default="fp32", - help="Precision for export", - ) - parser.add_argument( - "--format", type=str, choices=["onnx", "engine"], default="onnx", help="Export format" - ) - return parser.parse_args() - - -def main() -> None: - args = parse_args() # type: ignore[no-untyped-call] - half = args.precision == "fp16" - int8 = args.precision == "int8" - # Load the appropriate model - if args.model_type == "yolo": - model: YOLO | FastSAM = YOLO(args.model_path) - else: - model = FastSAM(args.model_path) - - # Export the model - model.export(format=args.format, half=half, int8=int8) - - -if __name__ == "__main__": - main() diff --git a/dimos/perception/common/ibvs.py b/dimos/perception/common/ibvs.py deleted file mode 100644 index e24819f432..0000000000 --- a/dimos/perception/common/ibvs.py +++ /dev/null @@ -1,280 +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 numpy as np - - -class PersonDistanceEstimator: - def __init__(self, K, camera_pitch, camera_height) -> None: # type: ignore[no-untyped-def] - """ - Initialize the distance estimator using ground plane constraint. - - Args: - K: 3x3 Camera intrinsic matrix in OpenCV format - (Assumed to be already for an undistorted image) - camera_pitch: Upward pitch of the camera (in radians), in the robot frame - Positive means looking up, negative means looking down - camera_height: Height of the camera above the ground (in meters) - """ - self.K = K - self.camera_height = camera_height - - # Precompute the inverse intrinsic matrix - self.K_inv = np.linalg.inv(K) - - # Transform from camera to robot frame (z-forward to x-forward) - self.T = np.array([[0, 0, 1], [-1, 0, 0], [0, -1, 0]]) - - # Pitch rotation matrix (positive is upward) - theta = -camera_pitch # Negative since positive pitch is negative rotation about robot Y - self.R_pitch = np.array( - [[np.cos(theta), 0, np.sin(theta)], [0, 1, 0], [-np.sin(theta), 0, np.cos(theta)]] - ) - - # Combined transform from camera to robot frame - self.A = self.R_pitch @ self.T - - # Store focal length and principal point for angle calculation - self.fx = K[0, 0] - self.cx = K[0, 2] - - def estimate_distance_angle(self, bbox: tuple, robot_pitch: float | None = None): # type: ignore[no-untyped-def, type-arg] - """ - Estimate distance and angle to person using ground plane constraint. - - Args: - bbox: tuple (x_min, y_min, x_max, y_max) - where y_max represents the feet position - robot_pitch: Current pitch of the robot body (in radians) - If provided, this will be combined with the camera's fixed pitch - - Returns: - depth: distance to person along camera's z-axis (meters) - angle: horizontal angle in camera frame (radians, positive right) - """ - x_min, _, x_max, y_max = bbox - - # Get center point of feet - u_c = (x_min + x_max) / 2.0 - v_feet = y_max - - # Create homogeneous feet point and get ray direction - p_feet = np.array([u_c, v_feet, 1.0]) - d_feet_cam = self.K_inv @ p_feet - - # If robot_pitch is provided, recalculate the transformation matrix - if robot_pitch is not None: - # Combined pitch (fixed camera pitch + current robot pitch) - total_pitch = -camera_pitch - robot_pitch # Both negated for correct rotation direction - R_total_pitch = np.array( - [ - [np.cos(total_pitch), 0, np.sin(total_pitch)], - [0, 1, 0], - [-np.sin(total_pitch), 0, np.cos(total_pitch)], - ] - ) - # Use the updated transformation matrix - A = R_total_pitch @ self.T - else: - # Use the precomputed transformation matrix - A = self.A - - # Convert ray to robot frame using appropriate transformation - d_feet_robot = A @ d_feet_cam - - # Ground plane intersection (z=0) - # camera_height + t * d_feet_robot[2] = 0 - if abs(d_feet_robot[2]) < 1e-6: - raise ValueError("Feet ray is parallel to ground plane") - - # Solve for scaling factor t - t = -self.camera_height / d_feet_robot[2] - - # Get 3D feet position in robot frame - p_feet_robot = t * d_feet_robot - - # Convert back to camera frame - p_feet_cam = self.A.T @ p_feet_robot - - # Extract depth (z-coordinate in camera frame) - depth = p_feet_cam[2] - - # Calculate horizontal angle from image center - angle = np.arctan((u_c - self.cx) / self.fx) - - return depth, angle - - -class ObjectDistanceEstimator: - """ - Estimate distance to an object using the ground plane constraint. - This class assumes the camera is mounted on a robot and uses the - camera's intrinsic parameters to estimate the distance to a detected object. - """ - - def __init__(self, K, camera_pitch, camera_height) -> None: # type: ignore[no-untyped-def] - """ - Initialize the distance estimator using ground plane constraint. - - Args: - K: 3x3 Camera intrinsic matrix in OpenCV format - (Assumed to be already for an undistorted image) - camera_pitch: Upward pitch of the camera (in radians) - Positive means looking up, negative means looking down - camera_height: Height of the camera above the ground (in meters) - """ - self.K = K - self.camera_height = camera_height - - # Precompute the inverse intrinsic matrix - self.K_inv = np.linalg.inv(K) - - # Transform from camera to robot frame (z-forward to x-forward) - self.T = np.array([[0, 0, 1], [-1, 0, 0], [0, -1, 0]]) - - # Pitch rotation matrix (positive is upward) - theta = -camera_pitch # Negative since positive pitch is negative rotation about robot Y - self.R_pitch = np.array( - [[np.cos(theta), 0, np.sin(theta)], [0, 1, 0], [-np.sin(theta), 0, np.cos(theta)]] - ) - - # Combined transform from camera to robot frame - self.A = self.R_pitch @ self.T - - # Store focal length and principal point for angle calculation - self.fx = K[0, 0] - self.fy = K[1, 1] - self.cx = K[0, 2] - self.estimated_object_size = None - - def estimate_object_size(self, bbox: tuple, distance: float): # type: ignore[no-untyped-def, type-arg] - """ - Estimate the physical size of an object based on its bbox and known distance. - - Args: - bbox: tuple (x_min, y_min, x_max, y_max) bounding box in the image - distance: Known distance to the object (in meters) - robot_pitch: Current pitch of the robot body (in radians), if any - - Returns: - estimated_size: Estimated physical height of the object (in meters) - """ - _x_min, y_min, _x_max, y_max = bbox - - # Calculate object height in pixels - object_height_px = y_max - y_min - - # Calculate the physical height using the known distance and focal length - estimated_size = object_height_px * distance / self.fy - self.estimated_object_size = estimated_size - - return estimated_size - - def set_estimated_object_size(self, size: float) -> None: - """ - Set the estimated object size for future distance calculations. - - Args: - size: Estimated physical size of the object (in meters) - """ - self.estimated_object_size = size # type: ignore[assignment] - - def estimate_distance_angle(self, bbox: tuple): # type: ignore[no-untyped-def, type-arg] - """ - Estimate distance and angle to object using size-based estimation. - - Args: - bbox: tuple (x_min, y_min, x_max, y_max) - where y_max represents the bottom of the object - robot_pitch: Current pitch of the robot body (in radians) - If provided, this will be combined with the camera's fixed pitch - initial_distance: Initial distance estimate for the object (in meters) - Used to calibrate object size if not previously known - - Returns: - depth: distance to object along camera's z-axis (meters) - angle: horizontal angle in camera frame (radians, positive right) - or None, None if estimation not possible - """ - # If we don't have estimated object size and no initial distance is provided, - # we can't estimate the distance - if self.estimated_object_size is None: - return None, None - - x_min, y_min, x_max, y_max = bbox - - # Calculate center of the object for angle calculation - u_c = (x_min + x_max) / 2.0 - - # If we have an initial distance estimate and no object size yet, - # calculate and store the object size using the initial distance - object_height_px = y_max - y_min - depth = self.estimated_object_size * self.fy / object_height_px - - # Calculate horizontal angle from image center - angle = np.arctan((u_c - self.cx) / self.fx) - - return depth, angle - - -# Example usage: -if __name__ == "__main__": - # Example camera calibration - K = np.array([[600, 0, 320], [0, 600, 240], [0, 0, 1]], dtype=np.float32) - - # Camera mounted 1.2m high, pitched down 10 degrees - camera_pitch = np.deg2rad(0) # negative for downward pitch - camera_height = 1.0 # meters - - estimator = PersonDistanceEstimator(K, camera_pitch, camera_height) - object_estimator = ObjectDistanceEstimator(K, camera_pitch, camera_height) - - # Example detection - bbox = (300, 100, 380, 400) # x1, y1, x2, y2 - - depth, angle = estimator.estimate_distance_angle(bbox) - # Estimate object size based on the known distance - object_size = object_estimator.estimate_object_size(bbox, depth) - depth_obj, angle_obj = object_estimator.estimate_distance_angle(bbox) - - print(f"Estimated person depth: {depth:.2f} m") - print(f"Estimated person angle: {np.rad2deg(angle):.1f}°") - print(f"Estimated object depth: {depth_obj:.2f} m") - print(f"Estimated object angle: {np.rad2deg(angle_obj):.1f}°") - - # Shrink the bbox by 30 pixels while keeping the same center - x_min, y_min, x_max, y_max = bbox - width = x_max - x_min - height = y_max - y_min - center_x = (x_min + x_max) // 2 - center_y = (y_min + y_max) // 2 - - new_width = max(width - 20, 2) # Ensure width is at least 2 pixels - new_height = max(height - 20, 2) # Ensure height is at least 2 pixels - - x_min = center_x - new_width // 2 - x_max = center_x + new_width // 2 - y_min = center_y - new_height // 2 - y_max = center_y + new_height // 2 - - bbox = (x_min, y_min, x_max, y_max) - - # Re-estimate distance and angle with the new bbox - depth, angle = estimator.estimate_distance_angle(bbox) - depth_obj, angle_obj = object_estimator.estimate_distance_angle(bbox) - - print(f"New estimated person depth: {depth:.2f} m") - print(f"New estimated person angle: {np.rad2deg(angle):.1f}°") - print(f"New estimated object depth: {depth_obj:.2f} m") - print(f"New estimated object angle: {np.rad2deg(angle_obj):.1f}°") diff --git a/dimos/perception/demo_object_scene_registration.py b/dimos/perception/demo_object_scene_registration.py new file mode 100644 index 0000000000..96b25c54f1 --- /dev/null +++ b/dimos/perception/demo_object_scene_registration.py @@ -0,0 +1,41 @@ +#!/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 dimos.agents.agent import llm_agent +from dimos.agents.cli.human import human_input +from dimos.agents.spec import Provider +from dimos.core.blueprints import autoconnect +from dimos.hardware.sensors.camera.realsense import realsense_camera +from dimos.hardware.sensors.camera.zed import zed_camera +from dimos.perception.detection.detectors.yoloe import YoloePromptMode +from dimos.perception.object_scene_registration import object_scene_registration_module +from dimos.robot.foxglove_bridge import foxglove_bridge + +camera_choice = "zed" + +if camera_choice == "realsense": + camera_module = realsense_camera(enable_pointcloud=False) +elif camera_choice == "zed": + camera_module = zed_camera(enable_pointcloud=False) +else: + raise ValueError(f"Invalid camera choice: {camera_choice}") + +demo_object_scene_registration = autoconnect( + camera_module, + object_scene_registration_module(target_frame="world", prompt_mode=YoloePromptMode.PROMPT), + foxglove_bridge(), + human_input(), + llm_agent(), +).global_config(viewer_backend="foxglove") diff --git a/dimos/perception/detection/detectors/detic.py b/dimos/perception/detection/detectors/detic.py deleted file mode 100644 index 288a3e056d..0000000000 --- a/dimos/perception/detection/detectors/detic.py +++ /dev/null @@ -1,426 +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. - -from collections.abc import Sequence -import os -import sys - -import numpy as np - -# Add Detic to Python path -from dimos.constants import DIMOS_PROJECT_ROOT -from dimos.msgs.sensor_msgs import Image -from dimos.perception.detection.detectors.types import Detector -from dimos.perception.detection2d.utils import plot_results - -detic_path = DIMOS_PROJECT_ROOT / "dimos/models/Detic" -if str(detic_path) not in sys.path: - sys.path.append(str(detic_path)) - sys.path.append(str(detic_path / "third_party/CenterNet2")) - -# PIL patch for compatibility -import PIL.Image - -if not hasattr(PIL.Image, "LINEAR") and hasattr(PIL.Image, "BILINEAR"): - PIL.Image.LINEAR = PIL.Image.BILINEAR # type: ignore[attr-defined] - -# Detectron2 imports -from detectron2.config import get_cfg # type: ignore[import-not-found] -from detectron2.data import MetadataCatalog # type: ignore[import-not-found] - - -# Simple tracking implementation -class SimpleTracker: - """Simple IOU-based tracker implementation without external dependencies""" - - def __init__(self, iou_threshold: float = 0.3, max_age: int = 5) -> None: - self.iou_threshold = iou_threshold - self.max_age = max_age - self.next_id = 1 - self.tracks = {} # type: ignore[var-annotated] # id -> {bbox, class_id, age, mask, etc} - - def _calculate_iou(self, bbox1, bbox2): # type: ignore[no-untyped-def] - """Calculate IoU between two bboxes in format [x1,y1,x2,y2]""" - x1 = max(bbox1[0], bbox2[0]) - y1 = max(bbox1[1], bbox2[1]) - x2 = min(bbox1[2], bbox2[2]) - y2 = min(bbox1[3], bbox2[3]) - - if x2 < x1 or y2 < y1: - return 0.0 - - intersection = (x2 - x1) * (y2 - y1) - area1 = (bbox1[2] - bbox1[0]) * (bbox1[3] - bbox1[1]) - area2 = (bbox2[2] - bbox2[0]) * (bbox2[3] - bbox2[1]) - union = area1 + area2 - intersection - - return intersection / union if union > 0 else 0 - - def update(self, detections, masks): # type: ignore[no-untyped-def] - """Update tracker with new detections - - Args: - detections: List of [x1,y1,x2,y2,score,class_id] - masks: List of segmentation masks corresponding to detections - - Returns: - List of [track_id, bbox, score, class_id, mask] - """ - if len(detections) == 0: - # Age existing tracks - for track_id in list(self.tracks.keys()): - self.tracks[track_id]["age"] += 1 - # Remove old tracks - if self.tracks[track_id]["age"] > self.max_age: - del self.tracks[track_id] - return [] - - # Convert to numpy for easier handling - if not isinstance(detections, np.ndarray): - detections = np.array(detections) - - result = [] - matched_indices = set() - - # Update existing tracks - for track_id, track in list(self.tracks.items()): - track["age"] += 1 - - if track["age"] > self.max_age: - del self.tracks[track_id] - continue - - # Find best matching detection for this track - best_iou = self.iou_threshold - best_idx = -1 - - for i, det in enumerate(detections): - if i in matched_indices: - continue - - # Check class match - if det[5] != track["class_id"]: - continue - - iou = self._calculate_iou(track["bbox"], det[:4]) # type: ignore[no-untyped-call] - if iou > best_iou: - best_iou = iou - best_idx = i - - # If we found a match, update the track - if best_idx >= 0: - self.tracks[track_id]["bbox"] = detections[best_idx][:4] - self.tracks[track_id]["score"] = detections[best_idx][4] - self.tracks[track_id]["age"] = 0 - self.tracks[track_id]["mask"] = masks[best_idx] - matched_indices.add(best_idx) - - # Add to results with mask - result.append( - [ - track_id, - detections[best_idx][:4], - detections[best_idx][4], - int(detections[best_idx][5]), - self.tracks[track_id]["mask"], - ] - ) - - # Create new tracks for unmatched detections - for i, det in enumerate(detections): - if i in matched_indices: - continue - - # Create new track - new_id = self.next_id - self.next_id += 1 - - self.tracks[new_id] = { - "bbox": det[:4], - "score": det[4], - "class_id": int(det[5]), - "age": 0, - "mask": masks[i], - } - - # Add to results with mask directly from the track - result.append([new_id, det[:4], det[4], int(det[5]), masks[i]]) - - return result - - -class Detic2DDetector(Detector): - def __init__( # type: ignore[no-untyped-def] - self, model_path=None, device: str = "cuda", vocabulary=None, threshold: float = 0.5 - ) -> None: - """ - Initialize the Detic detector with open vocabulary support. - - Args: - model_path (str): Path to a custom Detic model weights (optional) - device (str): Device to run inference on ('cuda' or 'cpu') - vocabulary (list): Custom vocabulary (list of class names) or 'lvis', 'objects365', 'openimages', 'coco' - threshold (float): Detection confidence threshold - """ - self.device = device - self.threshold = threshold - - # Set up Detic paths - already added to sys.path at module level - - # Import Detic modules - from centernet.config import add_centernet_config # type: ignore[import-not-found] - from detic.config import add_detic_config # type: ignore[import-not-found] - from detic.modeling.text.text_encoder import ( # type: ignore[import-not-found] - build_text_encoder, - ) - from detic.modeling.utils import reset_cls_test # type: ignore[import-not-found] - - # Keep reference to these functions for later use - self.reset_cls_test = reset_cls_test - self.build_text_encoder = build_text_encoder - - # Setup model configuration - self.cfg = get_cfg() - add_centernet_config(self.cfg) - add_detic_config(self.cfg) - - # Use default Detic config - self.cfg.merge_from_file( - os.path.join( - detic_path, "configs/Detic_LCOCOI21k_CLIP_SwinB_896b32_4x_ft4x_max-size.yaml" - ) - ) - - # Set default weights if not provided - if model_path is None: - self.cfg.MODEL.WEIGHTS = "https://dl.fbaipublicfiles.com/detic/Detic_LCOCOI21k_CLIP_SwinB_896b32_4x_ft4x_max-size.pth" - else: - self.cfg.MODEL.WEIGHTS = model_path - - # Set device - if device == "cpu": - self.cfg.MODEL.DEVICE = "cpu" - - # Set detection threshold - self.cfg.MODEL.ROI_HEADS.SCORE_THRESH_TEST = threshold - self.cfg.MODEL.ROI_BOX_HEAD.ZEROSHOT_WEIGHT_PATH = "rand" - self.cfg.MODEL.ROI_HEADS.ONE_CLASS_PER_PROPOSAL = True - - # Built-in datasets for Detic - use absolute paths with detic_path - self.builtin_datasets = { - "lvis": { - "metadata": "lvis_v1_val", - "classifier": os.path.join( - detic_path, "datasets/metadata/lvis_v1_clip_a+cname.npy" - ), - }, - "objects365": { - "metadata": "objects365_v2_val", - "classifier": os.path.join( - detic_path, "datasets/metadata/o365_clip_a+cnamefix.npy" - ), - }, - "openimages": { - "metadata": "oid_val_expanded", - "classifier": os.path.join(detic_path, "datasets/metadata/oid_clip_a+cname.npy"), - }, - "coco": { - "metadata": "coco_2017_val", - "classifier": os.path.join(detic_path, "datasets/metadata/coco_clip_a+cname.npy"), - }, - } - - # Override config paths to use absolute paths - self.cfg.MODEL.ROI_BOX_HEAD.CAT_FREQ_PATH = os.path.join( - detic_path, "datasets/metadata/lvis_v1_train_cat_info.json" - ) - - # Initialize model - self.predictor = None - - # Setup with initial vocabulary - vocabulary = vocabulary or "lvis" - self.setup_vocabulary(vocabulary) # type: ignore[no-untyped-call] - - # Initialize our simple tracker - self.tracker = SimpleTracker(iou_threshold=0.5, max_age=5) - - def setup_vocabulary(self, vocabulary): # type: ignore[no-untyped-def] - """ - Setup the model's vocabulary. - - Args: - vocabulary: Either a string ('lvis', 'objects365', 'openimages', 'coco') - or a list of class names for custom vocabulary. - """ - if self.predictor is None: - # Initialize the model - from detectron2.engine import DefaultPredictor # type: ignore[import-not-found] - - self.predictor = DefaultPredictor(self.cfg) - - if isinstance(vocabulary, str) and vocabulary in self.builtin_datasets: - # Use built-in dataset - dataset = vocabulary - metadata = MetadataCatalog.get(self.builtin_datasets[dataset]["metadata"]) - classifier = self.builtin_datasets[dataset]["classifier"] - num_classes = len(metadata.thing_classes) - self.class_names = metadata.thing_classes - else: - # Use custom vocabulary - if isinstance(vocabulary, str): - # If it's a string but not a built-in dataset, treat as a file - try: - with open(vocabulary) as f: - class_names = [line.strip() for line in f if line.strip()] - except: - # Default to LVIS if there's an issue - print(f"Error loading vocabulary from {vocabulary}, using LVIS") - return self.setup_vocabulary("lvis") # type: ignore[no-untyped-call] - else: - # Assume it's a list of class names - class_names = vocabulary - - # Create classifier from text embeddings - metadata = MetadataCatalog.get("__unused") - metadata.thing_classes = class_names - self.class_names = class_names - - # Generate CLIP embeddings for custom vocabulary - classifier = self._get_clip_embeddings(class_names) - num_classes = len(class_names) - - # Reset model with new vocabulary - self.reset_cls_test(self.predictor.model, classifier, num_classes) # type: ignore[attr-defined] - return self.class_names - - def _get_clip_embeddings(self, vocabulary, prompt: str = "a "): # type: ignore[no-untyped-def] - """ - Generate CLIP embeddings for a vocabulary list. - - Args: - vocabulary (list): List of class names - prompt (str): Prompt prefix to use for CLIP - - Returns: - torch.Tensor: Tensor of embeddings - """ - text_encoder = self.build_text_encoder(pretrain=True) - text_encoder.eval() - texts = [prompt + x for x in vocabulary] - emb = text_encoder(texts).detach().permute(1, 0).contiguous().cpu() - return emb - - def process_image(self, image: Image): # type: ignore[no-untyped-def] - """ - Process an image and return detection results. - - Args: - image: Input image in BGR format (OpenCV) - - Returns: - tuple: (bboxes, track_ids, class_ids, confidences, names, masks) - - bboxes: list of [x1, y1, x2, y2] coordinates - - track_ids: list of tracking IDs (or -1 if no tracking) - - class_ids: list of class indices - - confidences: list of detection confidences - - names: list of class names - - masks: list of segmentation masks (numpy arrays) - """ - # Run inference with Detic - outputs = self.predictor(image.to_opencv()) # type: ignore[misc] - instances = outputs["instances"].to("cpu") - - # Extract bounding boxes, classes, scores, and masks - if len(instances) == 0: - return [], [], [], [], [] # , [] - - boxes = instances.pred_boxes.tensor.numpy() - class_ids = instances.pred_classes.numpy() - scores = instances.scores.numpy() - masks = instances.pred_masks.numpy() - - # Convert boxes to [x1, y1, x2, y2] format - bboxes = [] - for box in boxes: - x1, y1, x2, y2 = box.tolist() - bboxes.append([x1, y1, x2, y2]) - - # Get class names - [self.class_names[class_id] for class_id in class_ids] - - # Apply tracking - detections = [] - filtered_masks = [] - for i, bbox in enumerate(bboxes): - if scores[i] >= self.threshold: - # Format for tracker: [x1, y1, x2, y2, score, class_id] - detections.append([*bbox, scores[i], class_ids[i]]) - filtered_masks.append(masks[i]) - - if not detections: - return [], [], [], [], [] # , [] - - # Update tracker with detections and correctly aligned masks - track_results = self.tracker.update(detections, filtered_masks) # type: ignore[no-untyped-call] - - # Process tracking results - track_ids = [] - tracked_bboxes = [] - tracked_class_ids = [] - tracked_scores = [] - tracked_names = [] - tracked_masks = [] - - for track_id, bbox, score, class_id, mask in track_results: - track_ids.append(int(track_id)) - tracked_bboxes.append(bbox.tolist() if isinstance(bbox, np.ndarray) else bbox) - tracked_class_ids.append(int(class_id)) - tracked_scores.append(score) - tracked_names.append(self.class_names[int(class_id)]) - tracked_masks.append(mask) - - return ( - tracked_bboxes, - track_ids, - tracked_class_ids, - tracked_scores, - tracked_names, - # tracked_masks, - ) - - def visualize_results( # type: ignore[no-untyped-def] - self, image, bboxes, track_ids, class_ids, confidences, names: Sequence[str] - ): - """ - Generate visualization of detection results. - - Args: - image: Original input image - bboxes: List of bounding boxes - track_ids: List of tracking IDs - class_ids: List of class indices - confidences: List of detection confidences - names: List of class names - - Returns: - Image with visualized detections - """ - - return plot_results(image, bboxes, track_ids, class_ids, confidences, names) - - def cleanup(self) -> None: - """Clean up resources.""" - # Nothing specific to clean up for Detic - pass diff --git a/dimos/perception/detection/detectors/person/yolo.py b/dimos/perception/detection/detectors/person/yolo.py index 519f45f2f6..75d9a47921 100644 --- a/dimos/perception/detection/detectors/person/yolo.py +++ b/dimos/perception/detection/detectors/person/yolo.py @@ -12,13 +12,15 @@ # See the License for the specific language governing permissions and # limitations under the License. +from typing import Any + from ultralytics import YOLO # type: ignore[attr-defined, import-not-found] from dimos.msgs.sensor_msgs import Image from dimos.perception.detection.detectors.types import Detector from dimos.perception.detection.type import ImageDetections2D from dimos.utils.data import get_data -from dimos.utils.gpu_utils import is_cuda_available +from dimos.utils.gpu_utils import is_cuda_available # type: ignore[attr-defined] from dimos.utils.logging_config import setup_logger logger = setup_logger() @@ -46,7 +48,7 @@ def __init__( self.device = "cpu" logger.info("Using CPU for YOLO person detector") - def process_image(self, image: Image) -> ImageDetections2D: + def process_image(self, image: Image) -> "ImageDetections2D[Any]": # type: ignore[override] """Process image and return detection results. Args: diff --git a/dimos/perception/detection/detectors/types.py b/dimos/perception/detection/detectors/types.py index e85c5ae18e..5c81feccc2 100644 --- a/dimos/perception/detection/detectors/types.py +++ b/dimos/perception/detection/detectors/types.py @@ -13,6 +13,7 @@ # limitations under the License. from abc import ABC, abstractmethod +from typing import Any from dimos.msgs.sensor_msgs import Image from dimos.perception.detection.type import ImageDetections2D @@ -20,4 +21,4 @@ class Detector(ABC): @abstractmethod - def process_image(self, image: Image) -> ImageDetections2D: ... + def process_image(self, image: Image) -> ImageDetections2D[Any]: ... diff --git a/dimos/perception/detection/detectors/yolo.py b/dimos/perception/detection/detectors/yolo.py index c9a65a120e..4a7ee1ff06 100644 --- a/dimos/perception/detection/detectors/yolo.py +++ b/dimos/perception/detection/detectors/yolo.py @@ -12,6 +12,8 @@ # See the License for the specific language governing permissions and # limitations under the License. +from typing import Any + from ultralytics import YOLO # type: ignore[attr-defined, import-not-found] from dimos.msgs.sensor_msgs import Image @@ -47,7 +49,7 @@ def __init__( self.device = "cpu" logger.debug("Using CPU for YOLO 2d detector") - def process_image(self, image: Image) -> ImageDetections2D: + def process_image(self, image: Image) -> ImageDetections2D[Any]: """ Process an image and return detection results. diff --git a/dimos/perception/detection/detectors/yoloe.py b/dimos/perception/detection/detectors/yoloe.py new file mode 100644 index 0000000000..960ed1e2b6 --- /dev/null +++ b/dimos/perception/detection/detectors/yoloe.py @@ -0,0 +1,177 @@ +# 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 enum import Enum +import threading +from typing import Any + +import numpy as np +from numpy.typing import NDArray +from ultralytics import YOLOE # type: ignore[attr-defined] + +from dimos.msgs.sensor_msgs import Image +from dimos.perception.detection.detectors.types import Detector +from dimos.perception.detection.type import ImageDetections2D +from dimos.utils.data import get_data +from dimos.utils.gpu_utils import is_cuda_available + + +class YoloePromptMode(Enum): + """YOLO-E prompt modes.""" + + LRPC = "lrpc" + PROMPT = "prompt" + + +class Yoloe2DDetector(Detector): + def __init__( + self, + model_path: str = "models_yoloe", + model_name: str | None = None, + device: str | None = None, + prompt_mode: YoloePromptMode = YoloePromptMode.LRPC, + exclude_class_ids: list[int] | None = None, + max_area_ratio: float | None = 0.3, + ) -> None: + """ + Initialize YOLO-E 2D detector. + + Args: + model_path: Path to model directory (fetched via get_data from LFS). + model_name: Model filename. Defaults based on prompt_mode. + device: Device to run inference on ('cuda', 'cpu', or None for auto). + prompt_mode: LRPC for prompt-free detection, PROMPT for text/visual prompting. + exclude_class_ids: Class IDs to filter out from results (pass [] to disable). + max_area_ratio: Maximum bbox area ratio (0-1) relative to image. + """ + if model_name is None: + if prompt_mode == YoloePromptMode.LRPC: + model_name = "yoloe-11s-seg-pf.pt" + else: + model_name = "yoloe-11s-seg.pt" + + self.model = YOLOE(get_data(model_path) / model_name) + self.prompt_mode = prompt_mode + self._visual_prompts: dict[str, NDArray[Any]] | None = None + self.max_area_ratio = max_area_ratio + self._lock = threading.Lock() + + if prompt_mode == YoloePromptMode.PROMPT: + self.set_prompts(text=["nothing"]) + self.exclude_class_ids = set(exclude_class_ids) if exclude_class_ids else set() + + if self.max_area_ratio is not None and not (0.0 < self.max_area_ratio <= 1.0): + raise ValueError("max_area_ratio must be in the range (0, 1].") + + if device: + self.device = device + elif is_cuda_available(): # type: ignore[no-untyped-call] + self.device = "cuda" + else: + self.device = "cpu" + + def set_prompts( + self, + text: list[str] | None = None, + bboxes: NDArray[np.float64] | None = None, + ) -> None: + """ + Set prompts for detection. Provide either text or bboxes, not both. + + Args: + text: List of class names to detect. + bboxes: Bounding boxes in xyxy format, shape (N, 4). + """ + if text is not None and bboxes is not None: + raise ValueError("Provide either text or bboxes, not both.") + if text is None and bboxes is None: + raise ValueError("Must provide either text or bboxes.") + + with self._lock: + self.model.predictor = None + if text is not None: + self.model.set_classes(text, self.model.get_text_pe(text)) # type: ignore[no-untyped-call] + self._visual_prompts = None + else: + cls = np.arange(len(bboxes), dtype=np.int16) # type: ignore[arg-type] + self._visual_prompts = {"bboxes": bboxes, "cls": cls} # type: ignore[dict-item] + + def process_image(self, image: Image) -> "ImageDetections2D[Any]": # type: ignore[override] + """ + Process an image and return detection results. + + Args: + image: Input image + + Returns: + ImageDetections2D containing all detected objects + """ + track_kwargs = { + "source": image.to_opencv(), + "device": self.device, + "conf": 0.6, + "iou": 0.6, + "persist": True, + "verbose": False, + } + + with self._lock: + if self._visual_prompts is not None: + track_kwargs["visual_prompts"] = self._visual_prompts + + results = self.model.track(**track_kwargs) # type: ignore[arg-type] + + detections = ImageDetections2D.from_ultralytics_result(image, results) + return self._apply_filters(image, detections) + + def _apply_filters( + self, + image: Image, + detections: "ImageDetections2D[Any]", + ) -> "ImageDetections2D[Any]": + if not self.exclude_class_ids and self.max_area_ratio is None: + return detections + + predicates = [] + + if self.exclude_class_ids: + predicates.append(lambda det: det.class_id not in self.exclude_class_ids) + + if self.max_area_ratio is not None: + image_area = image.width * image.height + + def area_filter(det): # type: ignore[no-untyped-def] + if image_area <= 0: + return True + return (det.bbox_2d_volume() / image_area) <= self.max_area_ratio + + predicates.append(area_filter) + + filtered = detections.detections + for predicate in predicates: + filtered = [det for det in filtered if predicate(det)] # type: ignore[no-untyped-call] + + return ImageDetections2D(image, filtered) + + def stop(self) -> None: + """Clean up resources used by the detector.""" + if hasattr(self.model, "predictor") and self.model.predictor is not None: + predictor = self.model.predictor + if hasattr(predictor, "trackers") and predictor.trackers: + for tracker in predictor.trackers: + if hasattr(tracker, "tracker") and hasattr(tracker.tracker, "gmc"): + gmc = tracker.tracker.gmc + if hasattr(gmc, "executor") and gmc.executor is not None: + gmc.executor.shutdown(wait=True) + self.model.predictor = None diff --git a/dimos/perception/detection/module2D.py b/dimos/perception/detection/module2D.py index cfca3b2192..5eb479e03e 100644 --- a/dimos/perception/detection/module2D.py +++ b/dimos/perception/detection/module2D.py @@ -73,7 +73,7 @@ def __init__(self, *args, **kwargs) -> None: # type: ignore[no-untyped-def] self.vlm_detections_subject = Subject() # type: ignore[var-annotated] self.previous_detection_count = 0 - def process_image_frame(self, image: Image) -> ImageDetections2D: + def process_image_frame(self, image: Image) -> ImageDetections2D[Any]: imageDetections = self.detector.process_image(image) if not self.config.filter: return imageDetections @@ -88,10 +88,10 @@ def sharp_image_stream(self) -> Observable[Image]: ) @simple_mcache - def detection_stream_2d(self) -> Observable[ImageDetections2D]: + def detection_stream_2d(self) -> Observable[ImageDetections2D[Any]]: return backpressure(self.sharp_image_stream().pipe(ops.map(self.process_image_frame))) - def track(self, detections: ImageDetections2D) -> None: + def track(self, detections: ImageDetections2D[Any]) -> None: sensor_frame = self.tf.get("sensor", "camera_optical", detections.image.ts, 5.0) if not sensor_frame: @@ -144,7 +144,7 @@ def start(self) -> None: lambda det: self.annotations.publish(det.to_foxglove_annotations()) ) - def publish_cropped_images(detections: ImageDetections2D) -> None: + def publish_cropped_images(detections: ImageDetections2D[Any]) -> None: for index, detection in enumerate(detections[:3]): image_topic = getattr(self, "detected_image_" + str(index)) image_topic.publish(detection.cropped_image()) diff --git a/dimos/perception/detection/module3D.py b/dimos/perception/detection/module3D.py index 037376f995..1804e0e9cd 100644 --- a/dimos/perception/detection/module3D.py +++ b/dimos/perception/detection/module3D.py @@ -13,6 +13,8 @@ # limitations under the License. +from typing import Any + from dimos_lcm.foxglove_msgs.ImageAnnotations import ( ImageAnnotations, ) @@ -59,7 +61,7 @@ class Detection3DModule(Detection2DModule): def process_frame( self, - detections: ImageDetections2D, + detections: ImageDetections2D[Any], pointcloud: PointCloud2, transform: Transform, ) -> ImageDetections3DPC: @@ -138,7 +140,7 @@ def nav_vlm(self, question: str) -> str: if isinstance(result, str) or not result or not len(result): return None # type: ignore[return-value] - detections: ImageDetections2D = result + detections: ImageDetections2D[Any] = result print(detections) if not len(detections): @@ -148,7 +150,7 @@ def nav_vlm(self, question: str) -> str: pc = self.pointcloud.get_next() transform = self.tf.get("camera_optical", pc.frame_id, detections.image.ts, 5.0) - detections3d = self.process_frame(detections, pc, transform) + detections3d = self.process_frame(detections, pc, transform) # type: ignore[arg-type] if len(detections3d): return detections3d[0].pose # type: ignore[no-any-return] diff --git a/dimos/perception/detection/objectDB.py b/dimos/perception/detection/objectDB.py new file mode 100644 index 0000000000..850ee367f0 --- /dev/null +++ b/dimos/perception/detection/objectDB.py @@ -0,0 +1,306 @@ +# 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 threading +import time +from typing import TYPE_CHECKING, Any + +from dimos.utils.logging_config import setup_logger + +if TYPE_CHECKING: + from dimos.msgs.geometry_msgs import Vector3 + from dimos.perception.detection.type.detection3d.object import Object + +logger = setup_logger() + + +class ObjectDB: + """Spatial memory database for 3D object detections. + + Maintains two tiers of objects internally: + - _pending_objects: Recently detected objects (detection_count < threshold) + - _objects: Confirmed permanent objects (detection_count >= threshold) + + Deduplication uses two heuristics: + 1. track_id match from YOLOE tracker (recent match) + 2. Center distance within threshold (spatial proximity match) + """ + + def __init__( + self, + distance_threshold: float = 0.15, + min_detections_for_permanent: int = 6, + pending_ttl_s: float = 5.0, + track_id_ttl_s: float = 2.0, + ) -> None: + self._distance_threshold = distance_threshold + self._min_detections = min_detections_for_permanent + self._pending_ttl_s = pending_ttl_s + self._track_id_ttl_s = track_id_ttl_s + + # Internal storage - keyed by object_id + self._pending_objects: dict[str, Object] = {} + self._objects: dict[str, Object] = {} # Permanent objects + + # track_id -> object_id mapping for fast lookup + self._track_id_map: dict[int, str] = {} + self._last_add_stats: dict[str, int] = {} + + self._lock = threading.RLock() + + # ───────────────────────────────────────────────────────────────── + # Public Methods + # ───────────────────────────────────────────────────────────────── + + def add_objects(self, objects: list[Object]) -> list[Object]: + """Add multiple objects to the database with deduplication. + + Args: + objects: List of Object instances from object_scene_registration + + Returns: + List of updated/created Object instances + """ + stats = { + "input": len(objects), + "created": 0, + "updated": 0, + "promoted": 0, + "matched_track": 0, + "matched_distance": 0, + } + + results: list[Object] = [] + now = time.time() + with self._lock: + self._prune_stale_pending(now) + for obj in objects: + matched, reason = self._match(obj, now) + if matched is None: + results.append(self._insert_pending(obj, now)) + stats["created"] += 1 + continue + + self._update_existing(matched, obj, now) + results.append(matched) + stats["updated"] += 1 + if reason == "track": + stats["matched_track"] += 1 + elif reason == "distance": + stats["matched_distance"] += 1 + if self._check_promotion(matched): + stats["promoted"] += 1 + + stats["pending"] = len(self._pending_objects) + stats["permanent"] = len(self._objects) + self._last_add_stats = stats + return results + + def get_last_add_stats(self) -> dict[str, int]: + with self._lock: + return dict(self._last_add_stats) + + def get_objects(self) -> list[Object]: + """Get all permanent objects (detection_count >= threshold).""" + with self._lock: + return list(self._objects.values()) + + def get_all_objects(self) -> list[Object]: + """Get all objects (both pending and permanent).""" + with self._lock: + return list(self._pending_objects.values()) + list(self._objects.values()) + + def promote(self, object_id: str) -> bool: + """Promote an object from pending to permanent.""" + with self._lock: + if object_id in self._pending_objects: + self._objects[object_id] = self._pending_objects.pop(object_id) + return True + return object_id in self._objects + + def find_by_name(self, name: str) -> list[Object]: + """Find all permanent objects with matching name.""" + with self._lock: + return [obj for obj in self._objects.values() if obj.name == name] + + def find_nearest( + self, + position: Vector3, + name: str | None = None, + ) -> Object | None: + """Find nearest permanent object to a position, optionally filtered by name. + + Args: + position: Position to search from + name: Optional name filter + + Returns: + Nearest Object or None if no objects found + """ + with self._lock: + candidates = [ + obj + for obj in self._objects.values() + if obj.center is not None and (name is None or obj.name == name) + ] + + if not candidates: + return None + + return min(candidates, key=lambda obj: position.distance(obj.center)) # type: ignore[arg-type] + + def clear(self) -> None: + """Clear all objects from the database.""" + with self._lock: + # Drop Open3D pointcloud references before clearing to reduce shutdown warnings. + for obj in list(self._pending_objects.values()) + list(self._objects.values()): + if obj.pointcloud is not None: + obj.pointcloud = None + self._pending_objects.clear() + self._objects.clear() + self._track_id_map.clear() + logger.info("ObjectDB cleared") + + def get_stats(self) -> dict[str, int]: + """Get statistics about the database.""" + with self._lock: + return { + "pending_count": len(self._pending_objects), + "permanent_count": len(self._objects), + "total_count": len(self._pending_objects) + len(self._objects), + } + + # ───────────────────────────────────────────────────────────────── + # Internal Methods + # ───────────────────────────────────────────────────────────────── + + def _match(self, obj: Object, now: float) -> tuple[Object | None, str | None]: + if obj.track_id >= 0: + matched = self._match_by_track_id(obj.track_id, now) + if matched is not None: + return matched, "track" + + matched = self._match_by_distance(obj) + if matched is not None: + return matched, "distance" + return None, None + + def _insert_pending(self, obj: Object, now: float) -> Object: + if not obj.ts: + obj.ts = now + self._pending_objects[obj.object_id] = obj + if obj.track_id >= 0: + self._track_id_map[obj.track_id] = obj.object_id + logger.info(f"Created new pending object {obj.object_id} ({obj.name})") + return obj + + def _update_existing(self, existing: Object, obj: Object, now: float) -> None: + existing.update_object(obj) + existing.ts = obj.ts or now + if obj.track_id >= 0: + self._track_id_map[obj.track_id] = existing.object_id + + def _match_by_track_id(self, track_id: int, now: float) -> Object | None: + """Find object with matching track_id from YOLOE.""" + if track_id < 0: + return None + + object_id = self._track_id_map.get(track_id) + if object_id is None: + return None + + # Check in permanent objects first + if object_id in self._objects: + obj = self._objects[object_id] + elif object_id in self._pending_objects: + obj = self._pending_objects[object_id] + else: + del self._track_id_map[track_id] + return None + + last_seen = obj.ts if obj.ts else now + if now - last_seen > self._track_id_ttl_s: + del self._track_id_map[track_id] + return None + + return obj + + def _match_by_distance(self, obj: Object) -> Object | None: + """Find object within distance threshold.""" + if obj.center is None: + return None + + # Combine all objects and filter by valid center + all_objects = list(self._objects.values()) + list(self._pending_objects.values()) + candidates = [ + o + for o in all_objects + if o.center is not None and obj.center.distance(o.center) < self._distance_threshold + ] + + if not candidates: + return None + + return min(candidates, key=lambda o: obj.center.distance(o.center)) # type: ignore[union-attr] + + def _prune_stale_pending(self, now: float) -> None: + if self._pending_ttl_s <= 0: + return + cutoff = now - self._pending_ttl_s + stale_ids = [ + obj_id for obj_id, obj in self._pending_objects.items() if (obj.ts or now) < cutoff + ] + for obj_id in stale_ids: + del self._pending_objects[obj_id] + for track_id, mapped_id in list(self._track_id_map.items()): + if mapped_id == obj_id: + del self._track_id_map[track_id] + + def _check_promotion(self, obj: Object) -> bool: + """Move object from pending to permanent if threshold met.""" + if obj.detections_count >= self._min_detections: + # Check if it's in pending + if obj.object_id in self._pending_objects: + # Promote to permanent + del self._pending_objects[obj.object_id] + self._objects[obj.object_id] = obj + logger.info( + f"Promoted object {obj.object_id} ({obj.name}) to permanent " + f"with {obj.detections_count} detections" + ) + return True + return False + + # ───────────────────────────────────────────────────────────────── + # Agent encoding + # ───────────────────────────────────────────────────────────────── + + def agent_encode(self) -> list[dict[str, Any]]: + """Encode permanent objects for agent consumption.""" + with self._lock: + return [obj.agent_encode() for obj in self._objects.values()] + + def __len__(self) -> int: + """Return number of permanent objects.""" + with self._lock: + return len(self._objects) + + def __repr__(self) -> str: + with self._lock: + return f"ObjectDB(permanent={len(self._objects)}, pending={len(self._pending_objects)})" + + +__all__ = ["ObjectDB"] diff --git a/dimos/perception/detection/person_tracker.py b/dimos/perception/detection/person_tracker.py index 6212080858..ad37901408 100644 --- a/dimos/perception/detection/person_tracker.py +++ b/dimos/perception/detection/person_tracker.py @@ -73,7 +73,7 @@ def center_to_3d( # Transformation: x_link = z_optical, y_link = -x_optical, z_link = -y_optical return Vector3(z_optical, -x_optical, -y_optical) - def detections_stream(self) -> Observable[ImageDetections2D]: + def detections_stream(self) -> Observable[ImageDetections2D[Any]]: return backpressure( align_timestamped( self.color_image.pure_observable(), @@ -84,8 +84,9 @@ def detections_stream(self) -> Observable[ImageDetections2D]: buffer_size=2.0, ).pipe( ops.map( - lambda pair: ImageDetections2D.from_ros_detection2d_array( # type: ignore[misc] - *pair + lambda pair: ImageDetections2D.from_ros_detection2d_array( + pair[0], + pair[1], # type: ignore[index, arg-type] ) ) ) @@ -99,7 +100,7 @@ def start(self) -> None: def stop(self) -> None: super().stop() - def track(self, detections2D: ImageDetections2D) -> None: + def track(self, detections2D: ImageDetections2D[Any]) -> None: if len(detections2D) == 0: return diff --git a/dimos/perception/detection/reid/module.py b/dimos/perception/detection/reid/module.py index 4e239da39a..8d0acaebec 100644 --- a/dimos/perception/detection/reid/module.py +++ b/dimos/perception/detection/reid/module.py @@ -12,6 +12,8 @@ # See the License for the specific language governing permissions and # limitations under the License. +from typing import Any + from dimos_lcm.foxglove_msgs.ImageAnnotations import ( ImageAnnotations, TextAnnotation, @@ -56,7 +58,7 @@ def __init__(self, idsystem: IDSystem | None = None, **kwargs) -> None: # type: self.idsystem = idsystem - def detections_stream(self) -> Observable[ImageDetections2D]: + def detections_stream(self) -> Observable[ImageDetections2D[Any]]: return backpressure( align_timestamped( self.image.pure_observable(), @@ -65,7 +67,7 @@ def detections_stream(self) -> Observable[ImageDetections2D]: ), match_tolerance=0.0, buffer_size=2.0, - ).pipe(ops.map(lambda pair: ImageDetections2D.from_ros_detection2d_array(*pair))) # type: ignore[misc] + ).pipe(ops.map(lambda pair: ImageDetections2D.from_ros_detection2d_array(*pair))) # type: ignore[misc, arg-type] ) @rpc @@ -76,7 +78,7 @@ def start(self) -> None: def stop(self) -> None: super().stop() - def ingress(self, imageDetections: ImageDetections2D) -> None: + def ingress(self, imageDetections: ImageDetections2D[Any]) -> None: text_annotations = [] for detection in imageDetections: diff --git a/dimos/perception/detection/reid/type.py b/dimos/perception/detection/reid/type.py index 28ea719f81..62c7449578 100644 --- a/dimos/perception/detection/reid/type.py +++ b/dimos/perception/detection/reid/type.py @@ -15,6 +15,7 @@ from __future__ import annotations from abc import ABC, abstractmethod +from typing import Any from dimos.perception.detection.type import Detection2DBBox, ImageDetections2D @@ -22,7 +23,7 @@ class IDSystem(ABC): """Abstract base class for ID assignment systems.""" - def register_detections(self, detections: ImageDetections2D) -> None: + def register_detections(self, detections: ImageDetections2D[Any]) -> None: """Register multiple detections.""" for detection in detections.detections: if isinstance(detection, Detection2DBBox): diff --git a/dimos/perception/detection/type/detection2d/__init__.py b/dimos/perception/detection/type/detection2d/__init__.py index ad3b7fa62e..8994d840b6 100644 --- a/dimos/perception/detection/type/detection2d/__init__.py +++ b/dimos/perception/detection/type/detection2d/__init__.py @@ -17,11 +17,13 @@ from dimos.perception.detection.type.detection2d.imageDetections2D import ImageDetections2D from dimos.perception.detection.type.detection2d.person import Detection2DPerson from dimos.perception.detection.type.detection2d.point import Detection2DPoint +from dimos.perception.detection.type.detection2d.seg import Detection2DSeg __all__ = [ "Detection2D", "Detection2DBBox", "Detection2DPerson", "Detection2DPoint", + "Detection2DSeg", "ImageDetections2D", ] diff --git a/dimos/perception/detection/type/detection2d/imageDetections2D.py b/dimos/perception/detection/type/detection2d/imageDetections2D.py index 680f9dd117..aa57b45aa7 100644 --- a/dimos/perception/detection/type/detection2d/imageDetections2D.py +++ b/dimos/perception/detection/type/detection2d/imageDetections2D.py @@ -16,26 +16,32 @@ from typing import TYPE_CHECKING, Generic +import cv2 +import numpy as np from typing_extensions import TypeVar +from dimos.msgs.sensor_msgs import Image from dimos.perception.detection.type.detection2d.base import Detection2D from dimos.perception.detection.type.detection2d.bbox import Detection2DBBox +from dimos.perception.detection.type.detection2d.person import Detection2DPerson +from dimos.perception.detection.type.detection2d.seg import Detection2DSeg from dimos.perception.detection.type.imageDetections import ImageDetections if TYPE_CHECKING: - from dimos_lcm.vision_msgs import Detection2DArray - from ultralytics.engine.results import Results # type: ignore[import-not-found] + from ultralytics.engine.results import Results - from dimos.msgs.sensor_msgs import Image + from dimos.msgs.vision_msgs import Detection2DArray -# TypeVar with default - Detection2DBBox is the default when no type param given -T2D = TypeVar("T2D", bound=Detection2D, default=Detection2DBBox) +T2D = TypeVar("T2D", bound=Detection2D) class ImageDetections2D(ImageDetections[T2D], Generic[T2D]): @classmethod def from_ros_detection2d_array( # type: ignore[no-untyped-def] - cls, image: Image, ros_detections: Detection2DArray, **kwargs + cls, + image: Image, + ros_detections: Detection2DArray, + **kwargs, # type: ignore[name-defined] ) -> ImageDetections2D[Detection2DBBox]: """Convert from ROS Detection2DArray message to ImageDetections2D object.""" detections: list[Detection2DBBox] = [] @@ -47,24 +53,25 @@ def from_ros_detection2d_array( # type: ignore[no-untyped-def] return ImageDetections2D(image=image, detections=detections) @classmethod - def from_ultralytics_result( # type: ignore[no-untyped-def] - cls, image: Image, results: list[Results], **kwargs + def from_ultralytics_result( + cls, + image: Image, + results: list[Results], ) -> ImageDetections2D[Detection2DBBox]: """Create ImageDetections2D from ultralytics Results. Dispatches to appropriate Detection2D subclass based on result type: + - If masks present: creates Detection2DSeg - If keypoints present: creates Detection2DPerson - Otherwise: creates Detection2DBBox Args: image: Source image results: List of ultralytics Results objects - **kwargs: Additional arguments passed to detection constructors Returns: ImageDetections2D containing appropriate detection types """ - from dimos.perception.detection.type.detection2d.person import Detection2DPerson detections: list[Detection2DBBox] = [] for result in results: @@ -73,8 +80,11 @@ def from_ultralytics_result( # type: ignore[no-untyped-def] num_detections = len(result.boxes.xyxy) for i in range(num_detections): - detection: Detection2DBBox - if result.keypoints is not None: + detection: Detection2D + if result.masks is not None: + # Segmentation detection with mask + detection = Detection2DSeg.from_ultralytics_result(result, i, image) + elif result.keypoints is not None: # Pose detection with keypoints detection = Detection2DPerson.from_ultralytics_result(result, i, image) else: @@ -83,4 +93,71 @@ def from_ultralytics_result( # type: ignore[no-untyped-def] if detection.is_valid(): detections.append(detection) - return ImageDetections2D(image=image, detections=detections) + return ImageDetections2D(image=image, detections=detections) # type: ignore[return-value] + + def overlay(self, alpha: float = 0.4) -> Image: + """Overlay detection bboxes and masks onto the image. + + Args: + alpha: Transparency for mask overlay (default: 0.4) + + Returns: + Image with detection bboxes, masks, and labels drawn + """ + img = self.image.to_opencv().copy() + img = cv2.cvtColor(img, cv2.COLOR_BGR2RGB) + + for i, det in enumerate(self.detections): + track_id = det.track_id if hasattr(det, "track_id") else i + name = det.name if hasattr(det, "name") else "" + confidence = det.confidence if hasattr(det, "confidence") else 0.0 + + # Generate consistent color from track_id + np.random.seed(abs(track_id) if track_id >= 0 else i) + color = tuple(np.random.randint(50, 255, 3).tolist()) + + # Draw mask if available + if hasattr(det, "mask") and det.mask is not None: + mask = det.mask + mask_indices = mask > 0 + if np.any(mask_indices): + # Create colored mask overlay + colored_mask = np.zeros_like(img) + colored_mask[mask_indices] = color + img[mask_indices] = cv2.addWeighted( + img[mask_indices], 1 - alpha, colored_mask[mask_indices], alpha, 0 + ) + + # Draw contour + mask_uint8 = mask.astype(np.uint8) if mask.dtype == bool else mask + contours, _ = cv2.findContours( + mask_uint8, cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_SIMPLE + ) + cv2.drawContours(img, contours, -1, color, 2) + + # Draw bbox + x1, y1, x2, y2 = map(int, det.bbox) # type: ignore[attr-defined] + cv2.rectangle(img, (x1, y1), (x2, y2), color, 2) + + # Draw label + label = f"{name}" if name else f"ID:{track_id}" + if track_id >= 0: + label += f":{track_id}" + if confidence > 0: + label += f" ({confidence:.2f})" + + (text_w, text_h), baseline = cv2.getTextSize(label, cv2.FONT_HERSHEY_SIMPLEX, 0.5, 1) + cv2.rectangle(img, (x1, y1 - text_h - baseline - 2), (x1 + text_w, y1), color, -1) + cv2.putText( + img, + label, + (x1, y1 - baseline - 2), + cv2.FONT_HERSHEY_SIMPLEX, + 0.5, + (255, 255, 255), + 1, + ) + + return Image.from_numpy( + img, format=self.image.format, ts=self.image.ts, frame_id=self.image.frame_id + ) diff --git a/dimos/perception/detection/type/detection2d/seg.py b/dimos/perception/detection/type/detection2d/seg.py new file mode 100644 index 0000000000..4de4fd2098 --- /dev/null +++ b/dimos/perception/detection/type/detection2d/seg.py @@ -0,0 +1,204 @@ +# Copyright 2025-2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from __future__ import annotations + +from dataclasses import dataclass +from typing import TYPE_CHECKING, Any + +import cv2 +from dimos_lcm.foxglove_msgs.ImageAnnotations import PointsAnnotation +from dimos_lcm.foxglove_msgs.Point2 import Point2 +import numpy as np +import torch + +from dimos.msgs.foxglove_msgs.Color import Color +from dimos.perception.detection.type.detection2d.bbox import Bbox, Detection2DBBox +from dimos.types.timestamped import to_ros_stamp + +if TYPE_CHECKING: + from ultralytics.engine.results import Results + + from dimos.msgs.sensor_msgs import Image + + +@dataclass +class Detection2DSeg(Detection2DBBox): + """Represents a detection with a segmentation mask.""" + + mask: np.ndarray[Any, np.dtype[np.uint8]] # Binary mask [H, W], uint8 0 or 255 + + @classmethod + def from_sam2_result( + cls, + mask: np.ndarray[Any, Any] | torch.Tensor, + obj_id: int, + image: Image, + class_id: int = 0, + name: str = "object", + confidence: float = 1.0, + ) -> Detection2DSeg: + """Create Detection2DSeg from SAM output (single object). + + Args: + mask: Segmentation mask (logits or binary). Shape [H, W] or [1, H, W]. + obj_id: Tracking ID of the object. + image: Source image. + class_id: Class ID (default 0). + name: Class name (default "object"). + confidence: Confidence score (default 1.0). + + Returns: + Detection2DSeg instance. + """ + # Convert mask to numpy if tensor + if isinstance(mask, torch.Tensor): + mask = mask.detach().cpu().numpy() + + # Handle dimensions (EdgeTAM might return [1, H, W] or [H, W]) + if mask.ndim == 3: + mask = mask.squeeze() + + # Binarize if it's logits (usually < 0 is background, > 0 is foreground) + # or if it's boolean + if mask.dtype == bool: + mask = mask.astype(np.uint8) * 255 + elif np.issubdtype(mask.dtype, np.floating): + mask = (mask > 0.0).astype(np.uint8) * 255 + + # Calculate bbox + y_indices, x_indices = np.where(mask > 0) + if len(x_indices) > 0: + x1_val, y1_val = float(np.min(x_indices)), float(np.min(y_indices)) + x2_val, y2_val = float(np.max(x_indices)), float(np.max(y_indices)) + else: + x1_val = y1_val = x2_val = y2_val = 0.0 + + bbox = (x1_val, y1_val, x2_val, y2_val) + + return cls( + bbox=bbox, + track_id=obj_id, + class_id=class_id, + confidence=confidence, + name=name, + ts=image.ts, + image=image, + mask=mask.astype(np.uint8), # type: ignore[arg-type] + ) + + @classmethod + def from_ultralytics_result(cls, result: Results, idx: int, image: Image) -> Detection2DSeg: + """Create Detection2DSeg from ultralytics Results object with segmentation mask. + + Args: + result: Ultralytics Results object containing detection and mask data + idx: Index of the detection in the results + image: Source image + + Returns: + Detection2DSeg instance + """ + if result.boxes is None: + raise ValueError("Result has no boxes") + + # Extract bounding box coordinates + bbox_array = result.boxes.xyxy[idx].cpu().numpy() + bbox: Bbox = ( + float(bbox_array[0]), + float(bbox_array[1]), + float(bbox_array[2]), + float(bbox_array[3]), + ) + + # Extract confidence + confidence = float(result.boxes.conf[idx].cpu()) + + # Extract class ID and name + class_id = int(result.boxes.cls[idx].cpu()) + if hasattr(result, "names") and result.names is not None: + if isinstance(result.names, dict): + name = result.names.get(class_id, f"class_{class_id}") + elif isinstance(result.names, list) and class_id < len(result.names): + name = result.names[class_id] + else: + name = f"class_{class_id}" + else: + name = f"class_{class_id}" + + # Extract track ID if available + track_id = -1 + if hasattr(result.boxes, "id") and result.boxes.id is not None: + track_id = int(result.boxes.id[idx].cpu()) + + # Extract mask + mask = np.zeros((image.height, image.width), dtype=np.uint8) + if result.masks is not None and idx < len(result.masks.data): + mask_tensor = result.masks.data[idx] + mask_np = mask_tensor.cpu().numpy() + + # Resize mask to image size if needed + if mask_np.shape != (image.height, image.width): + mask_np = cv2.resize( + mask_np.astype(np.float32), + (image.width, image.height), + interpolation=cv2.INTER_LINEAR, + ) + + # Binarize mask + mask = (mask_np > 0.5).astype(np.uint8) * 255 # type: ignore[assignment] + + return cls( + bbox=bbox, + track_id=track_id, + class_id=class_id, + confidence=confidence, + name=name, + ts=image.ts, + image=image, + mask=mask, + ) + + def to_points_annotation(self) -> list[PointsAnnotation]: + """Override to include mask outline.""" + annotations = super().to_points_annotation() + + # Find contours + contours, _ = cv2.findContours(self.mask, cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_SIMPLE) + + for contour in contours: + # Simplify contour to reduce points + epsilon = 0.005 * cv2.arcLength(contour, True) + approx = cv2.approxPolyDP(contour, epsilon, True) + + points = [] + for pt in approx: + points.append(Point2(x=float(pt[0][0]), y=float(pt[0][1]))) + + if len(points) < 3: + continue + + annotations.append( + PointsAnnotation( + timestamp=to_ros_stamp(self.ts), + outline_color=Color.from_string(self.name, alpha=1.0, brightness=1.25), + fill_color=Color.from_string(self.name, alpha=0.4), + thickness=1.0, + points_length=len(points), + points=points, + type=PointsAnnotation.LINE_LOOP, + ) + ) + + return annotations diff --git a/dimos/perception/detection/type/detection3d/base.py b/dimos/perception/detection/type/detection3d/base.py index d8cc430c44..b036584f3e 100644 --- a/dimos/perception/detection/type/detection3d/base.py +++ b/dimos/perception/detection/type/detection3d/base.py @@ -15,23 +15,22 @@ from __future__ import annotations from abc import abstractmethod -from dataclasses import dataclass +from dataclasses import dataclass, field from typing import TYPE_CHECKING +from dimos.msgs.geometry_msgs import Transform from dimos.perception.detection.type.detection2d import Detection2DBBox if TYPE_CHECKING: from dimos_lcm.sensor_msgs import CameraInfo - from dimos.msgs.geometry_msgs import Transform - @dataclass class Detection3D(Detection2DBBox): """Abstract base class for 3D detections.""" - transform: Transform - frame_id: str + frame_id: str = "" + transform: Transform = field(default_factory=Transform.identity) @classmethod @abstractmethod diff --git a/dimos/perception/detection/type/detection3d/bbox.py b/dimos/perception/detection/type/detection3d/bbox.py index ac6f82a25e..764b207e75 100644 --- a/dimos/perception/detection/type/detection3d/bbox.py +++ b/dimos/perception/detection/type/detection3d/bbox.py @@ -14,11 +14,15 @@ from __future__ import annotations -from dataclasses import dataclass +from dataclasses import dataclass, field import functools from typing import Any -from dimos.msgs.geometry_msgs import PoseStamped, Transform, Vector3 +from dimos_lcm.vision_msgs import ObjectHypothesis, ObjectHypothesisWithPose + +from dimos.msgs.geometry_msgs import Pose, PoseStamped, Quaternion, Transform, Vector3 +from dimos.msgs.std_msgs import Header +from dimos.msgs.vision_msgs import Detection3D from dimos.perception.detection.type.detection2d import Detection2DBBox @@ -29,11 +33,11 @@ class Detection3DBBox(Detection2DBBox): Represents a 3D detection as an oriented bounding box in world space. """ - transform: Transform # Camera to world transform - frame_id: str # Frame ID (e.g., "world", "map") - center: Vector3 # Center point in world frame - size: Vector3 # Width, height, depth - orientation: tuple[float, float, float, float] # Quaternion (x, y, z, w) + transform: Transform | None = None # Camera to world transform + frame_id: str = "" # Frame ID (e.g., "world", "map") + center: Vector3 | None = None # Center point in world frame + size: Vector3 | None = None # Width, height, depth + orientation: Quaternion = field(default_factory=lambda: Quaternion(0.0, 0.0, 0.0, 1.0)) @functools.cached_property def pose(self) -> PoseStamped: @@ -48,8 +52,34 @@ def pose(self) -> PoseStamped: orientation=self.orientation, ) + def to_ros_detection3d(self) -> Detection3D: + """Convert to ROS Detection3D message.""" + msg = Detection3D() + msg.header = Header(self.ts, self.frame_id) + + # Results + msg.results = [ + ObjectHypothesisWithPose( + hypothesis=ObjectHypothesis( + class_id=str(self.class_id), + score=self.confidence, + ) + ) + ] + + # Bounding Box + msg.bbox.center = Pose( + position=self.center, + orientation=self.orientation, + ) + msg.bbox.size = self.size + + return msg + def to_repr_dict(self) -> dict[str, Any]: # Calculate distance from camera + if self.transform is None or self.center is None or self.size is None: + return super().to_repr_dict() camera_pos = self.transform.translation distance = (self.center - camera_pos).magnitude() diff --git a/dimos/perception/detection/type/detection3d/imageDetections3DPC.py b/dimos/perception/detection/type/detection3d/imageDetections3DPC.py index 0fbb1a7c59..2277d84634 100644 --- a/dimos/perception/detection/type/detection3d/imageDetections3DPC.py +++ b/dimos/perception/detection/type/detection3d/imageDetections3DPC.py @@ -14,15 +14,174 @@ from __future__ import annotations -from lcm_msgs.foxglove_msgs import SceneUpdate # type: ignore[import-not-found] +from typing import TYPE_CHECKING -from dimos.perception.detection.type.detection3d.pointcloud import Detection3DPC +from dimos_lcm.foxglove_msgs import SceneUpdate +import numpy as np +import open3d as o3d # type: ignore[import-untyped] + +try: + from geometry_msgs.msg import ( # type: ignore[attr-defined] + Point as ROSPoint, + Pose as ROSPose, + Quaternion as ROSQuaternion, + Vector3 as ROSVector3, + ) + from std_msgs.msg import Header as ROSHeader # type: ignore[attr-defined] + from vision_msgs.msg import ( # type: ignore[attr-defined, import-untyped] + BoundingBox3D as ROSBoundingBox3D, + Detection3D as ROSDetection3D, + Detection3DArray as ROSDetection3DArray, + ObjectHypothesisWithPose as ROSObjectHypothesisWithPose, + ) +except ImportError: + ROSPoint = None # type: ignore[assignment, misc] + ROSPose = None # type: ignore[assignment, misc] + ROSQuaternion = None # type: ignore[assignment, misc] + ROSVector3 = None # type: ignore[assignment, misc] + ROSHeader = None # type: ignore[assignment, misc] + ROSBoundingBox3D = None # type: ignore[assignment, misc] + ROSDetection3D = None # type: ignore[assignment, misc] + ROSDetection3DArray = None # type: ignore[assignment, misc] + ROSObjectHypothesisWithPose = None # type: ignore[assignment, misc] + +from dimos.msgs.sensor_msgs import PointCloud2 from dimos.perception.detection.type.imageDetections import ImageDetections +if TYPE_CHECKING: + from dimos.perception.detection.type.detection3d.pointcloud import Detection3DPC + -class ImageDetections3DPC(ImageDetections[Detection3DPC]): +class ImageDetections3DPC(ImageDetections["Detection3DPC"]): """Specialized class for 3D detections in an image.""" + def get_aggregated_objects_pointcloud(self) -> PointCloud2 | None: + """Aggregate all detection pointclouds into a single colored pointcloud. + + Each detection's points are colored based on a consistent color derived + from its track_id, similar to the 2D overlay visualization. + + Returns: + Combined PointCloud2 with all detection points colored by object, + or None if no detections. + """ + if not self.detections: + return None + + all_points = [] + all_colors = [] + + for i, det in enumerate(self.detections): + points, original_colors = det.pointcloud.as_numpy() + if len(points) == 0: + continue + + track_id = det.track_id if det.track_id >= 0 else i + np.random.seed(abs(track_id)) + track_color = np.random.randint(50, 255, 3) / 255.0 + + if original_colors is not None: + blended_colors = 0.6 * original_colors + 0.4 * track_color + blended_colors = np.clip(blended_colors, 0.0, 1.0) + else: + blended_colors = np.tile(track_color, (len(points), 1)) + + all_points.append(points) + all_colors.append(blended_colors) + + if not all_points: + return None + + # Combine all points and colors + combined_points = np.vstack(all_points) + combined_colors = np.vstack(all_colors) + + # Get frame_id and timestamp from first detection + frame_id = self.detections[0].frame_id + ts = self.detections[0].ts + + # Create combined pointcloud + combined_pc = PointCloud2.from_numpy( + combined_points, + frame_id=frame_id, + timestamp=ts, + ) + + combined_pc.pointcloud.colors = o3d.utility.Vector3dVector(combined_colors) + + return combined_pc + + def to_ros_detection3d_array(self) -> ROSDetection3DArray: + """Convert ImageDetections3DPC to ROS Detection3DArray message. + + Returns: + Detection3DArray ROS message containing all 3D detections + """ + detection_array = ROSDetection3DArray() + + # Set header from image or first detection + detection_array.header = ROSHeader() + if self.detections: + detection_array.header.frame_id = self.detections[0].frame_id or "" + ts = self.detections[0].ts + detection_array.header.stamp.sec = int(ts) + detection_array.header.stamp.nanosec = int((ts % 1) * 1_000_000_000) + elif self.image: + detection_array.header.frame_id = self.image.frame_id or "" + if self.image.ts: + detection_array.header.stamp.sec = int(self.image.ts) + detection_array.header.stamp.nanosec = int((self.image.ts % 1) * 1_000_000_000) + + # Convert each detection + for det in self.detections: + ros_detection = ROSDetection3D() + + # Set header + ros_detection.header = ROSHeader() + ros_detection.header.frame_id = det.frame_id or "" + ros_detection.header.stamp.sec = int(det.ts) + ros_detection.header.stamp.nanosec = int((det.ts % 1) * 1_000_000_000) + + # Set bounding box + ros_detection.bbox = ROSBoundingBox3D() + ros_detection.bbox.center = ROSPose() + ros_detection.bbox.center.position = ROSPoint() + + # Get center from pointcloud + center = det.center + ros_detection.bbox.center.position.x = float(center.x) + ros_detection.bbox.center.position.y = float(center.y) + ros_detection.bbox.center.position.z = float(center.z) + + # Identity orientation for axis-aligned bbox + ros_detection.bbox.center.orientation = ROSQuaternion() + ros_detection.bbox.center.orientation.x = 0.0 + ros_detection.bbox.center.orientation.y = 0.0 + ros_detection.bbox.center.orientation.z = 0.0 + ros_detection.bbox.center.orientation.w = 1.0 + + # Set size from bounding box dimensions + dims = det.get_bounding_box_dimensions() + ros_detection.bbox.size = ROSVector3() + ros_detection.bbox.size.x = float(dims[0]) + ros_detection.bbox.size.y = float(dims[1]) + ros_detection.bbox.size.z = float(dims[2]) + + # Add class hypothesis + if det.name: + hypothesis = ROSObjectHypothesisWithPose() + hypothesis.hypothesis.class_id = det.name + hypothesis.hypothesis.score = float(det.confidence) + ros_detection.results.append(hypothesis) + + # Set tracking ID + if det.track_id >= 0: + ros_detection.id = str(det.track_id) + + detection_array.detections.append(ros_detection) + + return detection_array + def to_foxglove_scene_update(self) -> SceneUpdate: """Convert all detections to a Foxglove SceneUpdate message. diff --git a/dimos/perception/detection/type/detection3d/object.py b/dimos/perception/detection/type/detection3d/object.py new file mode 100644 index 0000000000..ce6e9df915 --- /dev/null +++ b/dimos/perception/detection/type/detection3d/object.py @@ -0,0 +1,377 @@ +# Copyright 2025-2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from __future__ import annotations + +from dataclasses import dataclass, field +import time +from typing import TYPE_CHECKING, Any +import uuid + +import cv2 +from dimos_lcm.geometry_msgs import Pose +from dimos_lcm.vision_msgs import ObjectHypothesis, ObjectHypothesisWithPose +import numpy as np +import open3d as o3d # type: ignore[import-untyped] + +from dimos.msgs.geometry_msgs import PoseStamped, Quaternion, Transform, Vector3 +from dimos.msgs.sensor_msgs import Image, PointCloud2 +from dimos.msgs.std_msgs import Header +from dimos.msgs.vision_msgs import Detection3D as ROSDetection3D, Detection3DArray +from dimos.perception.detection.type.detection2d.seg import Detection2DSeg +from dimos.perception.detection.type.detection3d.base import Detection3D + +if TYPE_CHECKING: + from dimos_lcm.sensor_msgs import CameraInfo + + from dimos.perception.detection.type.detection2d import ImageDetections2D + + +@dataclass +class Object(Detection3D): + """3D object detection combining bounding box and pointcloud representations. + + Represents a detected object in 3D space with support for accumulating + multiple detections over time. + """ + + object_id: str = field(default_factory=lambda: uuid.uuid4().hex[:8]) + pointcloud: PointCloud2 | None = None + camera_transform: Transform | None = None + center: Vector3 | None = None + size: Vector3 | None = None + pose: PoseStamped | None = None + mask: np.ndarray[Any, np.dtype[np.uint8]] | None = None + detections_count: int = 1 + + def update_object(self, other: Object) -> None: + """Update this object with data from another detection. + + Accumulates pointclouds by transforming the new pointcloud to world frame + and adding it to the existing pointcloud. Updates center and camera_transform, + and increments the detections_count. + + Args: + other: Another Object instance with newer detection data. + """ + # Accumulate pointclouds if both exist and transforms are available + if ( + self.pointcloud is not None + and other.pointcloud is not None + and other.camera_transform is not None + ): + # Transform new pointcloud to world frame and add to existing + # transformed_pc = other.pointcloud.transform(other.camera_transform) + # self.pointcloud = self.pointcloud + transformed_pc + + # Recompute center from accumulated pointcloud + self.pointcloud = other.pointcloud + pc_center = other.pointcloud.center + self.center = Vector3(pc_center.x, pc_center.y, pc_center.z) + else: + # No transform available, just replace + self.pointcloud = other.pointcloud + self.center = other.center + + self.camera_transform = other.camera_transform + self.track_id = other.track_id + self.mask = other.mask + self.name = other.name + self.bbox = other.bbox + self.confidence = other.confidence + self.class_id = other.class_id + self.ts = other.ts + self.frame_id = other.frame_id + self.image = other.image + self.detections_count += 1 + + def get_oriented_bounding_box(self) -> Any: + """Get oriented bounding box of the pointcloud.""" + if self.pointcloud is None: + raise ValueError("No pointcloud available") + return self.pointcloud.get_oriented_bounding_box() + + def scene_entity_label(self) -> str: + """Get label for scene visualization.""" + if self.detections_count > 1: + return f"{self.name} ({self.detections_count})" + return f"{self.track_id}/{self.name} ({self.confidence:.0%})" + + def to_ros_detection3d(self) -> ROSDetection3D: + """Convert to ROS Detection3D message.""" + msg = ROSDetection3D() + msg.header = Header(self.ts, self.frame_id) + msg.results = [ + ObjectHypothesisWithPose( + hypothesis=ObjectHypothesis( + class_id=str(self.class_id), + score=self.confidence, + ) + ) + ] + + obb = self.get_oriented_bounding_box() # type: ignore[no-untyped-call] + obb_center = obb.center + obb_extent = obb.extent + orientation = Quaternion.from_rotation_matrix(obb.R) + + msg.bbox.center = Pose( + position=Vector3(obb_center[0], obb_center[1], obb_center[2]), + orientation=orientation, + ) + msg.bbox.size = Vector3(obb_extent[0], obb_extent[1], obb_extent[2]) + + return msg + + def agent_encode(self) -> dict[str, Any]: + """Encode for agent consumption.""" + return { + "id": self.track_id, + "name": self.name, + "detections": self.detections_count, + "last_seen": f"{round(time.time() - self.ts)}s ago", + } + + def to_dict(self) -> dict[str, Any]: + """Convert object to dictionary with all relevant data.""" + return { + "object_id": self.object_id, + "track_id": self.track_id, + "class_id": self.class_id, + "name": self.name, + "mask": self.mask, + "pointcloud": self.pointcloud.as_numpy() if self.pointcloud else None, + "image": self.image.as_numpy() if self.image else None, + } + + @classmethod + def from_2d( # type: ignore[override] + cls, + detections_2d: ImageDetections2D[Detection2DSeg], + color_image: Image, + depth_image: Image, + camera_info: CameraInfo, + camera_transform: Transform | None = None, + depth_scale: float = 1.0, + depth_trunc: float = 10.0, + statistical_nb_neighbors: int = 10, + statistical_std_ratio: float = 0.5, + voxel_downsample: float = 0.005, + mask_erode_pixels: int = 3, + ) -> list[Object]: + """Create 3D Objects from 2D detections and RGBD images. + + Uses Open3D's optimized RGBD projection for efficient processing. + + Args: + detections_2d: 2D detections with segmentation masks + color_image: RGB color image + depth_image: Depth image (in meters if depth_scale=1.0) + camera_info: Camera intrinsics + camera_transform: Optional transform from camera frame to world frame. + If provided, pointclouds will be transformed to world frame. + depth_scale: Scale factor for depth (1.0 for meters, 1000.0 for mm) + depth_trunc: Maximum depth value in meters + statistical_nb_neighbors: Neighbors for statistical outlier removal + statistical_std_ratio: Std ratio for statistical outlier removal + voxel_downsample: Voxel size (meters) for downsampling before filtering. Set <= 0 to skip. + mask_erode_pixels: Number of pixels to erode the mask by to remove + noisy depth edge points. Set to 0 to disable. + + Returns: + List of Object instances with pointclouds + """ + color_cv = color_image.to_opencv() + if color_cv.ndim == 3 and color_cv.shape[2] == 3: + color_cv = cv2.cvtColor(color_cv, cv2.COLOR_BGR2RGB) + + depth_cv = depth_image.to_opencv() + h, w = depth_cv.shape[:2] + + # Build Open3D camera intrinsics + fx, fy = camera_info.K[0], camera_info.K[4] + cx, cy = camera_info.K[2], camera_info.K[5] + intrinsic_o3d = o3d.camera.PinholeCameraIntrinsic(w, h, fx, fy, cx, cy) + + objects: list[Object] = [] + + for det in detections_2d.detections: + if isinstance(det, Detection2DSeg): + mask = det.mask + store_mask = det.mask + else: + mask = np.zeros((h, w), dtype=np.uint8) + x1, y1, x2, y2 = map(int, det.bbox) + x1, y1 = max(0, x1), max(0, y1) + x2, y2 = min(w, x2), min(h, y2) + mask[y1:y2, x1:x2] = 255 + store_mask = mask + + if mask_erode_pixels > 0: + mask_uint8 = mask.astype(np.uint8) + if mask_uint8.max() == 1: + mask_uint8 = mask_uint8 * 255 # type: ignore[assignment] + kernel_size = 2 * mask_erode_pixels + 1 + erode_kernel = cv2.getStructuringElement( + cv2.MORPH_ELLIPSE, (kernel_size, kernel_size) + ) + mask = cv2.erode(mask_uint8, erode_kernel) # type: ignore[assignment] + + depth_masked = depth_cv.copy() + depth_masked[mask == 0] = 0 + + rgbd = o3d.geometry.RGBDImage.create_from_color_and_depth( + o3d.geometry.Image(color_cv.astype(np.uint8)), + o3d.geometry.Image(depth_masked.astype(np.float32)), + depth_scale=depth_scale, + depth_trunc=depth_trunc, + convert_rgb_to_intensity=False, + ) + pcd = o3d.geometry.PointCloud.create_from_rgbd_image(rgbd, intrinsic_o3d) + + if len(pcd.points) < 20: + continue + + if voxel_downsample > 0: + pcd = ( + PointCloud2( + pcd, + frame_id=depth_image.frame_id, + ts=depth_image.ts, + ) + .voxel_downsample(voxel_downsample) + .pointcloud + ) + + pcd_filtered, _ = pcd.remove_statistical_outlier( + nb_neighbors=statistical_nb_neighbors, + std_ratio=statistical_std_ratio, + ) + + if len(pcd_filtered.points) < 10: + continue + + pc = PointCloud2( + pcd_filtered, + frame_id=depth_image.frame_id, + ts=depth_image.ts, + ) + + # Transform pointcloud to world frame if camera_transform is provided + if camera_transform is not None: + pc = pc.transform(camera_transform) + frame_id = camera_transform.frame_id + else: + frame_id = depth_image.frame_id + + # Compute center from pointcloud + pc_center = pc.center + center = Vector3(pc_center.x, pc_center.y, pc_center.z) + + objects.append( + cls( + bbox=det.bbox, + track_id=det.track_id, + class_id=det.class_id, + confidence=det.confidence, + name=det.name, + ts=det.ts, + image=det.image, + frame_id=frame_id, + pointcloud=pc, + center=center, + camera_transform=camera_transform, + mask=store_mask, + ) + ) + + return objects + + +def aggregate_pointclouds(objects: list[Object]) -> PointCloud2 | None: + """Aggregate all object pointclouds into a single colored pointcloud. + + Each object's points are colored based on its track_id. + + Args: + objects: List of Object instances with pointclouds + + Returns: + Combined PointCloud2 with all points colored by object, or None if empty. + """ + if not objects: + return None + + all_points = [] + all_colors = [] + + for _i, obj in enumerate(objects): + if obj.pointcloud is None: + continue + + points, colors = obj.pointcloud.as_numpy() + if len(points) == 0: + continue + + try: + seed = int(obj.object_id, 16) + except (ValueError, TypeError): + seed = abs(hash(obj.object_id)) + np.random.seed(abs(seed) % (2**32 - 1)) + track_color = np.random.randint(50, 255, 3) / 255.0 + + if colors is not None: + blended = np.clip(0.6 * colors + 0.4 * track_color, 0.0, 1.0) + else: + blended = np.tile(track_color, (len(points), 1)) + + all_points.append(points) + all_colors.append(blended) + + if not all_points: + return None + + combined_points = np.vstack(all_points) + combined_colors = np.vstack(all_colors) + + pc = PointCloud2.from_numpy( + combined_points, + frame_id=objects[0].frame_id, + timestamp=objects[0].ts, + ) + pcd = pc.pointcloud + pcd.colors = o3d.utility.Vector3dVector(combined_colors) + pc.pointcloud = pcd + + return pc + + +def to_detection3d_array(objects: list[Object]) -> Detection3DArray: + """Convert a list of Objects to a ROS Detection3DArray message. + + Args: + objects: List of Object instances + + Returns: + Detection3DArray ROS message + """ + array = Detection3DArray() + + if objects: + array.header = Header(objects[0].ts, objects[0].frame_id) + + for obj in objects: + array.detections.append(obj.to_ros_detection3d()) + + return array diff --git a/dimos/perception/detection/type/detection3d/pointcloud.py b/dimos/perception/detection/type/detection3d/pointcloud.py index fd924a6564..7edceb17a5 100644 --- a/dimos/perception/detection/type/detection3d/pointcloud.py +++ b/dimos/perception/detection/type/detection3d/pointcloud.py @@ -14,7 +14,7 @@ from __future__ import annotations -from dataclasses import dataclass +from dataclasses import dataclass, field import functools from typing import TYPE_CHECKING, Any @@ -52,7 +52,7 @@ @dataclass class Detection3DPC(Detection3D): - pointcloud: PointCloud2 + pointcloud: PointCloud2 = field(default_factory=PointCloud2) @functools.cached_property def center(self) -> Vector3: diff --git a/dimos/perception/detection2d/utils.py b/dimos/perception/detection2d/utils.py deleted file mode 100644 index a505eef7c8..0000000000 --- a/dimos/perception/detection2d/utils.py +++ /dev/null @@ -1,309 +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. - -from collections.abc import Sequence - -import cv2 -import numpy as np - - -def filter_detections( # type: ignore[no-untyped-def] - bboxes, - track_ids, - class_ids, - confidences, - names: Sequence[str], - class_filter=None, - name_filter=None, - track_id_filter=None, -): - """ - Filter detection results based on class IDs, names, and/or tracking IDs. - - Args: - bboxes: List of bounding boxes [x1, y1, x2, y2] - track_ids: List of tracking IDs - class_ids: List of class indices - confidences: List of detection confidences - names: List of class names - class_filter: List/set of class IDs to keep, or None to keep all - name_filter: List/set of class names to keep, or None to keep all - track_id_filter: List/set of track IDs to keep, or None to keep all - - Returns: - tuple: (filtered_bboxes, filtered_track_ids, filtered_class_ids, - filtered_confidences, filtered_names) - """ - # Convert filters to sets for efficient lookup - if class_filter is not None: - class_filter = set(class_filter) - if name_filter is not None: - name_filter = set(name_filter) - if track_id_filter is not None: - track_id_filter = set(track_id_filter) - - # Initialize lists for filtered results - filtered_bboxes = [] - filtered_track_ids = [] - filtered_class_ids = [] - filtered_confidences = [] - filtered_names = [] - - # Filter detections - for bbox, track_id, class_id, conf, name in zip( - bboxes, track_ids, class_ids, confidences, names, strict=False - ): - # Check if detection passes all specified filters - keep = True - - if class_filter is not None: - keep = keep and (class_id in class_filter) - - if name_filter is not None: - keep = keep and (name in name_filter) - - if track_id_filter is not None: - keep = keep and (track_id in track_id_filter) - - # If detection passes all filters, add it to results - if keep: - filtered_bboxes.append(bbox) - filtered_track_ids.append(track_id) - filtered_class_ids.append(class_id) - filtered_confidences.append(conf) - filtered_names.append(name) - - return ( - filtered_bboxes, - filtered_track_ids, - filtered_class_ids, - filtered_confidences, - filtered_names, - ) - - -def extract_detection_results(result, class_filter=None, name_filter=None, track_id_filter=None): # type: ignore[no-untyped-def] - """ - Extract and optionally filter detection information from a YOLO result object. - - Args: - result: Ultralytics result object - class_filter: List/set of class IDs to keep, or None to keep all - name_filter: List/set of class names to keep, or None to keep all - track_id_filter: List/set of track IDs to keep, or None to keep all - - Returns: - tuple: (bboxes, track_ids, class_ids, confidences, names) - - bboxes: list of [x1, y1, x2, y2] coordinates - - track_ids: list of tracking IDs - - class_ids: list of class indices - - confidences: list of detection confidences - - names: list of class names - """ - bboxes = [] # type: ignore[var-annotated] - track_ids = [] # type: ignore[var-annotated] - class_ids = [] # type: ignore[var-annotated] - confidences = [] # type: ignore[var-annotated] - names = [] # type: ignore[var-annotated] - - if result.boxes is None: - return bboxes, track_ids, class_ids, confidences, names - - for box in result.boxes: - # Extract bounding box coordinates - x1, y1, x2, y2 = box.xyxy[0].tolist() - - # Extract tracking ID if available - track_id = -1 - if hasattr(box, "id") and box.id is not None: - track_id = int(box.id[0].item()) - - # Extract class information - cls_idx = int(box.cls[0]) - name = result.names[cls_idx] - - # Extract confidence - conf = float(box.conf[0]) - - # Check filters before adding to results - keep = True - if class_filter is not None: - keep = keep and (cls_idx in class_filter) - if name_filter is not None: - keep = keep and (name in name_filter) - if track_id_filter is not None: - keep = keep and (track_id in track_id_filter) - - if keep: - bboxes.append([x1, y1, x2, y2]) - track_ids.append(track_id) - class_ids.append(cls_idx) - confidences.append(conf) - names.append(name) - - return bboxes, track_ids, class_ids, confidences, names - - -def plot_results( # type: ignore[no-untyped-def] - image, bboxes, track_ids, class_ids, confidences, names: Sequence[str], alpha: float = 0.5 -): - """ - Draw bounding boxes and labels on the image. - - Args: - image: Original input image - bboxes: List of bounding boxes [x1, y1, x2, y2] - track_ids: List of tracking IDs - class_ids: List of class indices - confidences: List of detection confidences - names: List of class names - alpha: Transparency of the overlay - - Returns: - Image with visualized detections - """ - vis_img = image.copy() - - for bbox, track_id, conf, name in zip(bboxes, track_ids, confidences, names, strict=False): - # Generate consistent color based on track_id or class name - if track_id != -1: - np.random.seed(track_id) - else: - np.random.seed(hash(name) % 100000) - color = np.random.randint(0, 255, (3,), dtype=np.uint8) - np.random.seed(None) - - # Draw bounding box - x1, y1, x2, y2 = map(int, bbox) - cv2.rectangle(vis_img, (x1, y1), (x2, y2), color.tolist(), 2) - - # Prepare label text - if track_id != -1: - label = f"ID:{track_id} {name} {conf:.2f}" - else: - label = f"{name} {conf:.2f}" - - # Calculate text size for background rectangle - (text_w, text_h), _ = cv2.getTextSize(label, cv2.FONT_HERSHEY_SIMPLEX, 0.5, 1) - - # Draw background rectangle for text - cv2.rectangle(vis_img, (x1, y1 - text_h - 8), (x1 + text_w + 4, y1), color.tolist(), -1) - - # Draw text with white color for better visibility - cv2.putText( - vis_img, label, (x1 + 2, y1 - 5), cv2.FONT_HERSHEY_SIMPLEX, 0.5, (255, 255, 255), 1 - ) - - return vis_img - - -def calculate_depth_from_bbox(depth_map, bbox): # type: ignore[no-untyped-def] - """ - Calculate the average depth of an object within a bounding box. - Uses the 25th to 75th percentile range to filter outliers. - - Args: - depth_map: The depth map - bbox: Bounding box in format [x1, y1, x2, y2] - - Returns: - float: Average depth in meters, or None if depth estimation fails - """ - try: - # Extract region of interest from the depth map - x1, y1, x2, y2 = map(int, bbox) - roi_depth = depth_map[y1:y2, x1:x2] - - if roi_depth.size == 0: - return None - - # Calculate 25th and 75th percentile to filter outliers - p25 = np.percentile(roi_depth, 25) - p75 = np.percentile(roi_depth, 75) - - # Filter depth values within this range - filtered_depth = roi_depth[(roi_depth >= p25) & (roi_depth <= p75)] - - # Calculate average depth (convert to meters) - if filtered_depth.size > 0: - return np.mean(filtered_depth) / 1000.0 # Convert mm to meters - - return None - except Exception as e: - print(f"Error calculating depth from bbox: {e}") - return None - - -def calculate_distance_angle_from_bbox(bbox, depth: int, camera_intrinsics): # type: ignore[no-untyped-def] - """ - Calculate distance and angle to object center based on bbox and depth. - - Args: - bbox: Bounding box [x1, y1, x2, y2] - depth: Depth value in meters - camera_intrinsics: List [fx, fy, cx, cy] with camera parameters - - Returns: - tuple: (distance, angle) in meters and radians - """ - if camera_intrinsics is None: - raise ValueError("Camera intrinsics required for distance calculation") - - # Extract camera parameters - fx, _fy, cx, _cy = camera_intrinsics - - # Calculate center of bounding box in pixels - x1, y1, x2, y2 = bbox - center_x = (x1 + x2) / 2 - (y1 + y2) / 2 - - # Calculate normalized image coordinates - x_norm = (center_x - cx) / fx - - # Calculate angle (positive to the right) - angle = np.arctan(x_norm) - - # Calculate distance using depth and angle - distance = depth / np.cos(angle) if np.cos(angle) != 0 else depth - - return distance, angle - - -def calculate_object_size_from_bbox(bbox, depth: int, camera_intrinsics): # type: ignore[no-untyped-def] - """ - Estimate physical width and height of object in meters. - - Args: - bbox: Bounding box [x1, y1, x2, y2] - depth: Depth value in meters - camera_intrinsics: List [fx, fy, cx, cy] with camera parameters - - Returns: - tuple: (width, height) in meters - """ - if camera_intrinsics is None: - return 0.0, 0.0 - - fx, fy, _, _ = camera_intrinsics - - # Calculate bbox dimensions in pixels - x1, y1, x2, y2 = bbox - width_px = x2 - x1 - height_px = y2 - y1 - - # Convert to meters using similar triangles and depth - width_m = (width_px * depth) / fx - height_m = (height_px * depth) / fy - - return width_m, height_m diff --git a/dimos/perception/grasp_generation/__init__.py b/dimos/perception/grasp_generation/__init__.py deleted file mode 100644 index 16281fe0b6..0000000000 --- a/dimos/perception/grasp_generation/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from .utils import * diff --git a/dimos/perception/grasp_generation/grasp_generation.py b/dimos/perception/grasp_generation/grasp_generation.py deleted file mode 100644 index 4f2e4b68a1..0000000000 --- a/dimos/perception/grasp_generation/grasp_generation.py +++ /dev/null @@ -1,233 +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. - -""" -Dimensional-hosted grasp generation for manipulation pipeline. -""" - -import asyncio - -import numpy as np -import open3d as o3d # type: ignore[import-untyped] - -from dimos.perception.grasp_generation.utils import parse_grasp_results -from dimos.types.manipulation import ObjectData -from dimos.utils.logging_config import setup_logger - -logger = setup_logger() - - -class HostedGraspGenerator: - """ - Dimensional-hosted grasp generator using WebSocket communication. - """ - - def __init__(self, server_url: str) -> None: - """ - Initialize Dimensional-hosted grasp generator. - - Args: - server_url: WebSocket URL for Dimensional-hosted grasp generator server - """ - self.server_url = server_url - logger.info(f"Initialized grasp generator with server: {server_url}") - - def generate_grasps_from_objects( - self, objects: list[ObjectData], full_pcd: o3d.geometry.PointCloud - ) -> list[dict]: # type: ignore[type-arg] - """ - Generate grasps from ObjectData objects using grasp generator. - - Args: - objects: List of ObjectData with point clouds - full_pcd: Open3D point cloud of full scene - - Returns: - Parsed grasp results as list of dictionaries - """ - try: - # Combine all point clouds - all_points = [] - all_colors = [] - valid_objects = 0 - - for obj in objects: - if "point_cloud_numpy" not in obj or obj["point_cloud_numpy"] is None: - continue - - points = obj["point_cloud_numpy"] - if not isinstance(points, np.ndarray) or points.size == 0: - continue - - if len(points.shape) != 2 or points.shape[1] != 3: - continue - - colors = None - if "colors_numpy" in obj and obj["colors_numpy"] is not None: # type: ignore[typeddict-item] - colors = obj["colors_numpy"] # type: ignore[typeddict-item] - if isinstance(colors, np.ndarray) and colors.size > 0: - if ( - colors.shape[0] != points.shape[0] - or len(colors.shape) != 2 - or colors.shape[1] != 3 - ): - colors = None - - all_points.append(points) - if colors is not None: - all_colors.append(colors) - valid_objects += 1 - - if not all_points: - return [] - - # Combine point clouds - combined_points = np.vstack(all_points) - combined_colors = None - if len(all_colors) == valid_objects and len(all_colors) > 0: - combined_colors = np.vstack(all_colors) - - # Send grasp request - grasps = self._send_grasp_request_sync(combined_points, combined_colors) - - if not grasps: - return [] - - # Parse and return results in list of dictionaries format - return parse_grasp_results(grasps) - - except Exception as e: - logger.error(f"Grasp generation failed: {e}") - return [] - - def _send_grasp_request_sync( - self, - points: np.ndarray, # type: ignore[type-arg] - colors: np.ndarray | None, # type: ignore[type-arg] - ) -> list[dict] | None: # type: ignore[type-arg] - """Send synchronous grasp request to grasp server.""" - - try: - # Prepare colors - colors = np.ones((points.shape[0], 3), dtype=np.float32) * 0.5 - - # Ensure correct data types - points = points.astype(np.float32) - colors = colors.astype(np.float32) - - # Validate ranges - if np.any(np.isnan(points)) or np.any(np.isinf(points)): - logger.error("Points contain NaN or Inf values") - return None - if np.any(np.isnan(colors)) or np.any(np.isinf(colors)): - logger.error("Colors contain NaN or Inf values") - return None - - colors = np.clip(colors, 0.0, 1.0) - - # Run async request in sync context - loop = asyncio.new_event_loop() - asyncio.set_event_loop(loop) - try: - result = loop.run_until_complete(self._async_grasp_request(points, colors)) - return result - finally: - loop.close() - - except Exception as e: - logger.error(f"Error in synchronous grasp request: {e}") - return None - - async def _async_grasp_request( - self, - points: np.ndarray, # type: ignore[type-arg] - colors: np.ndarray, # type: ignore[type-arg] - ) -> list[dict] | None: # type: ignore[type-arg] - """Async grasp request helper.""" - import json - - import websockets - - try: - async with websockets.connect(self.server_url) as websocket: - request = { - "points": points.tolist(), - "colors": colors.tolist(), - "lims": [-1.0, 1.0, -1.0, 1.0, 0.0, 2.0], - } - - await websocket.send(json.dumps(request)) - response = await websocket.recv() - grasps = json.loads(response) - - if isinstance(grasps, dict) and "error" in grasps: - logger.error(f"Server returned error: {grasps['error']}") - return None - elif isinstance(grasps, int | float) and grasps == 0: - return None - elif not isinstance(grasps, list): - logger.error(f"Server returned unexpected response type: {type(grasps)}") - return None - elif len(grasps) == 0: - return None - - return self._convert_grasp_format(grasps) - - except Exception as e: - logger.error(f"Async grasp request failed: {e}") - return None - - def _convert_grasp_format(self, grasps: list[dict]) -> list[dict]: # type: ignore[type-arg] - """Convert Dimensional Grasp format to visualization format.""" - converted = [] - - for i, grasp in enumerate(grasps): - rotation_matrix = np.array(grasp.get("rotation_matrix", np.eye(3))) - euler_angles = self._rotation_matrix_to_euler(rotation_matrix) - - converted_grasp = { - "id": f"grasp_{i}", - "score": grasp.get("score", 0.0), - "width": grasp.get("width", 0.0), - "height": grasp.get("height", 0.0), - "depth": grasp.get("depth", 0.0), - "translation": grasp.get("translation", [0, 0, 0]), - "rotation_matrix": rotation_matrix.tolist(), - "euler_angles": euler_angles, - } - converted.append(converted_grasp) - - converted.sort(key=lambda x: x["score"], reverse=True) - return converted - - def _rotation_matrix_to_euler(self, rotation_matrix: np.ndarray) -> dict[str, float]: # type: ignore[type-arg] - """Convert rotation matrix to Euler angles (in radians).""" - sy = np.sqrt(rotation_matrix[0, 0] ** 2 + rotation_matrix[1, 0] ** 2) - - singular = sy < 1e-6 - - if not singular: - x = np.arctan2(rotation_matrix[2, 1], rotation_matrix[2, 2]) - y = np.arctan2(-rotation_matrix[2, 0], sy) - z = np.arctan2(rotation_matrix[1, 0], rotation_matrix[0, 0]) - else: - x = np.arctan2(-rotation_matrix[1, 2], rotation_matrix[1, 1]) - y = np.arctan2(-rotation_matrix[2, 0], sy) - z = 0 - - return {"roll": x, "pitch": y, "yaw": z} - - def cleanup(self) -> None: - """Clean up resources.""" - logger.info("Grasp generator cleaned up") diff --git a/dimos/perception/grasp_generation/utils.py b/dimos/perception/grasp_generation/utils.py deleted file mode 100644 index 492a3d1df4..0000000000 --- a/dimos/perception/grasp_generation/utils.py +++ /dev/null @@ -1,529 +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. - -"""Utilities for grasp generation and visualization.""" - -import cv2 -import numpy as np -import open3d as o3d # type: ignore[import-untyped] - -from dimos.perception.common.utils import project_3d_points_to_2d - - -def create_gripper_geometry( - grasp_data: dict, # type: ignore[type-arg] - finger_length: float = 0.08, - finger_thickness: float = 0.004, -) -> list[o3d.geometry.TriangleMesh]: - """ - Create a simple fork-like gripper geometry from grasp data. - - Args: - grasp_data: Dictionary containing grasp parameters - - translation: 3D position list - - rotation_matrix: 3x3 rotation matrix defining gripper coordinate system - * X-axis: gripper width direction (opening/closing) - * Y-axis: finger length direction - * Z-axis: approach direction (toward object) - - width: Gripper opening width - finger_length: Length of gripper fingers (longer) - finger_thickness: Thickness of gripper fingers - base_height: Height of gripper base (longer) - color: RGB color for the gripper (solid blue) - - Returns: - List of Open3D TriangleMesh geometries for the gripper - """ - - translation = np.array(grasp_data["translation"]) - rotation_matrix = np.array(grasp_data["rotation_matrix"]) - - width = grasp_data.get("width", 0.04) - - # Create transformation matrix - transform = np.eye(4) - transform[:3, :3] = rotation_matrix - transform[:3, 3] = translation - - geometries = [] - - # Gripper dimensions - finger_width = 0.006 # Thickness of each finger - handle_length = 0.05 # Length of handle extending backward - - # Build gripper in local coordinate system: - # X-axis = width direction (left/right finger separation) - # Y-axis = finger length direction (fingers extend along +Y) - # Z-axis = approach direction (toward object, handle extends along -Z) - # IMPORTANT: Fingertips should be at origin (translation point) - - # Create left finger extending along +Y, positioned at +X - left_finger = o3d.geometry.TriangleMesh.create_box( - width=finger_width, # Thin finger - height=finger_length, # Extends along Y (finger length direction) - depth=finger_thickness, # Thin in Z direction - ) - left_finger.translate( - [ - width / 2 - finger_width / 2, # Position at +X (half width from center) - -finger_length, # Shift so fingertips are at origin - -finger_thickness / 2, # Center in Z - ] - ) - - # Create right finger extending along +Y, positioned at -X - right_finger = o3d.geometry.TriangleMesh.create_box( - width=finger_width, # Thin finger - height=finger_length, # Extends along Y (finger length direction) - depth=finger_thickness, # Thin in Z direction - ) - right_finger.translate( - [ - -width / 2 - finger_width / 2, # Position at -X (half width from center) - -finger_length, # Shift so fingertips are at origin - -finger_thickness / 2, # Center in Z - ] - ) - - # Create base connecting fingers - flat like a stickman body - base = o3d.geometry.TriangleMesh.create_box( - width=width + finger_width, # Full width plus finger thickness - height=finger_thickness, # Flat like fingers (stickman style) - depth=finger_thickness, # Thin like fingers - ) - base.translate( - [ - -width / 2 - finger_width / 2, # Start from left finger position - -finger_length - finger_thickness, # Behind fingers, adjusted for fingertips at origin - -finger_thickness / 2, # Center in Z - ] - ) - - # Create handle extending backward - flat stick like stickman arm - handle = o3d.geometry.TriangleMesh.create_box( - width=finger_width, # Same width as fingers - height=handle_length, # Extends backward along Y direction (same plane) - depth=finger_thickness, # Thin like fingers (same plane) - ) - handle.translate( - [ - -finger_width / 2, # Center in X - -finger_length - - finger_thickness - - handle_length, # Extend backward from base, adjusted for fingertips at origin - -finger_thickness / 2, # Same Z plane as other components - ] - ) - - # Use solid red color for all parts (user changed to red) - solid_color = [1.0, 0.0, 0.0] # Red color - - left_finger.paint_uniform_color(solid_color) - right_finger.paint_uniform_color(solid_color) - base.paint_uniform_color(solid_color) - handle.paint_uniform_color(solid_color) - - # Apply transformation to all parts - left_finger.transform(transform) - right_finger.transform(transform) - base.transform(transform) - handle.transform(transform) - - geometries.extend([left_finger, right_finger, base, handle]) - - return geometries - - -def create_all_gripper_geometries( - grasp_list: list[dict], # type: ignore[type-arg] - max_grasps: int = -1, -) -> list[o3d.geometry.TriangleMesh]: - """ - Create gripper geometries for multiple grasps. - - Args: - grasp_list: List of grasp dictionaries - max_grasps: Maximum number of grasps to visualize (-1 for all) - - Returns: - List of all gripper geometries - """ - all_geometries = [] - - grasps_to_show = grasp_list if max_grasps < 0 else grasp_list[:max_grasps] - - for grasp in grasps_to_show: - gripper_parts = create_gripper_geometry(grasp) - all_geometries.extend(gripper_parts) - - return all_geometries - - -def draw_grasps_on_image( - image: np.ndarray, # type: ignore[type-arg] - grasp_data: dict | dict[int | str, list[dict]] | list[dict], # type: ignore[type-arg] - camera_intrinsics: list[float] | np.ndarray, # type: ignore[type-arg] # [fx, fy, cx, cy] or 3x3 matrix - max_grasps: int = -1, # -1 means show all grasps - finger_length: float = 0.08, # Match 3D gripper - finger_thickness: float = 0.004, # Match 3D gripper -) -> np.ndarray: # type: ignore[type-arg] - """ - Draw fork-like gripper visualizations on the image matching 3D gripper design. - - Args: - image: Base image to draw on - grasp_data: Can be: - - A single grasp dict - - A list of grasp dicts - - A dictionary mapping object IDs or "scene" to list of grasps - camera_intrinsics: Camera parameters as [fx, fy, cx, cy] list or 3x3 matrix - max_grasps: Maximum number of grasps to visualize (-1 for all) - finger_length: Length of gripper fingers (matches 3D design) - finger_thickness: Thickness of gripper fingers (matches 3D design) - - Returns: - Image with grasps drawn - """ - result = image.copy() - - # Convert camera intrinsics to 3x3 matrix if needed - if isinstance(camera_intrinsics, list) and len(camera_intrinsics) == 4: - fx, fy, cx, cy = camera_intrinsics - camera_matrix = np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]]) - else: - camera_matrix = np.array(camera_intrinsics) - - # Convert input to standard format - if isinstance(grasp_data, dict) and not any( - key in grasp_data for key in ["scene", 0, 1, 2, 3, 4, 5] - ): - # Single grasp - grasps_to_draw = [(grasp_data, 0)] - elif isinstance(grasp_data, list): - # List of grasps - grasps_to_draw = [(grasp, i) for i, grasp in enumerate(grasp_data)] - else: - # Dictionary of grasps by object ID - grasps_to_draw = [] - for _obj_id, grasps in grasp_data.items(): - for i, grasp in enumerate(grasps): - grasps_to_draw.append((grasp, i)) - - # Limit number of grasps if specified - if max_grasps > 0: - grasps_to_draw = grasps_to_draw[:max_grasps] - - # Define grasp colors (solid red to match 3D design) - def get_grasp_color(index: int) -> tuple: # type: ignore[type-arg] - # Use solid red color for all grasps to match 3D design - return (0, 0, 255) # Red in BGR format for OpenCV - - # Draw each grasp - for grasp, index in grasps_to_draw: - try: - color = get_grasp_color(index) - thickness = max(1, 4 - index // 3) - - # Extract grasp parameters (using translation and rotation_matrix) - if "translation" not in grasp or "rotation_matrix" not in grasp: - continue - - translation = np.array(grasp["translation"]) - rotation_matrix = np.array(grasp["rotation_matrix"]) - width = grasp.get("width", 0.04) - - # Match 3D gripper dimensions - finger_width = 0.006 # Thickness of each finger (matches 3D) - handle_length = 0.05 # Length of handle extending backward (matches 3D) - - # Create gripper geometry in local coordinate system matching 3D design: - # X-axis = width direction (left/right finger separation) - # Y-axis = finger length direction (fingers extend along +Y) - # Z-axis = approach direction (toward object, handle extends along -Z) - # IMPORTANT: Fingertips should be at origin (translation point) - - # Left finger extending along +Y, positioned at +X - left_finger_points = np.array( - [ - [ - width / 2 - finger_width / 2, # type: ignore[operator] - -finger_length, - -finger_thickness / 2, - ], # Back left - [ - width / 2 + finger_width / 2, # type: ignore[operator] - -finger_length, - -finger_thickness / 2, - ], # Back right - [ - width / 2 + finger_width / 2, # type: ignore[operator] - 0, - -finger_thickness / 2, - ], # Front right (at origin) - [ - width / 2 - finger_width / 2, # type: ignore[operator] - 0, - -finger_thickness / 2, - ], # Front left (at origin) - ] - ) - - # Right finger extending along +Y, positioned at -X - right_finger_points = np.array( - [ - [ - -width / 2 - finger_width / 2, # type: ignore[operator] - -finger_length, - -finger_thickness / 2, - ], # Back left - [ - -width / 2 + finger_width / 2, # type: ignore[operator] - -finger_length, - -finger_thickness / 2, - ], # Back right - [ - -width / 2 + finger_width / 2, # type: ignore[operator] - 0, - -finger_thickness / 2, - ], # Front right (at origin) - [ - -width / 2 - finger_width / 2, # type: ignore[operator] - 0, - -finger_thickness / 2, - ], # Front left (at origin) - ] - ) - - # Base connecting fingers - flat rectangle behind fingers - base_points = np.array( - [ - [ - -width / 2 - finger_width / 2, # type: ignore[operator] - -finger_length - finger_thickness, - -finger_thickness / 2, - ], # Back left - [ - width / 2 + finger_width / 2, # type: ignore[operator] - -finger_length - finger_thickness, - -finger_thickness / 2, - ], # Back right - [ - width / 2 + finger_width / 2, # type: ignore[operator] - -finger_length, - -finger_thickness / 2, - ], # Front right - [ - -width / 2 - finger_width / 2, # type: ignore[operator] - -finger_length, - -finger_thickness / 2, - ], # Front left - ] - ) - - # Handle extending backward - thin rectangle - handle_points = np.array( - [ - [ - -finger_width / 2, - -finger_length - finger_thickness - handle_length, - -finger_thickness / 2, - ], # Back left - [ - finger_width / 2, - -finger_length - finger_thickness - handle_length, - -finger_thickness / 2, - ], # Back right - [ - finger_width / 2, - -finger_length - finger_thickness, - -finger_thickness / 2, - ], # Front right - [ - -finger_width / 2, - -finger_length - finger_thickness, - -finger_thickness / 2, - ], # Front left - ] - ) - - # Transform all points to world frame - def transform_points(points): # type: ignore[no-untyped-def] - # Apply rotation and translation - world_points = (rotation_matrix @ points.T).T + translation - return world_points - - left_finger_world = transform_points(left_finger_points) # type: ignore[no-untyped-call] - right_finger_world = transform_points(right_finger_points) # type: ignore[no-untyped-call] - base_world = transform_points(base_points) # type: ignore[no-untyped-call] - handle_world = transform_points(handle_points) # type: ignore[no-untyped-call] - - # Project to 2D - left_finger_2d = project_3d_points_to_2d(left_finger_world, camera_matrix) - right_finger_2d = project_3d_points_to_2d(right_finger_world, camera_matrix) - base_2d = project_3d_points_to_2d(base_world, camera_matrix) - handle_2d = project_3d_points_to_2d(handle_world, camera_matrix) - - # Draw left finger - pts = left_finger_2d.astype(np.int32) - cv2.polylines(result, [pts], True, color, thickness) - - # Draw right finger - pts = right_finger_2d.astype(np.int32) - cv2.polylines(result, [pts], True, color, thickness) - - # Draw base - pts = base_2d.astype(np.int32) - cv2.polylines(result, [pts], True, color, thickness) - - # Draw handle - pts = handle_2d.astype(np.int32) - cv2.polylines(result, [pts], True, color, thickness) - - # Draw grasp center (fingertips at origin) - center_2d = project_3d_points_to_2d(translation.reshape(1, -1), camera_matrix)[0] - cv2.circle(result, tuple(center_2d.astype(int)), 3, color, -1) - - except Exception: - # Skip this grasp if there's an error - continue - - return result - - -def get_standard_coordinate_transform(): # type: ignore[no-untyped-def] - """ - Get a standard coordinate transformation matrix for consistent visualization. - - This transformation ensures that: - - X (red) axis points right - - Y (green) axis points up - - Z (blue) axis points toward viewer - - Returns: - 4x4 transformation matrix - """ - # Standard transformation matrix to ensure consistent coordinate frame orientation - transform = np.array( - [ - [1, 0, 0, 0], # X points right - [0, -1, 0, 0], # Y points up (flip from OpenCV to standard) - [0, 0, -1, 0], # Z points toward viewer (flip depth) - [0, 0, 0, 1], - ] - ) - return transform - - -def visualize_grasps_3d( - point_cloud: o3d.geometry.PointCloud, - grasp_list: list[dict], # type: ignore[type-arg] - max_grasps: int = -1, -) -> None: - """ - Visualize grasps in 3D with point cloud. - - Args: - point_cloud: Open3D point cloud - grasp_list: List of grasp dictionaries - max_grasps: Maximum number of grasps to visualize - """ - # Apply standard coordinate transformation - transform = get_standard_coordinate_transform() # type: ignore[no-untyped-call] - - # Transform point cloud - pc_copy = o3d.geometry.PointCloud(point_cloud) - pc_copy.transform(transform) - geometries = [pc_copy] - - # Transform gripper geometries - gripper_geometries = create_all_gripper_geometries(grasp_list, max_grasps) - for geom in gripper_geometries: - geom.transform(transform) - geometries.extend(gripper_geometries) - - # Add transformed coordinate frame - origin_frame = o3d.geometry.TriangleMesh.create_coordinate_frame(size=0.1) - origin_frame.transform(transform) - geometries.append(origin_frame) - - o3d.visualization.draw_geometries(geometries, window_name="3D Grasp Visualization") - - -def parse_grasp_results(grasps: list[dict]) -> list[dict]: # type: ignore[type-arg] - """ - Parse grasp results into visualization format. - - Args: - grasps: List of grasp dictionaries - - Returns: - List of dictionaries containing: - - id: Unique grasp identifier - - score: Confidence score (float) - - width: Gripper opening width (float) - - translation: 3D position [x, y, z] - - rotation_matrix: 3x3 rotation matrix as nested list - """ - if not grasps: - return [] - - parsed_grasps = [] - - for i, grasp in enumerate(grasps): - # Extract data from each grasp - translation = grasp.get("translation", [0, 0, 0]) - rotation_matrix = np.array(grasp.get("rotation_matrix", np.eye(3))) - score = float(grasp.get("score", 0.0)) - width = float(grasp.get("width", 0.08)) - - parsed_grasp = { - "id": f"grasp_{i}", - "score": score, - "width": width, - "translation": translation, - "rotation_matrix": rotation_matrix.tolist(), - } - parsed_grasps.append(parsed_grasp) - - return parsed_grasps - - -def create_grasp_overlay( - rgb_image: np.ndarray, # type: ignore[type-arg] - grasps: list[dict], # type: ignore[type-arg] - camera_intrinsics: list[float] | np.ndarray, # type: ignore[type-arg] -) -> np.ndarray: # type: ignore[type-arg] - """ - Create grasp visualization overlay on RGB image. - - Args: - rgb_image: RGB input image - grasps: List of grasp dictionaries in viz format - camera_intrinsics: Camera parameters - - Returns: - RGB image with grasp overlay - """ - try: - bgr_image = cv2.cvtColor(rgb_image, cv2.COLOR_RGB2BGR) - - result_bgr = draw_grasps_on_image( - bgr_image, - grasps, - camera_intrinsics, - max_grasps=-1, - ) - return cv2.cvtColor(result_bgr, cv2.COLOR_BGR2RGB) - except Exception: - return rgb_image.copy() diff --git a/dimos/perception/object_detection_stream.py b/dimos/perception/object_detection_stream.py deleted file mode 100644 index 4d93e3ddd4..0000000000 --- a/dimos/perception/object_detection_stream.py +++ /dev/null @@ -1,322 +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 numpy as np -from reactivex import Observable, operators as ops - -from dimos.perception.detection2d.yolo_2d_det import ( # type: ignore[import-not-found, import-untyped] - Yolo2DDetector, -) - -try: - from dimos.perception.detection2d.detic_2d_det import ( # type: ignore[import-not-found, import-untyped] - Detic2DDetector, - ) - - DETIC_AVAILABLE = True -except (ModuleNotFoundError, ImportError): - DETIC_AVAILABLE = False - Detic2DDetector = None -from collections.abc import Callable -from typing import TYPE_CHECKING - -from dimos.models.depth.metric3d import Metric3D -from dimos.perception.common.utils import draw_object_detection_visualization -from dimos.perception.detection2d.utils import ( # type: ignore[attr-defined] - calculate_depth_from_bbox, - calculate_object_size_from_bbox, - calculate_position_rotation_from_bbox, -) -from dimos.types.vector import Vector -from dimos.utils.logging_config import setup_logger -from dimos.utils.transform_utils import transform_robot_to_map # type: ignore[attr-defined] - -if TYPE_CHECKING: - from dimos.types.manipulation import ObjectData - -# Initialize logger for the ObjectDetectionStream -logger = setup_logger() - - -class ObjectDetectionStream: - """ - A stream processor that: - 1. Detects objects using a Detector (Detic or Yolo) - 2. Estimates depth using Metric3D - 3. Calculates 3D position and dimensions using camera intrinsics - 4. Transforms coordinates to map frame - 5. Draws bounding boxes and segmentation masks on the frame - - Provides a stream of structured object data with position and rotation information. - """ - - def __init__( # type: ignore[no-untyped-def] - self, - camera_intrinsics=None, # [fx, fy, cx, cy] - device: str = "cuda", - gt_depth_scale: float = 1000.0, - min_confidence: float = 0.7, - class_filter=None, # Optional list of class names to filter (e.g., ["person", "car"]) - get_pose: Callable | None = None, # type: ignore[type-arg] # Optional function to transform coordinates to map frame - detector: Detic2DDetector | Yolo2DDetector | None = None, - video_stream: Observable = None, # type: ignore[assignment, type-arg] - disable_depth: bool = False, # Flag to disable monocular Metric3D depth estimation - draw_masks: bool = False, # Flag to enable drawing segmentation masks - ) -> None: - """ - Initialize the ObjectDetectionStream. - - Args: - camera_intrinsics: List [fx, fy, cx, cy] with camera parameters - device: Device to run inference on ("cuda" or "cpu") - gt_depth_scale: Ground truth depth scale for Metric3D - min_confidence: Minimum confidence for detections - class_filter: Optional list of class names to filter - get_pose: Optional function to transform pose to map coordinates - detector: Optional detector instance (Detic or Yolo) - video_stream: Observable of video frames to process (if provided, returns a stream immediately) - disable_depth: Flag to disable monocular Metric3D depth estimation - draw_masks: Flag to enable drawing segmentation masks - """ - self.min_confidence = min_confidence - self.class_filter = class_filter - self.get_pose = get_pose - self.disable_depth = disable_depth - self.draw_masks = draw_masks - # Initialize object detector - if detector is not None: - self.detector = detector - else: - if DETIC_AVAILABLE: - try: - self.detector = Detic2DDetector(vocabulary=None, threshold=min_confidence) - logger.info("Using Detic2DDetector") - except Exception as e: - logger.warning( - f"Failed to initialize Detic2DDetector: {e}. Falling back to Yolo2DDetector." - ) - self.detector = Yolo2DDetector() - else: - logger.info("Detic not available. Using Yolo2DDetector.") - self.detector = Yolo2DDetector() - # Set up camera intrinsics - self.camera_intrinsics = camera_intrinsics - - # Initialize depth estimation model - self.depth_model = None - if not disable_depth: - try: - self.depth_model = Metric3D(gt_depth_scale=gt_depth_scale) - - if camera_intrinsics is not None: - self.depth_model.update_intrinsic(camera_intrinsics) # type: ignore[no-untyped-call] - - # Create 3x3 camera matrix for calculations - fx, fy, cx, cy = camera_intrinsics - self.camera_matrix = np.array( - [[fx, 0, cx], [0, fy, cy], [0, 0, 1]], dtype=np.float32 - ) - else: - raise ValueError("camera_intrinsics must be provided") - - logger.info("Depth estimation enabled with Metric3D") - except Exception as e: - logger.warning(f"Failed to initialize Metric3D depth model: {e}") - logger.warning("Falling back to disable_depth=True mode") - self.disable_depth = True - self.depth_model = None - else: - logger.info("Depth estimation disabled") - - # If video_stream is provided, create and store the stream immediately - self.stream = None - if video_stream is not None: - self.stream = self.create_stream(video_stream) - - def create_stream(self, video_stream: Observable) -> Observable: # type: ignore[type-arg] - """ - Create an Observable stream of object data from a video stream. - - Args: - video_stream: Observable that emits video frames - - Returns: - Observable that emits dictionaries containing object data - with position and rotation information - """ - - def process_frame(frame): # type: ignore[no-untyped-def] - # TODO: More modular detector output interface - bboxes, track_ids, class_ids, confidences, names, *mask_data = ( # type: ignore[misc] - *self.detector.process_image(frame), - [], - ) - - masks = ( - mask_data[0] # type: ignore[has-type] - if mask_data and len(mask_data[0]) == len(bboxes) # type: ignore[has-type] - else [None] * len(bboxes) # type: ignore[has-type] - ) - - # Create visualization - viz_frame = frame.copy() - - # Process detections - objects = [] - if not self.disable_depth: - depth_map = self.depth_model.infer_depth(frame) # type: ignore[union-attr] - depth_map = np.array(depth_map) - else: - depth_map = None - - for i, bbox in enumerate(bboxes): # type: ignore[has-type] - # Skip if confidence is too low - if i < len(confidences) and confidences[i] < self.min_confidence: # type: ignore[has-type] - continue - - # Skip if class filter is active and class not in filter - class_name = names[i] if i < len(names) else None # type: ignore[has-type] - if self.class_filter and class_name not in self.class_filter: - continue - - if not self.disable_depth and depth_map is not None: - # Get depth for this object - depth = calculate_depth_from_bbox(depth_map, bbox) # type: ignore[no-untyped-call] - if depth is None: - # Skip objects with invalid depth - continue - # Calculate object position and rotation - position, rotation = calculate_position_rotation_from_bbox( - bbox, depth, self.camera_intrinsics - ) - # Get object dimensions - width, height = calculate_object_size_from_bbox( - bbox, depth, self.camera_intrinsics - ) - - # Transform to map frame if a transform function is provided - try: - if self.get_pose: - # position and rotation are already Vector objects, no need to convert - robot_pose = self.get_pose() - position, rotation = transform_robot_to_map( - robot_pose["position"], robot_pose["rotation"], position, rotation - ) - except Exception as e: - logger.error(f"Error transforming to map frame: {e}") - position, rotation = position, rotation - - else: - depth = -1 - position = Vector(0, 0, 0) # type: ignore[arg-type] - rotation = Vector(0, 0, 0) # type: ignore[arg-type] - width = -1 - height = -1 - - # Create a properly typed ObjectData instance - object_data: ObjectData = { - "object_id": track_ids[i] if i < len(track_ids) else -1, # type: ignore[has-type] - "bbox": bbox, - "depth": depth, - "confidence": confidences[i] if i < len(confidences) else None, # type: ignore[has-type, typeddict-item] - "class_id": class_ids[i] if i < len(class_ids) else None, # type: ignore[has-type, typeddict-item] - "label": class_name, # type: ignore[typeddict-item] - "position": position, - "rotation": rotation, - "size": {"width": width, "height": height}, - "segmentation_mask": masks[i], - } - - objects.append(object_data) - - # Create visualization using common function - viz_frame = draw_object_detection_visualization( - viz_frame, objects, draw_masks=self.draw_masks, font_scale=1.5 - ) - - return {"frame": frame, "viz_frame": viz_frame, "objects": objects} - - self.stream = video_stream.pipe(ops.map(process_frame)) - - return self.stream - - def get_stream(self): # type: ignore[no-untyped-def] - """ - Returns the current detection stream if available. - Creates a new one with the provided video_stream if not already created. - - Returns: - Observable: The reactive stream of detection results - """ - if self.stream is None: - raise ValueError( - "Stream not initialized. Either provide a video_stream during initialization or call create_stream first." - ) - return self.stream - - def get_formatted_stream(self): # type: ignore[no-untyped-def] - """ - Returns a formatted stream of object detection data for better readability. - This is especially useful for LLMs like Claude that need structured text input. - - Returns: - Observable: A stream of formatted string representations of object data - """ - if self.stream is None: - raise ValueError( - "Stream not initialized. Either provide a video_stream during initialization or call create_stream first." - ) - - def format_detection_data(result): # type: ignore[no-untyped-def] - # Extract objects from result - objects = result.get("objects", []) - - if not objects: - return "No objects detected." - - formatted_data = "[DETECTED OBJECTS]\n" - try: - for i, obj in enumerate(objects): - pos = obj["position"] - rot = obj["rotation"] - size = obj["size"] - bbox = obj["bbox"] - - # Format each object with a multiline f-string for better readability - bbox_str = f"[{bbox[0]}, {bbox[1]}, {bbox[2]}, {bbox[3]}]" - formatted_data += ( - f"Object {i + 1}: {obj['label']}\n" - f" ID: {obj['object_id']}\n" - f" Confidence: {obj['confidence']:.2f}\n" - f" Position: x={pos.x:.2f}m, y={pos.y:.2f}m, z={pos.z:.2f}m\n" - f" Rotation: yaw={rot.z:.2f} rad\n" - f" Size: width={size['width']:.2f}m, height={size['height']:.2f}m\n" - f" Depth: {obj['depth']:.2f}m\n" - f" Bounding box: {bbox_str}\n" - "----------------------------------\n" - ) - except Exception as e: - logger.warning(f"Error formatting object {i}: {e}") - formatted_data += f"Object {i + 1}: [Error formatting data]" - formatted_data += "\n----------------------------------\n" - - return formatted_data - - # Return a new stream with the formatter applied - return self.stream.pipe(ops.map(format_detection_data)) - - def cleanup(self) -> None: - """Clean up resources.""" - pass diff --git a/dimos/perception/object_scene_registration.py b/dimos/perception/object_scene_registration.py new file mode 100644 index 0000000000..3c92da70dc --- /dev/null +++ b/dimos/perception/object_scene_registration.py @@ -0,0 +1,259 @@ +# 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 time +from typing import Any + +import numpy as np +from numpy.typing import NDArray + +from dimos.core import In, Out, rpc +from dimos.core.skill_module import SkillModule +from dimos.msgs.sensor_msgs import CameraInfo, Image, PointCloud2 +from dimos.msgs.std_msgs import Header +from dimos.msgs.vision_msgs import Detection2DArray, Detection3DArray +from dimos.perception.detection.detectors.yoloe import Yoloe2DDetector, YoloePromptMode +from dimos.perception.detection.objectDB import ObjectDB +from dimos.perception.detection.type import ImageDetections2D +from dimos.perception.detection.type.detection3d.object import ( + Object, + aggregate_pointclouds, + to_detection3d_array, +) +from dimos.protocol.skill.skill import skill +from dimos.types.timestamped import align_timestamped +from dimos.utils.logging_config import setup_logger +from dimos.utils.reactive import backpressure + +logger = setup_logger() + + +class ObjectSceneRegistrationModule(SkillModule): + """Module for detecting objects in camera images using YOLO-E with 2D and 3D detection.""" + + color_image: In[Image] + depth_image: In[Image] + camera_info: In[CameraInfo] + + detections_2d: Out[Detection2DArray] + detections_3d: Out[Detection3DArray] + overlay: Out[Image] + pointcloud: Out[PointCloud2] + + _detector: Yoloe2DDetector | None = None + _camera_info: CameraInfo | None = None + _object_db: ObjectDB | None = None + + def __init__( + self, + target_frame: str = "map", + prompt_mode: YoloePromptMode = YoloePromptMode.LRPC, + ) -> None: + super().__init__() + self._target_frame = target_frame + self._prompt_mode = prompt_mode + + @rpc + def start(self) -> None: + super().start() + self._object_db = ObjectDB() + + if self._prompt_mode == YoloePromptMode.LRPC: + model_name = "yoloe-11l-seg-pf.pt" + else: + model_name = "yoloe-11l-seg.pt" + + self._detector = Yoloe2DDetector( + model_name=model_name, + prompt_mode=self._prompt_mode, + ) + + self.camera_info.subscribe(lambda msg: setattr(self, "_camera_info", msg)) + + aligned_frames = align_timestamped( + self.color_image.observable(), # type: ignore[no-untyped-call] + self.depth_image.observable(), # type: ignore[no-untyped-call] + buffer_size=2.0, + match_tolerance=0.1, + ) + backpressure(aligned_frames).subscribe(self._on_aligned_frames) + + @rpc + def stop(self) -> None: + """Stop the module and clean up resources.""" + + if self._detector: + self._detector.stop() + self._detector = None + + if self._object_db: + self._object_db.clear() + self._object_db = None + + logger.info("ObjectSceneRegistrationModule stopped") + super().stop() + + @property + def object_db(self) -> ObjectDB | None: + """Access the ObjectDB for querying detected objects.""" + return self._object_db + + @rpc + def set_prompts( + self, + text: list[str] | None = None, + bboxes: NDArray[np.float64] | None = None, + ) -> None: + """Set prompts for detection. Provide either text or bboxes, not both.""" + if self._detector is not None: + self._detector.set_prompts(text=text, bboxes=bboxes) + + @rpc + def select_object(self, track_id: int) -> dict[str, Any] | None: + """Get object data by track_id and promote to permanent.""" + if self._object_db is None: + return None + for obj in self._object_db.get_all_objects(): + if obj.track_id == track_id: + self._object_db.promote(obj.object_id) + return obj.to_dict() + return None + + @rpc + def get_object_track_ids(self) -> list[int]: + """Get track_ids of all permanent objects.""" + if self._object_db is None: + return [] + return [obj.track_id for obj in self._object_db.get_all_objects()] + + @skill() + def detect(self, *prompts: str) -> str: + """Detect objects matching the given text prompts. Returns track_ids after 2 seconds of detection. + + Do NOT call this tool multiple times for one query. Pass all objects in a single call. + For example, to detect a cup and mouse, call detect("cup", "mouse") not detect("cup") then detect("mouse"). + + Args: + prompts (str): Text descriptions of objects to detect (e.g., "person", "car", "dog") + + Returns: + str: A message containing the track_ids of detected objects + + Example: + detect("person", "car", "dog") + detect("person") + """ + if not prompts: + return "No prompts provided." + if self._detector is None: + return "Detector not initialized." + + self._detector.set_prompts(text=list(prompts)) + time.sleep(2.0) + + track_ids = self.get_object_track_ids() + if not track_ids: + return "No objects detected." + return f"Detected objects with track_ids: {track_ids}" + + @skill() + def select(self, track_id: int) -> str: + """Select an object by track_id and promote it to permanent. + + Example: + select(5) + """ + result = self.select_object(track_id) + if result is None: + return f"No object found with track_id {track_id}." + return f"Selected object {track_id}: {result['name']}" + + def _on_aligned_frames(self, frames) -> None: # type: ignore[no-untyped-def] + color_msg, depth_msg = frames + self._process_images(color_msg, depth_msg) + + def _process_images(self, color_msg: Image, depth_msg: Image) -> None: + """Process synchronized color and depth images (runs in background thread).""" + if not self._detector or not self._camera_info: + return + + color_image = color_msg + depth_image = depth_msg.to_depth_meters() + + # Run 2D detection + detections_2d: ImageDetections2D[Any] = self._detector.process_image(color_image) + + detections_2d_msg = Detection2DArray( + detections_length=len(detections_2d.detections), + header=Header(color_image.ts, color_image.frame_id or ""), + detections=[det.to_ros_detection2d() for det in detections_2d.detections], + ) + self.detections_2d.publish(detections_2d_msg) + + overlay_image = detections_2d.overlay() + self.overlay.publish(overlay_image) + + # Process 3D detections + self._process_3d_detections(detections_2d, color_image, depth_image) + + def _process_3d_detections( + self, + detections_2d: ImageDetections2D[Any], + color_image: Image, + depth_image: Image, + ) -> None: + """Convert 2D detections to 3D and publish.""" + if self._camera_info is None: + return + + # Look up transform from camera frame to target frame (e.g., map) + camera_transform = None + if self._target_frame != color_image.frame_id: + camera_transform = self.tf.get( + self._target_frame, + color_image.frame_id, + color_image.ts, + 0.1, + ) + if camera_transform is None: + logger.warning("Failed to lookup transform from camera frame to target frame") + return + + objects = Object.from_2d( + detections_2d=detections_2d, + color_image=color_image, + depth_image=depth_image, + camera_info=self._camera_info, + camera_transform=camera_transform, + ) + if not objects: + return + + # Add objects to spatial memory database + if self._object_db is not None: + objects = self._object_db.add_objects(objects) + + detections_3d = to_detection3d_array(objects) + self.detections_3d.publish(detections_3d) + + objects_for_pc = self._object_db.get_objects() if self._object_db else objects + aggregated_pc = aggregate_pointclouds(objects_for_pc) + if aggregated_pc is not None: + self.pointcloud.publish(aggregated_pc) + return + + +object_scene_registration_module = ObjectSceneRegistrationModule.blueprint + +__all__ = ["ObjectSceneRegistrationModule", "object_scene_registration_module"] diff --git a/dimos/perception/object_tracker.py b/dimos/perception/object_tracker.py index 9260003ce2..54a5873435 100644 --- a/dimos/perception/object_tracker.py +++ b/dimos/perception/object_tracker.py @@ -28,7 +28,6 @@ from reactivex.disposable import Disposable from dimos.core import In, Module, ModuleConfig, Out, rpc -from dimos.manipulation.visual_servoing.utils import visualize_detections_3d from dimos.msgs.geometry_msgs import Pose, Quaternion, Transform, Vector3 from dimos.msgs.sensor_msgs import ( CameraInfo, @@ -540,10 +539,13 @@ def _process_tracking(self) -> None: y2 = det_2d.bbox.center.position.y + det_2d.bbox.size_y / 2 bbox_2d = [[x1, y1, x2, y2]] - # Create visualization - viz_image = visualize_detections_3d( - frame, detections_3d, show_coordinates=True, bboxes_2d=bbox_2d - ) + # Use frame directly for visualization + viz_image = frame.copy() + + # Draw bounding boxes + for bbox in bbox_2d: + x1, y1, x2, y2 = map(int, bbox) + cv2.rectangle(viz_image, (x1, y1), (x2, y2), (0, 255, 0), 2) # Overlay REID feature matches if available if self.last_good_matches and self.last_roi_kps and self.last_roi_bbox: diff --git a/dimos/perception/object_tracker_3d.py b/dimos/perception/object_tracker_3d.py index 22846e1e2f..fa6361ac65 100644 --- a/dimos/perception/object_tracker_3d.py +++ b/dimos/perception/object_tracker_3d.py @@ -14,6 +14,7 @@ # Import LCM messages +import cv2 from dimos_lcm.sensor_msgs import CameraInfo from dimos_lcm.vision_msgs import ( Detection3D, @@ -22,7 +23,6 @@ import numpy as np from dimos.core import In, Out, rpc -from dimos.manipulation.visual_servoing.utils import visualize_detections_3d from dimos.msgs.geometry_msgs import Pose, Quaternion, Transform, Vector3 from dimos.msgs.sensor_msgs import Image, ImageFormat from dimos.msgs.std_msgs import Header @@ -145,10 +145,13 @@ def _process_tracking(self) -> None: y2 = det_2d.bbox.center.position.y + det_2d.bbox.size_y / 2 bbox_2d = [[x1, y1, x2, y2]] - # Create 3D visualization - viz_image = visualize_detections_3d( - frame, detection_3d.detections, show_coordinates=True, bboxes_2d=bbox_2d - ) + # Use frame directly for visualization + viz_image = frame.copy() + + # Draw bounding boxes + for bbox in bbox_2d: + x1, y1, x2, y2 = map(int, bbox) + cv2.rectangle(viz_image, (x1, y1), (x2, y2), (0, 255, 0), 2) # Overlay Re-ID matches if self.last_good_matches and self.last_roi_kps and self.last_roi_bbox: diff --git a/dimos/perception/person_tracker.py b/dimos/perception/person_tracker.py deleted file mode 100644 index a138467850..0000000000 --- a/dimos/perception/person_tracker.py +++ /dev/null @@ -1,262 +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 cv2 -import numpy as np -from reactivex import Observable, interval, operators as ops -from reactivex.disposable import Disposable - -from dimos.core import In, Module, Out, rpc -from dimos.msgs.sensor_msgs import Image -from dimos.perception.common.ibvs import PersonDistanceEstimator -from dimos.perception.detection2d.utils import filter_detections -from dimos.perception.detection2d.yolo_2d_det import ( # type: ignore[import-not-found, import-untyped] - Yolo2DDetector, -) -from dimos.utils.logging_config import setup_logger - -logger = setup_logger() - - -class PersonTrackingStream(Module): - """Module for person tracking with LCM input/output.""" - - # LCM inputs - video: In[Image] - - # LCM outputs - tracking_data: Out[dict] # type: ignore[type-arg] - - def __init__( # type: ignore[no-untyped-def] - self, - camera_intrinsics=None, - camera_pitch: float = 0.0, - camera_height: float = 1.0, - ) -> None: - """ - Initialize a person tracking stream using Yolo2DDetector and PersonDistanceEstimator. - - Args: - camera_intrinsics: List in format [fx, fy, cx, cy] where: - - fx: Focal length in x direction (pixels) - - fy: Focal length in y direction (pixels) - - cx: Principal point x-coordinate (pixels) - - cy: Principal point y-coordinate (pixels) - camera_pitch: Camera pitch angle in radians (positive is up) - camera_height: Height of the camera from the ground in meters - """ - # Call parent Module init - super().__init__() - - self.camera_intrinsics = camera_intrinsics - self.camera_pitch = camera_pitch - self.camera_height = camera_height - - self.detector = Yolo2DDetector() - - # Initialize distance estimator - if camera_intrinsics is None: - raise ValueError("Camera intrinsics are required for distance estimation") - - # Validate camera intrinsics format [fx, fy, cx, cy] - if ( - not isinstance(camera_intrinsics, list | tuple | np.ndarray) - or len(camera_intrinsics) != 4 - ): - raise ValueError("Camera intrinsics must be provided as [fx, fy, cx, cy]") - - # Convert [fx, fy, cx, cy] to 3x3 camera matrix - fx, fy, cx, cy = camera_intrinsics - K = np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]], dtype=np.float32) - - self.distance_estimator = PersonDistanceEstimator( - K=K, camera_pitch=camera_pitch, camera_height=camera_height - ) - - # For tracking latest frame data - self._latest_frame: np.ndarray | None = None # type: ignore[type-arg] - self._process_interval = 0.1 # Process at 10Hz - - # Tracking state - starts disabled - self._tracking_enabled = False - - @rpc - def start(self) -> None: - """Start the person tracking module and subscribe to LCM streams.""" - - super().start() - - # Subscribe to video stream - def set_video(image_msg: Image) -> None: - if hasattr(image_msg, "data"): - self._latest_frame = image_msg.data - else: - logger.warning("Received image message without data attribute") - - unsub = self.video.subscribe(set_video) - self._disposables.add(Disposable(unsub)) - - # Start periodic processing - unsub = interval(self._process_interval).subscribe(lambda _: self._process_frame()) # type: ignore[assignment] - self._disposables.add(unsub) # type: ignore[arg-type] - - logger.info("PersonTracking module started and subscribed to LCM streams") - - @rpc - def stop(self) -> None: - super().stop() - - def _process_frame(self) -> None: - """Process the latest frame if available.""" - if self._latest_frame is None: - return - - # Only process and publish if tracking is enabled - if not self._tracking_enabled: - return - - # Process frame through tracking pipeline - result = self._process_tracking(self._latest_frame) # type: ignore[no-untyped-call] - - # Publish result to LCM - if result: - self.tracking_data.publish(result) - - def _process_tracking(self, frame): # type: ignore[no-untyped-def] - """Process a single frame for person tracking.""" - # Detect people in the frame - bboxes, track_ids, class_ids, confidences, names = self.detector.process_image(frame) - - # Filter to keep only person detections using filter_detections - ( - filtered_bboxes, - filtered_track_ids, - filtered_class_ids, - filtered_confidences, - filtered_names, - ) = filter_detections( - bboxes, - track_ids, - class_ids, - confidences, - names, - class_filter=[0], # 0 is the class_id for person - name_filter=["person"], - ) - - # Create visualization - viz_frame = self.detector.visualize_results( - frame, - filtered_bboxes, - filtered_track_ids, - filtered_class_ids, - filtered_confidences, - filtered_names, - ) - - # Calculate distance and angle for each person - targets = [] - for i, bbox in enumerate(filtered_bboxes): - target_data = { - "target_id": filtered_track_ids[i] if i < len(filtered_track_ids) else -1, - "bbox": bbox, - "confidence": filtered_confidences[i] if i < len(filtered_confidences) else None, - } - - distance, angle = self.distance_estimator.estimate_distance_angle(bbox) - target_data["distance"] = distance - target_data["angle"] = angle - - # Add text to visualization - _x1, y1, x2, _y2 = map(int, bbox) - dist_text = f"{distance:.2f}m, {np.rad2deg(angle):.1f} deg" - - # Add black background for better visibility - text_size = cv2.getTextSize(dist_text, cv2.FONT_HERSHEY_SIMPLEX, 0.5, 2)[0] - # Position at top-right corner - cv2.rectangle( - viz_frame, (x2 - text_size[0], y1 - text_size[1] - 5), (x2, y1), (0, 0, 0), -1 - ) - - # Draw text in white at top-right - cv2.putText( - viz_frame, - dist_text, - (x2 - text_size[0], y1 - 5), - cv2.FONT_HERSHEY_SIMPLEX, - 0.5, - (255, 255, 255), - 2, - ) - - targets.append(target_data) - - # Create the result dictionary - return {"frame": frame, "viz_frame": viz_frame, "targets": targets} - - @rpc - def enable_tracking(self) -> bool: - """Enable person tracking. - - Returns: - bool: True if tracking was enabled successfully - """ - self._tracking_enabled = True - logger.info("Person tracking enabled") - return True - - @rpc - def disable_tracking(self) -> bool: - """Disable person tracking. - - Returns: - bool: True if tracking was disabled successfully - """ - self._tracking_enabled = False - logger.info("Person tracking disabled") - return True - - @rpc - def is_tracking_enabled(self) -> bool: - """Check if tracking is currently enabled. - - Returns: - bool: True if tracking is enabled - """ - return self._tracking_enabled - - @rpc - def get_tracking_data(self) -> dict: # type: ignore[type-arg] - """Get the latest tracking data. - - Returns: - Dictionary containing tracking results - """ - if self._latest_frame is not None: - return self._process_tracking(self._latest_frame) # type: ignore[no-any-return, no-untyped-call] - return {"frame": None, "viz_frame": None, "targets": []} - - def create_stream(self, video_stream: Observable) -> Observable: # type: ignore[type-arg] - """ - Create an Observable stream of person tracking results from a video stream. - - Args: - video_stream: Observable that emits video frames - - Returns: - Observable that emits dictionaries containing tracking results and visualizations - """ - - return video_stream.pipe(ops.map(self._process_tracking)) diff --git a/dimos/perception/pointcloud/__init__.py b/dimos/perception/pointcloud/__init__.py deleted file mode 100644 index a380e2aadf..0000000000 --- a/dimos/perception/pointcloud/__init__.py +++ /dev/null @@ -1,3 +0,0 @@ -from .cuboid_fit import * -from .pointcloud_filtering import * -from .utils import * diff --git a/dimos/perception/pointcloud/cuboid_fit.py b/dimos/perception/pointcloud/cuboid_fit.py deleted file mode 100644 index dfec2d9297..0000000000 --- a/dimos/perception/pointcloud/cuboid_fit.py +++ /dev/null @@ -1,420 +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 cv2 -import numpy as np -import open3d as o3d # type: ignore[import-untyped] - - -def fit_cuboid( - points: np.ndarray | o3d.geometry.PointCloud, # type: ignore[type-arg] - method: str = "minimal", -) -> dict | None: # type: ignore[type-arg] - """ - Fit a cuboid to a point cloud using Open3D's built-in methods. - - Args: - points: Nx3 array of points or Open3D PointCloud - method: Fitting method: - - 'minimal': Minimal oriented bounding box (best fit) - - 'oriented': PCA-based oriented bounding box - - 'axis_aligned': Axis-aligned bounding box - - Returns: - Dictionary containing: - - center: 3D center point - - dimensions: 3D dimensions (extent) - - rotation: 3x3 rotation matrix - - error: Fitting error - - bounding_box: Open3D OrientedBoundingBox object - Returns None if insufficient points or fitting fails. - - Raises: - ValueError: If method is invalid or inputs are malformed - """ - # Validate method - valid_methods = ["minimal", "oriented", "axis_aligned"] - if method not in valid_methods: - raise ValueError(f"method must be one of {valid_methods}, got '{method}'") - - # Convert to point cloud if needed - if isinstance(points, np.ndarray): - points = np.asarray(points) - if len(points.shape) != 2 or points.shape[1] != 3: - raise ValueError(f"points array must be Nx3, got shape {points.shape}") - if len(points) < 4: - return None - - pcd = o3d.geometry.PointCloud() - pcd.points = o3d.utility.Vector3dVector(points) - elif isinstance(points, o3d.geometry.PointCloud): - pcd = points - points = np.asarray(pcd.points) - if len(points) < 4: - return None - else: - raise ValueError(f"points must be numpy array or Open3D PointCloud, got {type(points)}") - - try: - # Get bounding box based on method - if method == "minimal": - obb = pcd.get_minimal_oriented_bounding_box(robust=True) - elif method == "oriented": - obb = pcd.get_oriented_bounding_box(robust=True) - elif method == "axis_aligned": - # Convert axis-aligned to oriented format for consistency - aabb = pcd.get_axis_aligned_bounding_box() - obb = o3d.geometry.OrientedBoundingBox() - obb.center = aabb.get_center() - obb.extent = aabb.get_extent() - obb.R = np.eye(3) # Identity rotation for axis-aligned - - # Extract parameters - center = np.asarray(obb.center) - dimensions = np.asarray(obb.extent) - rotation = np.asarray(obb.R) - - # Calculate fitting error - error = _compute_fitting_error(points, center, dimensions, rotation) - - return { - "center": center, - "dimensions": dimensions, - "rotation": rotation, - "error": error, - "bounding_box": obb, - "method": method, - } - - except Exception as e: - # Log error but don't crash - return None for graceful handling - print(f"Warning: Cuboid fitting failed with method '{method}': {e}") - return None - - -def fit_cuboid_simple(points: np.ndarray | o3d.geometry.PointCloud) -> dict | None: # type: ignore[type-arg] - """ - Simple wrapper for minimal oriented bounding box fitting. - - Args: - points: Nx3 array of points or Open3D PointCloud - - Returns: - Dictionary with center, dimensions, rotation, and bounding_box, - or None if insufficient points - """ - return fit_cuboid(points, method="minimal") - - -def _compute_fitting_error( - points: np.ndarray, # type: ignore[type-arg] - center: np.ndarray, # type: ignore[type-arg] - dimensions: np.ndarray, # type: ignore[type-arg] - rotation: np.ndarray, # type: ignore[type-arg] -) -> float: - """ - Compute fitting error as mean squared distance from points to cuboid surface. - - Args: - points: Nx3 array of points - center: 3D center point - dimensions: 3D dimensions - rotation: 3x3 rotation matrix - - Returns: - Mean squared error - """ - if len(points) == 0: - return 0.0 - - # Transform points to local coordinates - local_points = (points - center) @ rotation - half_dims = dimensions / 2 - - # Calculate distance to cuboid surface - dx = np.abs(local_points[:, 0]) - half_dims[0] - dy = np.abs(local_points[:, 1]) - half_dims[1] - dz = np.abs(local_points[:, 2]) - half_dims[2] - - # Points outside: distance to nearest face - # Points inside: negative distance to nearest face - outside_dist = np.sqrt(np.maximum(dx, 0) ** 2 + np.maximum(dy, 0) ** 2 + np.maximum(dz, 0) ** 2) - inside_dist = np.minimum(np.minimum(dx, dy), dz) - distances = np.where((dx > 0) | (dy > 0) | (dz > 0), outside_dist, -inside_dist) - - return float(np.mean(distances**2)) - - -def get_cuboid_corners( - center: np.ndarray, # type: ignore[type-arg] - dimensions: np.ndarray, # type: ignore[type-arg] - rotation: np.ndarray, # type: ignore[type-arg] -) -> np.ndarray: # type: ignore[type-arg] - """ - Get the 8 corners of a cuboid. - - Args: - center: 3D center point - dimensions: 3D dimensions - rotation: 3x3 rotation matrix - - Returns: - 8x3 array of corner coordinates - """ - half_dims = dimensions / 2 - corners_local = ( - np.array( - [ - [-1, -1, -1], # 0: left bottom back - [-1, -1, 1], # 1: left bottom front - [-1, 1, -1], # 2: left top back - [-1, 1, 1], # 3: left top front - [1, -1, -1], # 4: right bottom back - [1, -1, 1], # 5: right bottom front - [1, 1, -1], # 6: right top back - [1, 1, 1], # 7: right top front - ] - ) - * half_dims - ) - - # Apply rotation and translation - return corners_local @ rotation.T + center # type: ignore[no-any-return] - - -def visualize_cuboid_on_image( - image: np.ndarray, # type: ignore[type-arg] - cuboid_params: dict, # type: ignore[type-arg] - camera_matrix: np.ndarray, # type: ignore[type-arg] - extrinsic_rotation: np.ndarray | None = None, # type: ignore[type-arg] - extrinsic_translation: np.ndarray | None = None, # type: ignore[type-arg] - color: tuple[int, int, int] = (0, 255, 0), - thickness: int = 2, - show_dimensions: bool = True, -) -> np.ndarray: # type: ignore[type-arg] - """ - Draw a fitted cuboid on an image using camera projection. - - Args: - image: Input image to draw on - cuboid_params: Dictionary containing cuboid parameters - camera_matrix: Camera intrinsic matrix (3x3) - extrinsic_rotation: Optional external rotation (3x3) - extrinsic_translation: Optional external translation (3x1) - color: Line color as (B, G, R) tuple - thickness: Line thickness - show_dimensions: Whether to display dimension text - - Returns: - Image with cuboid visualization - - Raises: - ValueError: If required parameters are missing or invalid - """ - # Validate inputs - required_keys = ["center", "dimensions", "rotation"] - if not all(key in cuboid_params for key in required_keys): - raise ValueError(f"cuboid_params must contain keys: {required_keys}") - - if camera_matrix.shape != (3, 3): - raise ValueError(f"camera_matrix must be 3x3, got {camera_matrix.shape}") - - # Get corners in world coordinates - corners = get_cuboid_corners( - cuboid_params["center"], cuboid_params["dimensions"], cuboid_params["rotation"] - ) - - # Transform corners if extrinsic parameters are provided - if extrinsic_rotation is not None and extrinsic_translation is not None: - if extrinsic_rotation.shape != (3, 3): - raise ValueError(f"extrinsic_rotation must be 3x3, got {extrinsic_rotation.shape}") - if extrinsic_translation.shape not in [(3,), (3, 1)]: - raise ValueError( - f"extrinsic_translation must be (3,) or (3,1), got {extrinsic_translation.shape}" - ) - - extrinsic_translation = extrinsic_translation.flatten() - corners = (extrinsic_rotation @ corners.T).T + extrinsic_translation - - try: - # Project 3D corners to image coordinates - corners_img, _ = cv2.projectPoints( # type: ignore[call-overload] - corners.astype(np.float32), - np.zeros(3), - np.zeros(3), # No additional rotation/translation - camera_matrix.astype(np.float32), - None, # No distortion - ) - corners_img = corners_img.reshape(-1, 2).astype(int) - - # Check if corners are within image bounds - h, w = image.shape[:2] - valid_corners = ( - (corners_img[:, 0] >= 0) - & (corners_img[:, 0] < w) - & (corners_img[:, 1] >= 0) - & (corners_img[:, 1] < h) - ) - - if not np.any(valid_corners): - print("Warning: All cuboid corners are outside image bounds") - return image.copy() - - except Exception as e: - print(f"Warning: Failed to project cuboid corners: {e}") - return image.copy() - - # Define edges for wireframe visualization - edges = [ - # Bottom face - (0, 1), - (1, 5), - (5, 4), - (4, 0), - # Top face - (2, 3), - (3, 7), - (7, 6), - (6, 2), - # Vertical edges - (0, 2), - (1, 3), - (5, 7), - (4, 6), - ] - - # Draw edges - vis_img = image.copy() - for i, j in edges: - # Only draw edge if both corners are valid - if valid_corners[i] and valid_corners[j]: - cv2.line(vis_img, tuple(corners_img[i]), tuple(corners_img[j]), color, thickness) - - # Add dimension text if requested - if show_dimensions and np.any(valid_corners): - dims = cuboid_params["dimensions"] - dim_text = f"Dims: {dims[0]:.3f} x {dims[1]:.3f} x {dims[2]:.3f}" - - # Find a good position for text (top-left of image) - text_pos = (10, 30) - font_scale = 0.7 - - # Add background rectangle for better readability - text_size = cv2.getTextSize(dim_text, cv2.FONT_HERSHEY_SIMPLEX, font_scale, 2)[0] - cv2.rectangle( - vis_img, - (text_pos[0] - 5, text_pos[1] - text_size[1] - 5), - (text_pos[0] + text_size[0] + 5, text_pos[1] + 5), - (0, 0, 0), - -1, - ) - - cv2.putText(vis_img, dim_text, text_pos, cv2.FONT_HERSHEY_SIMPLEX, font_scale, color, 2) - - return vis_img - - -def compute_cuboid_volume(cuboid_params: dict) -> float: # type: ignore[type-arg] - """ - Compute the volume of a cuboid. - - Args: - cuboid_params: Dictionary containing cuboid parameters - - Returns: - Volume in cubic units - """ - if "dimensions" not in cuboid_params: - raise ValueError("cuboid_params must contain 'dimensions' key") - - dims = cuboid_params["dimensions"] - return float(np.prod(dims)) - - -def compute_cuboid_surface_area(cuboid_params: dict) -> float: # type: ignore[type-arg] - """ - Compute the surface area of a cuboid. - - Args: - cuboid_params: Dictionary containing cuboid parameters - - Returns: - Surface area in square units - """ - if "dimensions" not in cuboid_params: - raise ValueError("cuboid_params must contain 'dimensions' key") - - dims = cuboid_params["dimensions"] - return 2.0 * (dims[0] * dims[1] + dims[1] * dims[2] + dims[2] * dims[0]) # type: ignore[no-any-return] - - -def check_cuboid_quality(cuboid_params: dict, points: np.ndarray) -> dict: # type: ignore[type-arg] - """ - Assess the quality of a cuboid fit. - - Args: - cuboid_params: Dictionary containing cuboid parameters - points: Original points used for fitting - - Returns: - Dictionary with quality metrics - """ - if len(points) == 0: - return {"error": "No points provided"} - - # Basic metrics - volume = compute_cuboid_volume(cuboid_params) - surface_area = compute_cuboid_surface_area(cuboid_params) - error = cuboid_params.get("error", 0.0) - - # Aspect ratio analysis - dims = cuboid_params["dimensions"] - aspect_ratios = [ - dims[0] / dims[1] if dims[1] > 0 else float("inf"), - dims[1] / dims[2] if dims[2] > 0 else float("inf"), - dims[2] / dims[0] if dims[0] > 0 else float("inf"), - ] - max_aspect_ratio = max(aspect_ratios) - - # Volume ratio (cuboid volume vs convex hull volume) - try: - pcd = o3d.geometry.PointCloud() - pcd.points = o3d.utility.Vector3dVector(points) - hull, _ = pcd.compute_convex_hull() - hull_volume = hull.get_volume() - volume_ratio = volume / hull_volume if hull_volume > 0 else float("inf") - except: - volume_ratio = None - - return { - "fitting_error": error, - "volume": volume, - "surface_area": surface_area, - "max_aspect_ratio": max_aspect_ratio, - "volume_ratio": volume_ratio, - "num_points": len(points), - "method": cuboid_params.get("method", "unknown"), - } - - -# Backward compatibility -def visualize_fit(image, cuboid_params, camera_matrix, R=None, t=None): # type: ignore[no-untyped-def] - """ - Legacy function for backward compatibility. - Use visualize_cuboid_on_image instead. - """ - return visualize_cuboid_on_image( - image, cuboid_params, camera_matrix, R, t, show_dimensions=True - ) diff --git a/dimos/perception/pointcloud/pointcloud_filtering.py b/dimos/perception/pointcloud/pointcloud_filtering.py deleted file mode 100644 index d6aa2b835f..0000000000 --- a/dimos/perception/pointcloud/pointcloud_filtering.py +++ /dev/null @@ -1,370 +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 cv2 -import numpy as np -import open3d as o3d # type: ignore[import-untyped] -import torch - -from dimos.perception.pointcloud.cuboid_fit import fit_cuboid -from dimos.perception.pointcloud.utils import ( - create_point_cloud_and_extract_masks, - load_camera_matrix_from_yaml, -) -from dimos.types.manipulation import ObjectData -from dimos.types.vector import Vector - - -class PointcloudFiltering: - """ - A production-ready point cloud filtering pipeline for segmented objects. - - This class takes segmentation results and produces clean, filtered point clouds - for each object with consistent coloring and optional outlier removal. - """ - - def __init__( - self, - color_intrinsics: str | list[float] | np.ndarray | None = None, # type: ignore[type-arg] - depth_intrinsics: str | list[float] | np.ndarray | None = None, # type: ignore[type-arg] - color_weight: float = 0.3, - enable_statistical_filtering: bool = True, - statistical_neighbors: int = 20, - statistical_std_ratio: float = 1.5, - enable_radius_filtering: bool = True, - radius_filtering_radius: float = 0.015, - radius_filtering_min_neighbors: int = 25, - enable_subsampling: bool = True, - voxel_size: float = 0.005, - max_num_objects: int = 10, - min_points_for_cuboid: int = 10, - cuboid_method: str = "oriented", - max_bbox_size_percent: float = 30.0, - ) -> None: - """ - Initialize the point cloud filtering pipeline. - - Args: - color_intrinsics: Camera intrinsics for color image - depth_intrinsics: Camera intrinsics for depth image - color_weight: Weight for blending generated color with original (0.0-1.0) - enable_statistical_filtering: Enable/disable statistical outlier filtering - statistical_neighbors: Number of neighbors for statistical filtering - statistical_std_ratio: Standard deviation ratio for statistical filtering - enable_radius_filtering: Enable/disable radius outlier filtering - radius_filtering_radius: Search radius for radius filtering (meters) - radius_filtering_min_neighbors: Min neighbors within radius - enable_subsampling: Enable/disable point cloud subsampling - voxel_size: Voxel size for downsampling (meters, when subsampling enabled) - max_num_objects: Maximum number of objects to process (top N by confidence) - min_points_for_cuboid: Minimum points required for cuboid fitting - cuboid_method: Method for cuboid fitting ('minimal', 'oriented', 'axis_aligned') - max_bbox_size_percent: Maximum percentage of image size for object bboxes (0-100) - - Raises: - ValueError: If invalid parameters are provided - """ - # Validate parameters - if not 0.0 <= color_weight <= 1.0: - raise ValueError(f"color_weight must be between 0.0 and 1.0, got {color_weight}") - if not 0.0 <= max_bbox_size_percent <= 100.0: - raise ValueError( - f"max_bbox_size_percent must be between 0.0 and 100.0, got {max_bbox_size_percent}" - ) - - # Store settings - self.color_weight = color_weight - self.enable_statistical_filtering = enable_statistical_filtering - self.statistical_neighbors = statistical_neighbors - self.statistical_std_ratio = statistical_std_ratio - self.enable_radius_filtering = enable_radius_filtering - self.radius_filtering_radius = radius_filtering_radius - self.radius_filtering_min_neighbors = radius_filtering_min_neighbors - self.enable_subsampling = enable_subsampling - self.voxel_size = voxel_size - self.max_num_objects = max_num_objects - self.min_points_for_cuboid = min_points_for_cuboid - self.cuboid_method = cuboid_method - self.max_bbox_size_percent = max_bbox_size_percent - - # Load camera matrices - self.color_camera_matrix = load_camera_matrix_from_yaml(color_intrinsics) - self.depth_camera_matrix = load_camera_matrix_from_yaml(depth_intrinsics) - - # Store the full point cloud - self.full_pcd = None - - def generate_color_from_id(self, object_id: int) -> np.ndarray: # type: ignore[type-arg] - """Generate a consistent color for a given object ID.""" - np.random.seed(object_id) - color = np.random.randint(0, 255, 3, dtype=np.uint8) - np.random.seed(None) - return color - - def _validate_inputs( # type: ignore[no-untyped-def] - self, - color_img: np.ndarray, # type: ignore[type-arg] - depth_img: np.ndarray, # type: ignore[type-arg] - objects: list[ObjectData], - ): - """Validate input parameters.""" - if color_img.shape[:2] != depth_img.shape: - raise ValueError("Color and depth image dimensions don't match") - - def _prepare_masks(self, masks: list[np.ndarray], target_shape: tuple) -> list[np.ndarray]: # type: ignore[type-arg] - """Prepare and validate masks to match target shape.""" - processed_masks = [] - for mask in masks: - # Convert mask to numpy if it's a tensor - if hasattr(mask, "cpu"): - mask = mask.cpu().numpy() - - mask = mask.astype(bool) - - # Handle shape mismatches - if mask.shape != target_shape: - if len(mask.shape) > 2: - mask = mask[:, :, 0] - - if mask.shape != target_shape: - mask = cv2.resize( - mask.astype(np.uint8), - (target_shape[1], target_shape[0]), - interpolation=cv2.INTER_NEAREST, - ).astype(bool) - - processed_masks.append(mask) - - return processed_masks - - def _apply_color_mask( - self, - pcd: o3d.geometry.PointCloud, - rgb_color: np.ndarray, # type: ignore[type-arg] - ) -> o3d.geometry.PointCloud: - """Apply weighted color mask to point cloud.""" - if len(np.asarray(pcd.colors)) > 0: - original_colors = np.asarray(pcd.colors) - generated_color = rgb_color.astype(np.float32) / 255.0 - colored_mask = ( - 1.0 - self.color_weight - ) * original_colors + self.color_weight * generated_color - colored_mask = np.clip(colored_mask, 0.0, 1.0) - pcd.colors = o3d.utility.Vector3dVector(colored_mask) - return pcd - - def _apply_filtering(self, pcd: o3d.geometry.PointCloud) -> o3d.geometry.PointCloud: - """Apply optional filtering to point cloud based on enabled flags.""" - current_pcd = pcd - - # Apply statistical filtering if enabled - if self.enable_statistical_filtering: - current_pcd, _ = current_pcd.remove_statistical_outlier( - nb_neighbors=self.statistical_neighbors, std_ratio=self.statistical_std_ratio - ) - - # Apply radius filtering if enabled - if self.enable_radius_filtering: - current_pcd, _ = current_pcd.remove_radius_outlier( - nb_points=self.radius_filtering_min_neighbors, radius=self.radius_filtering_radius - ) - - return current_pcd - - def _apply_subsampling(self, pcd: o3d.geometry.PointCloud) -> o3d.geometry.PointCloud: - """Apply subsampling to limit point cloud size using Open3D's voxel downsampling.""" - if self.enable_subsampling: - return pcd.voxel_down_sample(self.voxel_size) - return pcd - - def _extract_masks_from_objects(self, objects: list[ObjectData]) -> list[np.ndarray]: # type: ignore[type-arg] - """Extract segmentation masks from ObjectData objects.""" - return [obj["segmentation_mask"] for obj in objects] - - def get_full_point_cloud(self) -> o3d.geometry.PointCloud: - """Get the full point cloud.""" - return self._apply_subsampling(self.full_pcd) - - def process_images( - self, - color_img: np.ndarray, # type: ignore[type-arg] - depth_img: np.ndarray, # type: ignore[type-arg] - objects: list[ObjectData], - ) -> list[ObjectData]: - """ - Process color and depth images with object detection results to create filtered point clouds. - - Args: - color_img: RGB image as numpy array (H, W, 3) - depth_img: Depth image as numpy array (H, W) in meters - objects: List of ObjectData from object detection stream - - Returns: - List of updated ObjectData with pointcloud and 3D information. Each ObjectData - dictionary is enhanced with the following new fields: - - **3D Spatial Information** (added when sufficient points for cuboid fitting): - - "position": Vector(x, y, z) - 3D center position in world coordinates (meters) - - "rotation": Vector(roll, pitch, yaw) - 3D orientation as Euler angles (radians) - - "size": {"width": float, "height": float, "depth": float} - 3D bounding box dimensions (meters) - - **Point Cloud Data**: - - "point_cloud": o3d.geometry.PointCloud - Filtered Open3D point cloud with colors - - "color": np.ndarray - Consistent RGB color [R,G,B] (0-255) generated from object_id - - **Grasp Generation Arrays** (Dimensional grasp format): - - "point_cloud_numpy": np.ndarray - Nx3 XYZ coordinates as float32 (meters) - - "colors_numpy": np.ndarray - Nx3 RGB colors as float32 (0.0-1.0 range) - - Raises: - ValueError: If inputs are invalid - RuntimeError: If processing fails - """ - # Validate inputs - self._validate_inputs(color_img, depth_img, objects) - - if not objects: - return [] - - # Filter to top N objects by confidence - if len(objects) > self.max_num_objects: - # Sort objects by confidence (highest first), handle None confidences - sorted_objects = sorted( - objects, - key=lambda obj: obj.get("confidence", 0.0) - if obj.get("confidence") is not None - else 0.0, - reverse=True, - ) - objects = sorted_objects[: self.max_num_objects] - - # Filter out objects with bboxes too large - image_area = color_img.shape[0] * color_img.shape[1] - max_bbox_area = image_area * (self.max_bbox_size_percent / 100.0) - - filtered_objects = [] - for obj in objects: - if "bbox" in obj and obj["bbox"] is not None: - bbox = obj["bbox"] - # Calculate bbox area (assuming bbox format [x1, y1, x2, y2]) - bbox_area = (bbox[2] - bbox[0]) * (bbox[3] - bbox[1]) - if bbox_area <= max_bbox_area: - filtered_objects.append(obj) - else: - filtered_objects.append(obj) - - objects = filtered_objects - - # Extract masks from ObjectData - masks = self._extract_masks_from_objects(objects) - - # Prepare masks - processed_masks = self._prepare_masks(masks, depth_img.shape) - - # Create point clouds efficiently - self.full_pcd, masked_pcds = create_point_cloud_and_extract_masks( - color_img, - depth_img, - processed_masks, - self.depth_camera_matrix, # type: ignore[arg-type] - depth_scale=1.0, - ) - - # Process each object and update ObjectData - updated_objects = [] - - for i, (obj, _mask, pcd) in enumerate( - zip(objects, processed_masks, masked_pcds, strict=False) - ): - # Skip empty point clouds - if len(np.asarray(pcd.points)) == 0: - continue - - # Create a copy of the object data to avoid modifying the original - updated_obj = obj.copy() - - # Generate consistent color - object_id = obj.get("object_id", i) - rgb_color = self.generate_color_from_id(object_id) - - # Apply color mask - pcd = self._apply_color_mask(pcd, rgb_color) - - # Apply subsampling to control point cloud size - pcd = self._apply_subsampling(pcd) - - # Apply filtering (optional based on flags) - pcd_filtered = self._apply_filtering(pcd) - - # Fit cuboid and extract 3D information - points = np.asarray(pcd_filtered.points) - if len(points) >= self.min_points_for_cuboid: - cuboid_params = fit_cuboid(points, method=self.cuboid_method) - if cuboid_params is not None: - # Update position, rotation, and size from cuboid - center = cuboid_params["center"] - dimensions = cuboid_params["dimensions"] - rotation_matrix = cuboid_params["rotation"] - - # Convert rotation matrix to euler angles (roll, pitch, yaw) - sy = np.sqrt( - rotation_matrix[0, 0] * rotation_matrix[0, 0] - + rotation_matrix[1, 0] * rotation_matrix[1, 0] - ) - singular = sy < 1e-6 - - if not singular: - roll = np.arctan2(rotation_matrix[2, 1], rotation_matrix[2, 2]) - pitch = np.arctan2(-rotation_matrix[2, 0], sy) - yaw = np.arctan2(rotation_matrix[1, 0], rotation_matrix[0, 0]) - else: - roll = np.arctan2(-rotation_matrix[1, 2], rotation_matrix[1, 1]) - pitch = np.arctan2(-rotation_matrix[2, 0], sy) - yaw = 0 - - # Update position, rotation, and size from cuboid - updated_obj["position"] = Vector(center[0], center[1], center[2]) - updated_obj["rotation"] = Vector(roll, pitch, yaw) - updated_obj["size"] = { - "width": float(dimensions[0]), - "height": float(dimensions[1]), - "depth": float(dimensions[2]), - } - - # Add point cloud data to ObjectData - updated_obj["point_cloud"] = pcd_filtered - updated_obj["color"] = rgb_color - - # Extract numpy arrays for grasp generation - points_array = np.asarray(pcd_filtered.points).astype(np.float32) # Nx3 XYZ coordinates - if pcd_filtered.has_colors(): - colors_array = np.asarray(pcd_filtered.colors).astype( - np.float32 - ) # Nx3 RGB (0-1 range) - else: - # If no colors, create array of zeros - colors_array = np.zeros((len(points_array), 3), dtype=np.float32) - - updated_obj["point_cloud_numpy"] = points_array - updated_obj["colors_numpy"] = colors_array # type: ignore[typeddict-unknown-key] - - updated_objects.append(updated_obj) - - return updated_objects - - def cleanup(self) -> None: - """Clean up resources.""" - if torch.cuda.is_available(): - torch.cuda.empty_cache() diff --git a/dimos/perception/pointcloud/test_pointcloud_filtering.py b/dimos/perception/pointcloud/test_pointcloud_filtering.py deleted file mode 100644 index 4ac7e5cb2d..0000000000 --- a/dimos/perception/pointcloud/test_pointcloud_filtering.py +++ /dev/null @@ -1,263 +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 os -from typing import TYPE_CHECKING - -import cv2 -import numpy as np -import open3d as o3d -import pytest - -from dimos.perception.pointcloud.pointcloud_filtering import PointcloudFiltering -from dimos.perception.pointcloud.utils import load_camera_matrix_from_yaml - -if TYPE_CHECKING: - from dimos.types.manipulation import ObjectData - - -class TestPointcloudFiltering: - def test_pointcloud_filtering_initialization(self) -> None: - """Test PointcloudFiltering initializes correctly with default parameters.""" - try: - filtering = PointcloudFiltering() - assert filtering is not None - assert filtering.color_weight == 0.3 - assert filtering.enable_statistical_filtering - assert filtering.enable_radius_filtering - assert filtering.enable_subsampling - except Exception as e: - pytest.skip(f"Skipping test due to initialization error: {e}") - - def test_pointcloud_filtering_with_custom_params(self) -> None: - """Test PointcloudFiltering with custom parameters.""" - try: - filtering = PointcloudFiltering( - color_weight=0.5, - enable_statistical_filtering=False, - enable_radius_filtering=False, - voxel_size=0.01, - max_num_objects=5, - ) - assert filtering.color_weight == 0.5 - assert not filtering.enable_statistical_filtering - assert not filtering.enable_radius_filtering - assert filtering.voxel_size == 0.01 - assert filtering.max_num_objects == 5 - except Exception as e: - pytest.skip(f"Skipping test due to initialization error: {e}") - - def test_pointcloud_filtering_process_images(self) -> None: - """Test PointcloudFiltering can process RGB-D images and return filtered point clouds.""" - try: - # Import data inside method to avoid pytest fixture confusion - from dimos.utils.data import get_data - - # Load test RGB-D data - data_dir = get_data("rgbd_frames") - - # Load first frame - color_path = os.path.join(data_dir, "color", "00000.png") - depth_path = os.path.join(data_dir, "depth", "00000.png") - intrinsics_path = os.path.join(data_dir, "color_camera_info.yaml") - - assert os.path.exists(color_path), f"Color image not found: {color_path}" - assert os.path.exists(depth_path), f"Depth image not found: {depth_path}" - assert os.path.exists(intrinsics_path), f"Intrinsics file not found: {intrinsics_path}" - - # Load images - color_img = cv2.imread(color_path) - color_img = cv2.cvtColor(color_img, cv2.COLOR_BGR2RGB) - - depth_img = cv2.imread(depth_path, cv2.IMREAD_ANYDEPTH) - if depth_img.dtype == np.uint16: - depth_img = depth_img.astype(np.float32) / 1000.0 - - # Load camera intrinsics - camera_matrix = load_camera_matrix_from_yaml(intrinsics_path) - if camera_matrix is None: - pytest.skip("Failed to load camera intrinsics") - - # Create mock objects with segmentation masks - height, width = color_img.shape[:2] - - # Create simple rectangular masks for testing - mock_objects = [] - - # Object 1: Top-left quadrant - mask1 = np.zeros((height, width), dtype=bool) - mask1[height // 4 : height // 2, width // 4 : width // 2] = True - - obj1: ObjectData = { - "object_id": 1, - "confidence": 0.9, - "bbox": [width // 4, height // 4, width // 2, height // 2], - "segmentation_mask": mask1, - "name": "test_object_1", - } - mock_objects.append(obj1) - - # Object 2: Bottom-right quadrant - mask2 = np.zeros((height, width), dtype=bool) - mask2[height // 2 : 3 * height // 4, width // 2 : 3 * width // 4] = True - - obj2: ObjectData = { - "object_id": 2, - "confidence": 0.8, - "bbox": [width // 2, height // 2, 3 * width // 4, 3 * height // 4], - "segmentation_mask": mask2, - "name": "test_object_2", - } - mock_objects.append(obj2) - - # Initialize filtering with intrinsics - filtering = PointcloudFiltering( - color_intrinsics=camera_matrix, - depth_intrinsics=camera_matrix, - enable_statistical_filtering=False, # Disable for faster testing - enable_radius_filtering=False, # Disable for faster testing - voxel_size=0.01, # Larger voxel for faster processing - ) - - # Process images - results = filtering.process_images(color_img, depth_img, mock_objects) - - print( - f"Processing results - Input objects: {len(mock_objects)}, Output objects: {len(results)}" - ) - - # Verify results - assert isinstance(results, list), "Results should be a list" - assert len(results) <= len(mock_objects), "Should not return more objects than input" - - # Check each result object - for i, result in enumerate(results): - print(f"Object {i}: {result.get('name', 'unknown')}") - - # Verify required fields exist - assert "point_cloud" in result, "Result should contain point_cloud" - assert "color" in result, "Result should contain color" - assert "point_cloud_numpy" in result, "Result should contain point_cloud_numpy" - - # Verify point cloud is valid Open3D object - pcd = result["point_cloud"] - assert isinstance(pcd, o3d.geometry.PointCloud), ( - "point_cloud should be Open3D PointCloud" - ) - - # Verify numpy arrays - points_array = result["point_cloud_numpy"] - assert isinstance(points_array, np.ndarray), ( - "point_cloud_numpy should be numpy array" - ) - assert points_array.shape[1] == 3, "Point array should have 3 columns (x,y,z)" - assert points_array.dtype == np.float32, "Point array should be float32" - - # Verify color - color = result["color"] - assert isinstance(color, np.ndarray), "Color should be numpy array" - assert color.shape == (3,), "Color should be RGB triplet" - assert color.dtype == np.uint8, "Color should be uint8" - - # Check if 3D information was added (when enough points for cuboid fitting) - points = np.asarray(pcd.points) - if len(points) >= filtering.min_points_for_cuboid: - if "position" in result: - assert "rotation" in result, "Should have rotation if position exists" - assert "size" in result, "Should have size if position exists" - - # Verify position format - from dimos.types.vector import Vector - - position = result["position"] - assert isinstance(position, Vector), "Position should be Vector" - - # Verify size format - size = result["size"] - assert isinstance(size, dict), "Size should be dict" - assert "width" in size and "height" in size and "depth" in size - - print(f" - Points: {len(points)}") - print(f" - Color: {color}") - if "position" in result: - print(f" - Position: {result['position']}") - print(f" - Size: {result['size']}") - - # Test full point cloud access - full_pcd = filtering.get_full_point_cloud() - if full_pcd is not None: - assert isinstance(full_pcd, o3d.geometry.PointCloud), ( - "Full point cloud should be Open3D PointCloud" - ) - full_points = np.asarray(full_pcd.points) - print(f"Full point cloud points: {len(full_points)}") - - print("All pointcloud filtering tests passed!") - - except Exception as e: - pytest.skip(f"Skipping test due to error: {e}") - - def test_pointcloud_filtering_empty_objects(self) -> None: - """Test PointcloudFiltering with empty object list.""" - try: - from dimos.utils.data import get_data - - # Load test data - data_dir = get_data("rgbd_frames") - color_path = os.path.join(data_dir, "color", "00000.png") - depth_path = os.path.join(data_dir, "depth", "00000.png") - - if not (os.path.exists(color_path) and os.path.exists(depth_path)): - pytest.skip("Test images not found") - - color_img = cv2.imread(color_path) - color_img = cv2.cvtColor(color_img, cv2.COLOR_BGR2RGB) - depth_img = cv2.imread(depth_path, cv2.IMREAD_ANYDEPTH) - if depth_img.dtype == np.uint16: - depth_img = depth_img.astype(np.float32) / 1000.0 - - filtering = PointcloudFiltering() - - # Test with empty object list - results = filtering.process_images(color_img, depth_img, []) - - assert isinstance(results, list), "Results should be a list" - assert len(results) == 0, "Should return empty list for empty input" - - except Exception as e: - pytest.skip(f"Skipping test due to error: {e}") - - def test_color_generation_consistency(self) -> None: - """Test that color generation is consistent for the same object ID.""" - try: - filtering = PointcloudFiltering() - - # Test color generation consistency - color1 = filtering.generate_color_from_id(42) - color2 = filtering.generate_color_from_id(42) - color3 = filtering.generate_color_from_id(43) - - assert np.array_equal(color1, color2), "Same ID should generate same color" - assert not np.array_equal(color1, color3), ( - "Different IDs should generate different colors" - ) - assert color1.shape == (3,), "Color should be RGB triplet" - assert color1.dtype == np.uint8, "Color should be uint8" - - except Exception as e: - pytest.skip(f"Skipping test due to error: {e}") - - -if __name__ == "__main__": - pytest.main(["-v", __file__]) diff --git a/dimos/perception/pointcloud/utils.py b/dimos/perception/pointcloud/utils.py deleted file mode 100644 index b2bb561000..0000000000 --- a/dimos/perception/pointcloud/utils.py +++ /dev/null @@ -1,1113 +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. - -""" -Point cloud utilities for RGBD data processing. - -This module provides efficient utilities for creating and manipulating point clouds -from RGBD images using Open3D. -""" - -import os -from typing import Any - -import cv2 -import numpy as np -import open3d as o3d # type: ignore[import-untyped] -from scipy.spatial import cKDTree # type: ignore[import-untyped] -import yaml # type: ignore[import-untyped] - -from dimos.perception.common.utils import project_3d_points_to_2d - - -def load_camera_matrix_from_yaml( - camera_info: str | list[float] | np.ndarray | dict | None, # type: ignore[type-arg] -) -> np.ndarray | None: # type: ignore[type-arg] - """ - Load camera intrinsic matrix from various input formats. - - Args: - camera_info: Can be: - - Path to YAML file containing camera parameters - - List of [fx, fy, cx, cy] - - 3x3 numpy array (returned as-is) - - Dict with camera parameters - - None (returns None) - - Returns: - 3x3 camera intrinsic matrix or None if input is None - - Raises: - ValueError: If camera_info format is invalid or file cannot be read - FileNotFoundError: If YAML file path doesn't exist - """ - if camera_info is None: - return None - - # Handle case where camera_info is already a matrix - if isinstance(camera_info, np.ndarray) and camera_info.shape == (3, 3): - return camera_info.astype(np.float32) - - # Handle case where camera_info is [fx, fy, cx, cy] format - if isinstance(camera_info, list) and len(camera_info) == 4: - fx, fy, cx, cy = camera_info - return np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]], dtype=np.float32) - - # Handle case where camera_info is a dict - if isinstance(camera_info, dict): - return _extract_matrix_from_dict(camera_info) - - # Handle case where camera_info is a path to a YAML file - if isinstance(camera_info, str): - if not os.path.isfile(camera_info): - raise FileNotFoundError(f"Camera info file not found: {camera_info}") - - try: - with open(camera_info) as f: - data = yaml.safe_load(f) - return _extract_matrix_from_dict(data) - except Exception as e: - raise ValueError(f"Failed to read camera info from {camera_info}: {e}") - - raise ValueError( - f"Invalid camera_info format. Expected str, list, dict, or numpy array, got {type(camera_info)}" - ) - - -def _extract_matrix_from_dict(data: dict) -> np.ndarray: # type: ignore[type-arg] - """Extract camera matrix from dictionary with various formats.""" - # ROS format with 'K' field (most common) - if "K" in data: - k_data = data["K"] - if len(k_data) == 9: - return np.array(k_data, dtype=np.float32).reshape(3, 3) - - # Standard format with 'camera_matrix' - if "camera_matrix" in data: - if "data" in data["camera_matrix"]: - matrix_data = data["camera_matrix"]["data"] - if len(matrix_data) == 9: - return np.array(matrix_data, dtype=np.float32).reshape(3, 3) - - # Explicit intrinsics format - if all(k in data for k in ["fx", "fy", "cx", "cy"]): - fx, fy = float(data["fx"]), float(data["fy"]) - cx, cy = float(data["cx"]), float(data["cy"]) - return np.array([[fx, 0, cx], [0, fy, cy], [0, 0, 1]], dtype=np.float32) - - # Error case - provide helpful debug info - available_keys = list(data.keys()) - if "K" in data: - k_info = f"K field length: {len(data['K']) if hasattr(data['K'], '__len__') else 'unknown'}" - else: - k_info = "K field not found" - - raise ValueError( - f"Cannot extract camera matrix from data. " - f"Available keys: {available_keys}. {k_info}. " - f"Expected formats: 'K' (9 elements), 'camera_matrix.data' (9 elements), " - f"or individual 'fx', 'fy', 'cx', 'cy' fields." - ) - - -def create_o3d_point_cloud_from_rgbd( - color_img: np.ndarray, # type: ignore[type-arg] - depth_img: np.ndarray, # type: ignore[type-arg] - intrinsic: np.ndarray, # type: ignore[type-arg] - depth_scale: float = 1.0, - depth_trunc: float = 3.0, -) -> o3d.geometry.PointCloud: - """ - Create an Open3D point cloud from RGB and depth images. - - Args: - color_img: RGB image as numpy array (H, W, 3) - depth_img: Depth image as numpy array (H, W) - intrinsic: Camera intrinsic matrix (3x3 numpy array) - depth_scale: Scale factor to convert depth to meters - depth_trunc: Maximum depth in meters - - Returns: - Open3D point cloud object - - Raises: - ValueError: If input dimensions are invalid - """ - # Validate inputs - if len(color_img.shape) != 3 or color_img.shape[2] != 3: - raise ValueError(f"color_img must be (H, W, 3), got {color_img.shape}") - if len(depth_img.shape) != 2: - raise ValueError(f"depth_img must be (H, W), got {depth_img.shape}") - if color_img.shape[:2] != depth_img.shape: - raise ValueError( - f"Color and depth image dimensions don't match: {color_img.shape[:2]} vs {depth_img.shape}" - ) - if intrinsic.shape != (3, 3): - raise ValueError(f"intrinsic must be (3, 3), got {intrinsic.shape}") - - # Convert to Open3D format - color_o3d = o3d.geometry.Image(color_img.astype(np.uint8)) - - # Filter out inf and nan values from depth image - depth_filtered = depth_img.copy() - - # Create mask for valid depth values (finite, positive, non-zero) - valid_mask = np.isfinite(depth_filtered) & (depth_filtered > 0) - - # Set invalid values to 0 (which Open3D treats as no depth) - depth_filtered[~valid_mask] = 0.0 - - depth_o3d = o3d.geometry.Image(depth_filtered.astype(np.float32)) - - # Create Open3D intrinsic object - height, width = color_img.shape[:2] - fx, fy = intrinsic[0, 0], intrinsic[1, 1] - cx, cy = intrinsic[0, 2], intrinsic[1, 2] - intrinsic_o3d = o3d.camera.PinholeCameraIntrinsic( - width, - height, - fx, - fy, # fx, fy - cx, - cy, # cx, cy - ) - - # Create RGBD image - rgbd = o3d.geometry.RGBDImage.create_from_color_and_depth( - color_o3d, - depth_o3d, - depth_scale=depth_scale, - depth_trunc=depth_trunc, - convert_rgb_to_intensity=False, - ) - - # Create point cloud - pcd = o3d.geometry.PointCloud.create_from_rgbd_image(rgbd, intrinsic_o3d) - - return pcd - - -def create_point_cloud_and_extract_masks( - color_img: np.ndarray, # type: ignore[type-arg] - depth_img: np.ndarray, # type: ignore[type-arg] - masks: list[np.ndarray], # type: ignore[type-arg] - intrinsic: np.ndarray, # type: ignore[type-arg] - depth_scale: float = 1.0, - depth_trunc: float = 3.0, -) -> tuple[o3d.geometry.PointCloud, list[o3d.geometry.PointCloud]]: - """ - Efficiently create a point cloud once and extract multiple masked regions. - - Args: - color_img: RGB image (H, W, 3) - depth_img: Depth image (H, W) - masks: List of boolean masks, each of shape (H, W) - intrinsic: Camera intrinsic matrix (3x3 numpy array) - depth_scale: Scale factor to convert depth to meters - depth_trunc: Maximum depth in meters - - Returns: - Tuple of (full_point_cloud, list_of_masked_point_clouds) - """ - if not masks: - return o3d.geometry.PointCloud(), [] - - # Create the full point cloud - full_pcd = create_o3d_point_cloud_from_rgbd( - color_img, depth_img, intrinsic, depth_scale, depth_trunc - ) - - if len(np.asarray(full_pcd.points)) == 0: - return full_pcd, [o3d.geometry.PointCloud() for _ in masks] - - # Create pixel-to-point mapping - valid_depth_mask = np.isfinite(depth_img) & (depth_img > 0) & (depth_img <= depth_trunc) - - valid_depth = valid_depth_mask.flatten() - if not np.any(valid_depth): - return full_pcd, [o3d.geometry.PointCloud() for _ in masks] - - pixel_to_point = np.full(len(valid_depth), -1, dtype=np.int32) - pixel_to_point[valid_depth] = np.arange(np.sum(valid_depth)) - - # Extract point clouds for each mask - masked_pcds = [] - max_points = len(np.asarray(full_pcd.points)) - - for mask in masks: - if mask.shape != depth_img.shape: - masked_pcds.append(o3d.geometry.PointCloud()) - continue - - mask_flat = mask.flatten() - valid_mask_indices = mask_flat & valid_depth - point_indices = pixel_to_point[valid_mask_indices] - valid_point_indices = point_indices[point_indices >= 0] - - if len(valid_point_indices) > 0: - valid_point_indices = np.clip(valid_point_indices, 0, max_points - 1) - valid_point_indices = np.unique(valid_point_indices) - masked_pcd = full_pcd.select_by_index(valid_point_indices.tolist()) - else: - masked_pcd = o3d.geometry.PointCloud() - - masked_pcds.append(masked_pcd) - - return full_pcd, masked_pcds - - -def filter_point_cloud_statistical( - pcd: o3d.geometry.PointCloud, nb_neighbors: int = 20, std_ratio: float = 2.0 -) -> tuple[o3d.geometry.PointCloud, np.ndarray]: # type: ignore[type-arg] - """ - Apply statistical outlier filtering to point cloud. - - Args: - pcd: Input point cloud - nb_neighbors: Number of neighbors to analyze for each point - std_ratio: Threshold level based on standard deviation - - Returns: - Tuple of (filtered_point_cloud, outlier_indices) - """ - if len(np.asarray(pcd.points)) == 0: - return pcd, np.array([]) - - return pcd.remove_statistical_outlier(nb_neighbors=nb_neighbors, std_ratio=std_ratio) # type: ignore[no-any-return] - - -def filter_point_cloud_radius( - pcd: o3d.geometry.PointCloud, nb_points: int = 16, radius: float = 0.05 -) -> tuple[o3d.geometry.PointCloud, np.ndarray]: # type: ignore[type-arg] - """ - Apply radius-based outlier filtering to point cloud. - - Args: - pcd: Input point cloud - nb_points: Minimum number of points within radius - radius: Search radius in meters - - Returns: - Tuple of (filtered_point_cloud, outlier_indices) - """ - if len(np.asarray(pcd.points)) == 0: - return pcd, np.array([]) - - return pcd.remove_radius_outlier(nb_points=nb_points, radius=radius) # type: ignore[no-any-return] - - -def overlay_point_clouds_on_image( - base_image: np.ndarray, # type: ignore[type-arg] - point_clouds: list[o3d.geometry.PointCloud], - camera_intrinsics: list[float] | np.ndarray, # type: ignore[type-arg] - colors: list[tuple[int, int, int]], - point_size: int = 2, - alpha: float = 0.7, -) -> np.ndarray: # type: ignore[type-arg] - """ - Overlay multiple colored point clouds onto an image. - - Args: - base_image: Base image to overlay onto (H, W, 3) - assumed to be RGB - point_clouds: List of Open3D point cloud objects - camera_intrinsics: Camera parameters as [fx, fy, cx, cy] list or 3x3 matrix - colors: List of RGB color tuples for each point cloud. If None, generates distinct colors. - point_size: Size of points to draw (in pixels) - alpha: Blending factor for overlay (0.0 = fully transparent, 1.0 = fully opaque) - - Returns: - Image with overlaid point clouds (H, W, 3) - """ - if len(point_clouds) == 0: - return base_image.copy() - - # Create overlay image - overlay = base_image.copy() - height, width = base_image.shape[:2] - - # Process each point cloud - for i, pcd in enumerate(point_clouds): - if pcd is None: - continue - - points_3d = np.asarray(pcd.points) - if len(points_3d) == 0: - continue - - # Project 3D points to 2D - points_2d = project_3d_points_to_2d(points_3d, camera_intrinsics) - - if len(points_2d) == 0: - continue - - # Filter points within image bounds - valid_mask = ( - (points_2d[:, 0] >= 0) - & (points_2d[:, 0] < width) - & (points_2d[:, 1] >= 0) - & (points_2d[:, 1] < height) - ) - valid_points_2d = points_2d[valid_mask] - - if len(valid_points_2d) == 0: - continue - - # Get color for this point cloud - color = colors[i % len(colors)] - - # Ensure color is a tuple of integers for OpenCV - if isinstance(color, list | tuple | np.ndarray): - color = tuple(int(c) for c in color[:3]) # type: ignore[assignment] - else: - color = (255, 255, 255) - - # Draw points on overlay - for point in valid_points_2d: - u, v = point - # Draw a small filled circle for each point - cv2.circle(overlay, (u, v), point_size, color, -1) - - # Blend overlay with base image - result = cv2.addWeighted(base_image, 1 - alpha, overlay, alpha, 0) - - return result - - -def create_point_cloud_overlay_visualization( - base_image: np.ndarray, # type: ignore[type-arg] - objects: list[dict], # type: ignore[type-arg] - intrinsics: np.ndarray, # type: ignore[type-arg] -) -> np.ndarray: # type: ignore[type-arg] - """ - Create a visualization showing object point clouds and bounding boxes overlaid on a base image. - - Args: - base_image: Base image to overlay onto (H, W, 3) - objects: List of object dictionaries containing 'point_cloud', 'color', 'position', 'rotation', 'size' keys - intrinsics: Camera intrinsics as [fx, fy, cx, cy] or 3x3 matrix - - Returns: - Visualization image with overlaid point clouds and bounding boxes (H, W, 3) - """ - # Extract point clouds and colors from objects - point_clouds = [] - colors = [] - for obj in objects: - if "point_cloud" in obj and obj["point_cloud"] is not None: - point_clouds.append(obj["point_cloud"]) - - # Convert color to tuple - color = obj["color"] - if isinstance(color, np.ndarray): - color = tuple(int(c) for c in color) - elif isinstance(color, list | tuple): - color = tuple(int(c) for c in color[:3]) - colors.append(color) - - # Create visualization - if point_clouds: - result = overlay_point_clouds_on_image( - base_image=base_image, - point_clouds=point_clouds, - camera_intrinsics=intrinsics, - colors=colors, - point_size=3, - alpha=0.8, - ) - else: - result = base_image.copy() - - # Draw 3D bounding boxes - height_img, width_img = result.shape[:2] - for i, obj in enumerate(objects): - if all(key in obj and obj[key] is not None for key in ["position", "rotation", "size"]): - try: - # Create and project 3D bounding box - corners_3d = create_3d_bounding_box_corners( - obj["position"], obj["rotation"], obj["size"] - ) - corners_2d = project_3d_points_to_2d(corners_3d, intrinsics) - - # Check if any corners are visible - valid_mask = ( - (corners_2d[:, 0] >= 0) - & (corners_2d[:, 0] < width_img) - & (corners_2d[:, 1] >= 0) - & (corners_2d[:, 1] < height_img) - ) - - if np.any(valid_mask): - # Get color - bbox_color = colors[i] if i < len(colors) else (255, 255, 255) - draw_3d_bounding_box_on_image(result, corners_2d, bbox_color, thickness=2) - except: - continue - - return result - - -def create_3d_bounding_box_corners(position, rotation, size: int): # type: ignore[no-untyped-def] - """ - Create 8 corners of a 3D bounding box from position, rotation, and size. - - Args: - position: Vector or dict with x, y, z coordinates - rotation: Vector or dict with roll, pitch, yaw angles - size: Dict with width, height, depth - - Returns: - 8x3 numpy array of corner coordinates - """ - # Convert position to numpy array - if hasattr(position, "x"): # Vector object - center = np.array([position.x, position.y, position.z]) - else: # Dictionary - center = np.array([position["x"], position["y"], position["z"]]) - - # Convert rotation (euler angles) to rotation matrix - if hasattr(rotation, "x"): # Vector object (roll, pitch, yaw) - roll, pitch, yaw = rotation.x, rotation.y, rotation.z - else: # Dictionary - roll, pitch, yaw = rotation["roll"], rotation["pitch"], rotation["yaw"] - - # Create rotation matrix from euler angles (ZYX order) - cos_r, sin_r = np.cos(roll), np.sin(roll) - cos_p, sin_p = np.cos(pitch), np.sin(pitch) - cos_y, sin_y = np.cos(yaw), np.sin(yaw) - - # Rotation matrix for ZYX euler angles - R = np.array( - [ - [ - cos_y * cos_p, - cos_y * sin_p * sin_r - sin_y * cos_r, - cos_y * sin_p * cos_r + sin_y * sin_r, - ], - [ - sin_y * cos_p, - sin_y * sin_p * sin_r + cos_y * cos_r, - sin_y * sin_p * cos_r - cos_y * sin_r, - ], - [-sin_p, cos_p * sin_r, cos_p * cos_r], - ] - ) - - # Get dimensions - width = size.get("width", 0.1) # type: ignore[attr-defined] - height = size.get("height", 0.1) # type: ignore[attr-defined] - depth = size.get("depth", 0.1) # type: ignore[attr-defined] - - # Create 8 corners of the bounding box (before rotation) - corners = np.array( - [ - [-width / 2, -height / 2, -depth / 2], # 0 - [width / 2, -height / 2, -depth / 2], # 1 - [width / 2, height / 2, -depth / 2], # 2 - [-width / 2, height / 2, -depth / 2], # 3 - [-width / 2, -height / 2, depth / 2], # 4 - [width / 2, -height / 2, depth / 2], # 5 - [width / 2, height / 2, depth / 2], # 6 - [-width / 2, height / 2, depth / 2], # 7 - ] - ) - - # Apply rotation and translation - rotated_corners = corners @ R.T + center - - return rotated_corners - - -def draw_3d_bounding_box_on_image(image, corners_2d, color, thickness: int = 2) -> None: # type: ignore[no-untyped-def] - """ - Draw a 3D bounding box on an image using projected 2D corners. - - Args: - image: Image to draw on - corners_2d: 8x2 array of 2D corner coordinates - color: RGB color tuple - thickness: Line thickness - """ - # Define the 12 edges of a cube (connecting corner indices) - edges = [ - (0, 1), - (1, 2), - (2, 3), - (3, 0), # Bottom face - (4, 5), - (5, 6), - (6, 7), - (7, 4), # Top face - (0, 4), - (1, 5), - (2, 6), - (3, 7), # Vertical edges - ] - - # Draw each edge - for start_idx, end_idx in edges: - start_point = tuple(corners_2d[start_idx].astype(int)) - end_point = tuple(corners_2d[end_idx].astype(int)) - cv2.line(image, start_point, end_point, color, thickness) - - -def extract_and_cluster_misc_points( - full_pcd: o3d.geometry.PointCloud, - all_objects: list[dict], # type: ignore[type-arg] - eps: float = 0.03, - min_points: int = 100, - enable_filtering: bool = True, - voxel_size: float = 0.02, -) -> tuple[list[o3d.geometry.PointCloud], o3d.geometry.VoxelGrid]: - """ - Extract miscellaneous/background points and cluster them using DBSCAN. - - Args: - full_pcd: Complete scene point cloud - all_objects: List of objects with point clouds to subtract - eps: DBSCAN epsilon parameter (max distance between points in cluster) - min_points: DBSCAN min_samples parameter (min points to form cluster) - enable_filtering: Whether to apply statistical and radius filtering - voxel_size: Size of voxels for voxel grid generation - - Returns: - Tuple of (clustered_point_clouds, voxel_grid) - """ - if full_pcd is None or len(np.asarray(full_pcd.points)) == 0: - return [], o3d.geometry.VoxelGrid() - - if not all_objects: - # If no objects detected, cluster the full point cloud - clusters = _cluster_point_cloud_dbscan(full_pcd, eps, min_points) - voxel_grid = _create_voxel_grid_from_clusters(clusters, voxel_size) - return clusters, voxel_grid - - try: - # Start with a copy of the full point cloud - misc_pcd = o3d.geometry.PointCloud(full_pcd) - - # Remove object points by combining all object point clouds - all_object_points = [] - for obj in all_objects: - if "point_cloud" in obj and obj["point_cloud"] is not None: - obj_points = np.asarray(obj["point_cloud"].points) - if len(obj_points) > 0: - all_object_points.append(obj_points) - - if not all_object_points: - # No object points to remove, cluster full point cloud - clusters = _cluster_point_cloud_dbscan(misc_pcd, eps, min_points) - voxel_grid = _create_voxel_grid_from_clusters(clusters, voxel_size) - return clusters, voxel_grid - - # Combine all object points - combined_obj_points = np.vstack(all_object_points) - - # For efficiency, downsample both point clouds - misc_downsampled = misc_pcd.voxel_down_sample(voxel_size=0.005) - - # Create object point cloud for efficient operations - obj_pcd = o3d.geometry.PointCloud() - obj_pcd.points = o3d.utility.Vector3dVector(combined_obj_points) - obj_downsampled = obj_pcd.voxel_down_sample(voxel_size=0.005) - - misc_points = np.asarray(misc_downsampled.points) - obj_points_down = np.asarray(obj_downsampled.points) - - if len(misc_points) == 0 or len(obj_points_down) == 0: - clusters = _cluster_point_cloud_dbscan(misc_downsampled, eps, min_points) - voxel_grid = _create_voxel_grid_from_clusters(clusters, voxel_size) - return clusters, voxel_grid - - # Build tree for object points - obj_tree = cKDTree(obj_points_down) - - # Find distances from misc points to nearest object points - distances, _ = obj_tree.query(misc_points, k=1) - - # Keep points that are far enough from any object point - threshold = 0.015 # 1.5cm threshold - keep_mask = distances > threshold - - if not np.any(keep_mask): - return [], o3d.geometry.VoxelGrid() - - # Filter misc points - misc_indices = np.where(keep_mask)[0] - final_misc_pcd = misc_downsampled.select_by_index(misc_indices) - - if len(np.asarray(final_misc_pcd.points)) == 0: - return [], o3d.geometry.VoxelGrid() - - # Apply additional filtering if enabled - if enable_filtering: - # Apply statistical outlier filtering - filtered_misc_pcd, _ = filter_point_cloud_statistical( - final_misc_pcd, nb_neighbors=30, std_ratio=2.0 - ) - - if len(np.asarray(filtered_misc_pcd.points)) == 0: - return [], o3d.geometry.VoxelGrid() - - # Apply radius outlier filtering - final_filtered_misc_pcd, _ = filter_point_cloud_radius( - filtered_misc_pcd, - nb_points=20, - radius=0.03, # 3cm radius - ) - - if len(np.asarray(final_filtered_misc_pcd.points)) == 0: - return [], o3d.geometry.VoxelGrid() - - final_misc_pcd = final_filtered_misc_pcd - - # Cluster the misc points using DBSCAN - clusters = _cluster_point_cloud_dbscan(final_misc_pcd, eps, min_points) - - # Create voxel grid from all misc points (before clustering) - voxel_grid = _create_voxel_grid_from_point_cloud(final_misc_pcd, voxel_size) - - return clusters, voxel_grid - - except Exception as e: - print(f"Error in misc point extraction and clustering: {e}") - # Fallback: return downsampled full point cloud as single cluster - try: - downsampled = full_pcd.voxel_down_sample(voxel_size=0.02) - if len(np.asarray(downsampled.points)) > 0: - voxel_grid = _create_voxel_grid_from_point_cloud(downsampled, voxel_size) - return [downsampled], voxel_grid - else: - return [], o3d.geometry.VoxelGrid() - except: - return [], o3d.geometry.VoxelGrid() - - -def _create_voxel_grid_from_point_cloud( - pcd: o3d.geometry.PointCloud, voxel_size: float = 0.02 -) -> o3d.geometry.VoxelGrid: - """ - Create a voxel grid from a point cloud. - - Args: - pcd: Input point cloud - voxel_size: Size of each voxel - - Returns: - Open3D VoxelGrid object - """ - if len(np.asarray(pcd.points)) == 0: - return o3d.geometry.VoxelGrid() - - try: - # Create voxel grid from point cloud - voxel_grid = o3d.geometry.VoxelGrid.create_from_point_cloud(pcd, voxel_size) - - # Color the voxels with a semi-transparent gray - for voxel in voxel_grid.get_voxels(): - voxel.color = [0.5, 0.5, 0.5] # Gray color - - print( - f"Created voxel grid with {len(voxel_grid.get_voxels())} voxels (voxel_size={voxel_size})" - ) - return voxel_grid - - except Exception as e: - print(f"Error creating voxel grid: {e}") - return o3d.geometry.VoxelGrid() - - -def _create_voxel_grid_from_clusters( - clusters: list[o3d.geometry.PointCloud], voxel_size: float = 0.02 -) -> o3d.geometry.VoxelGrid: - """ - Create a voxel grid from multiple clustered point clouds. - - Args: - clusters: List of clustered point clouds - voxel_size: Size of each voxel - - Returns: - Open3D VoxelGrid object - """ - if not clusters: - return o3d.geometry.VoxelGrid() - - # Combine all clusters into one point cloud - combined_points = [] - for cluster in clusters: - points = np.asarray(cluster.points) - if len(points) > 0: - combined_points.append(points) - - if not combined_points: - return o3d.geometry.VoxelGrid() - - # Create combined point cloud - all_points = np.vstack(combined_points) - combined_pcd = o3d.geometry.PointCloud() - combined_pcd.points = o3d.utility.Vector3dVector(all_points) - - return _create_voxel_grid_from_point_cloud(combined_pcd, voxel_size) - - -def _cluster_point_cloud_dbscan( - pcd: o3d.geometry.PointCloud, eps: float = 0.05, min_points: int = 50 -) -> list[o3d.geometry.PointCloud]: - """ - Cluster a point cloud using DBSCAN and return list of clustered point clouds. - - Args: - pcd: Point cloud to cluster - eps: DBSCAN epsilon parameter - min_points: DBSCAN min_samples parameter - - Returns: - List of point clouds, one for each cluster - """ - if len(np.asarray(pcd.points)) == 0: - return [] - - try: - # Apply DBSCAN clustering - labels = np.array(pcd.cluster_dbscan(eps=eps, min_points=min_points)) - - # Get unique cluster labels (excluding noise points labeled as -1) - unique_labels = np.unique(labels) - cluster_pcds = [] - - for label in unique_labels: - if label == -1: # Skip noise points - continue - - # Get indices for this cluster - cluster_indices = np.where(labels == label)[0] - - if len(cluster_indices) > 0: - # Create point cloud for this cluster - cluster_pcd = pcd.select_by_index(cluster_indices) - - # Assign a random color to this cluster - cluster_color = np.random.rand(3) # Random RGB color - cluster_pcd.paint_uniform_color(cluster_color) - - cluster_pcds.append(cluster_pcd) - - print( - f"DBSCAN clustering found {len(cluster_pcds)} clusters from {len(np.asarray(pcd.points))} points" - ) - return cluster_pcds - - except Exception as e: - print(f"Error in DBSCAN clustering: {e}") - return [pcd] # Return original point cloud as fallback - - -def get_standard_coordinate_transform(): # type: ignore[no-untyped-def] - """ - Get a standard coordinate transformation matrix for consistent visualization. - - This transformation ensures that: - - X (red) axis points right - - Y (green) axis points up - - Z (blue) axis points toward viewer - - Returns: - 4x4 transformation matrix - """ - # Standard transformation matrix to ensure consistent coordinate frame orientation - transform = np.array( - [ - [1, 0, 0, 0], # X points right - [0, -1, 0, 0], # Y points up (flip from OpenCV to standard) - [0, 0, -1, 0], # Z points toward viewer (flip depth) - [0, 0, 0, 1], - ] - ) - return transform - - -def visualize_clustered_point_clouds( - clustered_pcds: list[o3d.geometry.PointCloud], - window_name: str = "Clustered Point Clouds", - point_size: float = 2.0, - show_coordinate_frame: bool = True, - coordinate_frame_size: float = 0.1, -) -> None: - """ - Visualize multiple clustered point clouds with different colors. - - Args: - clustered_pcds: List of point clouds (already colored) - window_name: Name of the visualization window - point_size: Size of points in the visualization - show_coordinate_frame: Whether to show coordinate frame - coordinate_frame_size: Size of the coordinate frame - """ - if not clustered_pcds: - print("Warning: No clustered point clouds to visualize") - return - - # Apply standard coordinate transformation - transform = get_standard_coordinate_transform() # type: ignore[no-untyped-call] - geometries = [] - for pcd in clustered_pcds: - pcd_copy = o3d.geometry.PointCloud(pcd) - pcd_copy.transform(transform) - geometries.append(pcd_copy) - - # Add coordinate frame - if show_coordinate_frame: - coordinate_frame = o3d.geometry.TriangleMesh.create_coordinate_frame( - size=coordinate_frame_size - ) - coordinate_frame.transform(transform) - geometries.append(coordinate_frame) - - total_points = sum(len(np.asarray(pcd.points)) for pcd in clustered_pcds) - print(f"Visualizing {len(clustered_pcds)} clusters with {total_points} total points") - - try: - vis = o3d.visualization.Visualizer() - vis.create_window(window_name=window_name, width=1280, height=720) - for geom in geometries: - vis.add_geometry(geom) - render_option = vis.get_render_option() - render_option.point_size = point_size - vis.run() - vis.destroy_window() - except Exception as e: - print(f"Failed to create interactive visualization: {e}") - o3d.visualization.draw_geometries( - geometries, window_name=window_name, width=1280, height=720 - ) - - -def visualize_pcd( - pcd: o3d.geometry.PointCloud, - window_name: str = "Point Cloud Visualization", - point_size: float = 1.0, - show_coordinate_frame: bool = True, - coordinate_frame_size: float = 0.1, -) -> None: - """ - Visualize an Open3D point cloud using Open3D's visualization window. - - Args: - pcd: Open3D point cloud to visualize - window_name: Name of the visualization window - point_size: Size of points in the visualization - show_coordinate_frame: Whether to show coordinate frame - coordinate_frame_size: Size of the coordinate frame - """ - if pcd is None: - print("Warning: Point cloud is None, nothing to visualize") - return - - if len(np.asarray(pcd.points)) == 0: - print("Warning: Point cloud is empty, nothing to visualize") - return - - # Apply standard coordinate transformation - transform = get_standard_coordinate_transform() # type: ignore[no-untyped-call] - pcd_copy = o3d.geometry.PointCloud(pcd) - pcd_copy.transform(transform) - geometries = [pcd_copy] - - # Add coordinate frame - if show_coordinate_frame: - coordinate_frame = o3d.geometry.TriangleMesh.create_coordinate_frame( - size=coordinate_frame_size - ) - coordinate_frame.transform(transform) - geometries.append(coordinate_frame) - - print(f"Visualizing point cloud with {len(np.asarray(pcd.points))} points") - - try: - vis = o3d.visualization.Visualizer() - vis.create_window(window_name=window_name, width=1280, height=720) - for geom in geometries: - vis.add_geometry(geom) - render_option = vis.get_render_option() - render_option.point_size = point_size - vis.run() - vis.destroy_window() - except Exception as e: - print(f"Failed to create interactive visualization: {e}") - o3d.visualization.draw_geometries( - geometries, window_name=window_name, width=1280, height=720 - ) - - -def visualize_voxel_grid( - voxel_grid: o3d.geometry.VoxelGrid, - window_name: str = "Voxel Grid Visualization", - show_coordinate_frame: bool = True, - coordinate_frame_size: float = 0.1, -) -> None: - """ - Visualize an Open3D voxel grid using Open3D's visualization window. - - Args: - voxel_grid: Open3D voxel grid to visualize - window_name: Name of the visualization window - show_coordinate_frame: Whether to show coordinate frame - coordinate_frame_size: Size of the coordinate frame - """ - if voxel_grid is None: - print("Warning: Voxel grid is None, nothing to visualize") - return - - if len(voxel_grid.get_voxels()) == 0: - print("Warning: Voxel grid is empty, nothing to visualize") - return - - # VoxelGrid doesn't support transform, so we need to transform the source points instead - # For now, just visualize as-is with transformed coordinate frame - geometries = [voxel_grid] - - # Add coordinate frame - if show_coordinate_frame: - coordinate_frame = o3d.geometry.TriangleMesh.create_coordinate_frame( - size=coordinate_frame_size - ) - coordinate_frame.transform(get_standard_coordinate_transform()) # type: ignore[no-untyped-call] - geometries.append(coordinate_frame) - - print(f"Visualizing voxel grid with {len(voxel_grid.get_voxels())} voxels") - - try: - vis = o3d.visualization.Visualizer() - vis.create_window(window_name=window_name, width=1280, height=720) - for geom in geometries: - vis.add_geometry(geom) - vis.run() - vis.destroy_window() - except Exception as e: - print(f"Failed to create interactive visualization: {e}") - o3d.visualization.draw_geometries( - geometries, window_name=window_name, width=1280, height=720 - ) - - -def combine_object_pointclouds( - point_clouds: list[np.ndarray] | list[o3d.geometry.PointCloud], # type: ignore[type-arg] - colors: list[np.ndarray] | None = None, # type: ignore[type-arg] -) -> o3d.geometry.PointCloud: - """ - Combine multiple point clouds into a single Open3D point cloud. - - Args: - point_clouds: List of point clouds as numpy arrays or Open3D point clouds - colors: List of colors as numpy arrays - Returns: - Combined Open3D point cloud - """ - all_points = [] - all_colors = [] - - for i, pcd in enumerate(point_clouds): - if isinstance(pcd, np.ndarray): - points = pcd[:, :3] - all_points.append(points) - if colors: - all_colors.append(colors[i]) - - elif isinstance(pcd, o3d.geometry.PointCloud): - points = np.asarray(pcd.points) - all_points.append(points) - if pcd.has_colors(): - colors = np.asarray(pcd.colors) # type: ignore[assignment] - all_colors.append(colors) # type: ignore[arg-type] - - if not all_points: - return o3d.geometry.PointCloud() - - combined_pcd = o3d.geometry.PointCloud() - combined_pcd.points = o3d.utility.Vector3dVector(np.vstack(all_points)) - - if all_colors: - combined_pcd.colors = o3d.utility.Vector3dVector(np.vstack(all_colors)) - - return combined_pcd - - -def extract_centroids_from_masks( - rgb_image: np.ndarray, # type: ignore[type-arg] - depth_image: np.ndarray, # type: ignore[type-arg] - masks: list[np.ndarray], # type: ignore[type-arg] - camera_intrinsics: list[float] | np.ndarray, # type: ignore[type-arg] -) -> list[dict[str, Any]]: - """ - Extract 3D centroids and orientations from segmentation masks. - - Args: - rgb_image: RGB image (H, W, 3) - depth_image: Depth image (H, W) in meters - masks: List of boolean masks (H, W) - camera_intrinsics: Camera parameters as [fx, fy, cx, cy] or 3x3 matrix - - Returns: - List of dictionaries containing: - - centroid: 3D centroid position [x, y, z] in camera frame - - orientation: Normalized direction vector from camera to centroid - - num_points: Number of valid 3D points - - mask_idx: Index of the mask in the input list - """ - # Extract camera parameters - if isinstance(camera_intrinsics, list) and len(camera_intrinsics) == 4: - fx, fy, cx, cy = camera_intrinsics - else: - fx = camera_intrinsics[0, 0] # type: ignore[call-overload] - fy = camera_intrinsics[1, 1] # type: ignore[call-overload] - cx = camera_intrinsics[0, 2] # type: ignore[call-overload] - cy = camera_intrinsics[1, 2] # type: ignore[call-overload] - - results = [] - - for mask_idx, mask in enumerate(masks): - if mask is None or mask.sum() == 0: - continue - - # Get pixel coordinates where mask is True - y_coords, x_coords = np.where(mask) - - # Get depth values at mask locations - depths = depth_image[y_coords, x_coords] - - # Convert to 3D points in camera frame - X = (x_coords - cx) * depths / fx - Y = (y_coords - cy) * depths / fy - Z = depths - - # Calculate centroid - centroid_x = np.mean(X) - centroid_y = np.mean(Y) - centroid_z = np.mean(Z) - centroid = np.array([centroid_x, centroid_y, centroid_z]) - - # Calculate orientation as normalized direction from camera origin to centroid - # Camera origin is at (0, 0, 0) - orientation = centroid / np.linalg.norm(centroid) - - results.append( - { - "centroid": centroid, - "orientation": orientation, - "num_points": int(mask.sum()), - "mask_idx": mask_idx, - } - ) - - return results diff --git a/dimos/perception/segmentation/__init__.py b/dimos/perception/segmentation/__init__.py deleted file mode 100644 index a48a76d6a4..0000000000 --- a/dimos/perception/segmentation/__init__.py +++ /dev/null @@ -1,2 +0,0 @@ -from .sam_2d_seg import * -from .utils import * diff --git a/dimos/perception/segmentation/config/custom_tracker.yaml b/dimos/perception/segmentation/config/custom_tracker.yaml deleted file mode 100644 index 7a6748ebf6..0000000000 --- a/dimos/perception/segmentation/config/custom_tracker.yaml +++ /dev/null @@ -1,21 +0,0 @@ -# Ultralytics 🚀 AGPL-3.0 License - https://ultralytics.com/license - -# Default Ultralytics settings for BoT-SORT tracker when using mode="track" -# For documentation and examples see https://docs.ultralytics.com/modes/track/ -# For BoT-SORT source code see https://github.com/NirAharon/BoT-SORT - -tracker_type: botsort # tracker type, ['botsort', 'bytetrack'] -track_high_thresh: 0.4 # threshold for the first association -track_low_thresh: 0.2 # threshold for the second association -new_track_thresh: 0.5 # threshold for init new track if the detection does not match any tracks -track_buffer: 100 # buffer to calculate the time when to remove tracks -match_thresh: 0.4 # threshold for matching tracks -fuse_score: False # Whether to fuse confidence scores with the iou distances before matching -# min_box_area: 10 # threshold for min box areas(for tracker evaluation, not used for now) - -# BoT-SORT settings -gmc_method: sparseOptFlow # method of global motion compensation -# ReID model related thresh (not supported yet) -proximity_thresh: 0.6 -appearance_thresh: 0.35 -with_reid: False diff --git a/dimos/perception/segmentation/image_analyzer.py b/dimos/perception/segmentation/image_analyzer.py deleted file mode 100644 index 06db712ac7..0000000000 --- a/dimos/perception/segmentation/image_analyzer.py +++ /dev/null @@ -1,162 +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 base64 -import os - -import cv2 -from openai import OpenAI - -NORMAL_PROMPT = "What are in these images? Give a short word answer with at most two words, \ - if not sure, give a description of its shape or color like 'small tube', 'blue item'. \" \ - if does not look like an object, say 'unknown'. Export objects as a list of strings \ - in this exact format '['object 1', 'object 2', '...']'." - -RICH_PROMPT = ( - "What are in these images? Give a detailed description of each item, the first n images will be \ - cropped patches of the original image detected by the object detection model. \ - The last image will be the original image. Use the last image only for context, \ - do not describe objects in the last image. \ - Export the objects as a list of strings in this exact format, '['description of object 1', '...', '...']', \ - don't include anything else. " -) - - -class ImageAnalyzer: - def __init__(self) -> None: - """ - Initializes the ImageAnalyzer with OpenAI API credentials. - """ - self.client = OpenAI() - - def encode_image(self, image): # type: ignore[no-untyped-def] - """ - Encodes an image to Base64. - - Parameters: - image (numpy array): Image array (BGR format). - - Returns: - str: Base64 encoded string of the image. - """ - _, buffer = cv2.imencode(".jpg", image) - return base64.b64encode(buffer).decode("utf-8") - - def analyze_images(self, images, detail: str = "auto", prompt_type: str = "normal"): # type: ignore[no-untyped-def] - """ - Takes a list of cropped images and returns descriptions from OpenAI's Vision model. - - Parameters: - images (list of numpy arrays): Cropped images from the original frame. - detail (str): "low", "high", or "auto" to set image processing detail. - prompt_type (str): "normal" or "rich" to set the prompt type. - - Returns: - list of str: Descriptions of objects in each image. - """ - image_data = [ - { - "type": "image_url", - "image_url": { - "url": f"data:image/jpeg;base64,{self.encode_image(img)}", # type: ignore[no-untyped-call] - "detail": detail, - }, - } - for img in images - ] - - if prompt_type == "normal": - prompt = NORMAL_PROMPT - elif prompt_type == "rich": - prompt = RICH_PROMPT - else: - raise ValueError(f"Invalid prompt type: {prompt_type}") - - response = self.client.chat.completions.create( - model="gpt-4o-mini", - messages=[ - { # type: ignore[list-item, misc] - "role": "user", - "content": [{"type": "text", "text": prompt}, *image_data], - } - ], - max_tokens=300, - timeout=5, - ) - - # Accessing the content of the response using dot notation - return next(choice.message.content for choice in response.choices) - - -def main() -> None: - # Define the directory containing cropped images - cropped_images_dir = "cropped_images" - if not os.path.exists(cropped_images_dir): - print(f"Directory '{cropped_images_dir}' does not exist.") - return - - # Load all images from the directory - images = [] - for filename in os.listdir(cropped_images_dir): - if filename.endswith(".jpg") or filename.endswith(".png"): - image_path = os.path.join(cropped_images_dir, filename) - image = cv2.imread(image_path) - if image is not None: - images.append(image) - else: - print(f"Warning: Could not read image {image_path}") - - if not images: - print("No valid images found in the directory.") - return - - # Initialize ImageAnalyzer - analyzer = ImageAnalyzer() - - # Analyze images - results = analyzer.analyze_images(images) - - # Split results into a list of items - object_list = [item.strip()[2:] for item in results.split("\n")] - - # Overlay text on images and display them - for i, (img, obj) in enumerate(zip(images, object_list, strict=False)): - if obj: # Only process non-empty lines - # Add text to image - font = cv2.FONT_HERSHEY_SIMPLEX - font_scale = 0.5 - thickness = 2 - text = obj.strip() - - # Get text size - (text_width, text_height), _ = cv2.getTextSize(text, font, font_scale, thickness) - - # Position text at top of image - x = 10 - y = text_height + 10 - - # Add white background for text - cv2.rectangle( - img, (x - 5, y - text_height - 5), (x + text_width + 5, y + 5), (255, 255, 255), -1 - ) - # Add text - cv2.putText(img, text, (x, y), font, font_scale, (0, 0, 0), thickness) - - # Save or display the image - cv2.imwrite(f"annotated_image_{i}.jpg", img) - print(f"Detected object: {obj}") - - -if __name__ == "__main__": - main() diff --git a/dimos/perception/segmentation/sam_2d_seg.py b/dimos/perception/segmentation/sam_2d_seg.py deleted file mode 100644 index 741f71a9ab..0000000000 --- a/dimos/perception/segmentation/sam_2d_seg.py +++ /dev/null @@ -1,366 +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. - -from collections import deque -from collections.abc import Sequence -from concurrent.futures import ThreadPoolExecutor -import os -import time - -import cv2 -import onnxruntime # type: ignore[import-untyped] -import torch -from ultralytics import FastSAM # type: ignore[attr-defined, import-not-found] - -from dimos.perception.common.detection2d_tracker import get_tracked_results, target2dTracker -from dimos.perception.segmentation.image_analyzer import ImageAnalyzer -from dimos.perception.segmentation.utils import ( - crop_images_from_bboxes, - extract_masks_bboxes_probs_names, - filter_segmentation_results, - plot_results, -) -from dimos.utils.data import get_data -from dimos.utils.logging_config import setup_logger - -logger = setup_logger() - - -class Sam2DSegmenter: - def __init__( - self, - model_path: str = "models_fastsam", - model_name: str = "FastSAM-s.onnx", - min_analysis_interval: float = 5.0, - use_tracker: bool = True, - use_analyzer: bool = True, - use_rich_labeling: bool = False, - use_filtering: bool = True, - ) -> None: - # Use GPU if available, otherwise fall back to CPU - if torch.cuda.is_available(): - logger.info("Using CUDA for SAM 2d segmenter") - if hasattr(onnxruntime, "preload_dlls"): # Handles CUDA 11 / onnxruntime-gpu<=1.18 - onnxruntime.preload_dlls(cuda=True, cudnn=True) - self.device = "cuda" - # MacOS Metal performance shaders - elif torch.backends.mps.is_available() and torch.backends.mps.is_built(): - logger.info("Using Metal for SAM 2d segmenter") - self.device = "mps" - else: - logger.info("Using CPU for SAM 2d segmenter") - self.device = "cpu" - - # Core components - self.model = FastSAM(get_data(model_path) / model_name) - self.use_tracker = use_tracker - self.use_analyzer = use_analyzer - self.use_rich_labeling = use_rich_labeling - self.use_filtering = use_filtering - - module_dir = os.path.dirname(__file__) - self.tracker_config = os.path.join(module_dir, "config", "custom_tracker.yaml") - - # Initialize tracker if enabled - if self.use_tracker: - self.tracker = target2dTracker( - history_size=80, - score_threshold_start=0.7, - score_threshold_stop=0.05, - min_frame_count=10, - max_missed_frames=50, - min_area_ratio=0.05, - max_area_ratio=0.4, - texture_range=(0.0, 0.35), - border_safe_distance=100, - weights={"prob": 1.0, "temporal": 3.0, "texture": 2.0, "border": 3.0, "size": 1.0}, - ) - - # Initialize analyzer components if enabled - if self.use_analyzer: - self.image_analyzer = ImageAnalyzer() - self.min_analysis_interval = min_analysis_interval - self.last_analysis_time = 0 - self.to_be_analyzed = deque() # type: ignore[var-annotated] - self.object_names = {} # type: ignore[var-annotated] - self.analysis_executor = ThreadPoolExecutor(max_workers=1) - self.current_future = None - self.current_queue_ids = None - - def process_image(self, image): # type: ignore[no-untyped-def] - """Process an image and return segmentation results.""" - results = self.model.track( - source=image, - device=self.device, - retina_masks=True, - conf=0.3, - iou=0.5, - persist=True, - verbose=False, - ) - - if len(results) > 0: - # Get initial segmentation results - masks, bboxes, track_ids, probs, names, areas = extract_masks_bboxes_probs_names( - results[0] - ) - - # Filter results - if self.use_filtering: - ( - filtered_masks, - filtered_bboxes, - filtered_track_ids, - filtered_probs, - filtered_names, - filtered_texture_values, - ) = filter_segmentation_results( - image, masks, bboxes, track_ids, probs, names, areas - ) - else: - # Use original results without filtering - filtered_masks = masks - filtered_bboxes = bboxes - filtered_track_ids = track_ids - filtered_probs = probs - filtered_names = names - filtered_texture_values = [] - - if self.use_tracker: - # Update tracker with filtered results - tracked_targets = self.tracker.update( - image, - filtered_masks, - filtered_bboxes, - filtered_track_ids, - filtered_probs, - filtered_names, - filtered_texture_values, - ) - - # Get tracked results - tracked_masks, tracked_bboxes, tracked_target_ids, tracked_probs, tracked_names = ( - get_tracked_results(tracked_targets) # type: ignore[no-untyped-call] - ) - - if self.use_analyzer: - # Update analysis queue with tracked IDs - target_id_set = set(tracked_target_ids) - - # Remove untracked objects from object_names - all_target_ids = list(self.tracker.targets.keys()) - self.object_names = { - track_id: name - for track_id, name in self.object_names.items() - if track_id in all_target_ids - } - - # Remove untracked objects from queue and results - self.to_be_analyzed = deque( - [track_id for track_id in self.to_be_analyzed if track_id in target_id_set] - ) - - # Filter out any IDs being analyzed from the to_be_analyzed queue - if self.current_queue_ids: - self.to_be_analyzed = deque( - [ - tid - for tid in self.to_be_analyzed - if tid not in self.current_queue_ids - ] - ) - - # Add new track_ids to analysis queue - for track_id in tracked_target_ids: - if ( - track_id not in self.object_names - and track_id not in self.to_be_analyzed - ): - self.to_be_analyzed.append(track_id) - - return ( - tracked_masks, - tracked_bboxes, - tracked_target_ids, - tracked_probs, - tracked_names, - ) - else: - # When tracker disabled, just use the filtered results directly - if self.use_analyzer: - # Add unanalyzed IDs to the analysis queue - for track_id in filtered_track_ids: - if ( - track_id not in self.object_names - and track_id not in self.to_be_analyzed - ): - self.to_be_analyzed.append(track_id) - - # Simply return filtered results - return ( - filtered_masks, - filtered_bboxes, - filtered_track_ids, - filtered_probs, - filtered_names, - ) - return [], [], [], [], [] - - def check_analysis_status(self, tracked_target_ids): # type: ignore[no-untyped-def] - """Check if analysis is complete and prepare new queue if needed.""" - if not self.use_analyzer: - return None, None - - current_time = time.time() - - # Check if current queue analysis is complete - if self.current_future and self.current_future.done(): - try: - results = self.current_future.result() - if results is not None: - # Map results to track IDs - object_list = eval(results) - for track_id, result in zip(self.current_queue_ids, object_list, strict=False): - self.object_names[track_id] = result - except Exception as e: - print(f"Queue analysis failed: {e}") - self.current_future = None - self.current_queue_ids = None - self.last_analysis_time = current_time - - # If enough time has passed and we have items to analyze, start new analysis - if ( - not self.current_future - and self.to_be_analyzed - and current_time - self.last_analysis_time >= self.min_analysis_interval - ): - queue_indices = [] - queue_ids = [] - - # Collect all valid track IDs from the queue - while self.to_be_analyzed: - track_id = self.to_be_analyzed[0] - if track_id in tracked_target_ids: - bbox_idx = tracked_target_ids.index(track_id) - queue_indices.append(bbox_idx) - queue_ids.append(track_id) - self.to_be_analyzed.popleft() - - if queue_indices: - return queue_indices, queue_ids - return None, None - - def run_analysis(self, frame, tracked_bboxes, tracked_target_ids) -> None: # type: ignore[no-untyped-def] - """Run queue image analysis in background.""" - if not self.use_analyzer: - return - - queue_indices, queue_ids = self.check_analysis_status(tracked_target_ids) # type: ignore[no-untyped-call] - if queue_indices: - selected_bboxes = [tracked_bboxes[i] for i in queue_indices] - cropped_images = crop_images_from_bboxes(frame, selected_bboxes) - if cropped_images: - self.current_queue_ids = queue_ids - print(f"Analyzing objects with track_ids: {queue_ids}") - - if self.use_rich_labeling: - prompt_type = "rich" - cropped_images.append(frame) - else: - prompt_type = "normal" - - self.current_future = self.analysis_executor.submit( # type: ignore[assignment] - self.image_analyzer.analyze_images, cropped_images, prompt_type=prompt_type - ) - - def get_object_names(self, track_ids, tracked_names: Sequence[str]): # type: ignore[no-untyped-def] - """Get object names for the given track IDs, falling back to tracked names.""" - if not self.use_analyzer: - return tracked_names - - return [ - self.object_names.get(track_id, tracked_name) - for track_id, tracked_name in zip(track_ids, tracked_names, strict=False) - ] - - def visualize_results( # type: ignore[no-untyped-def] - self, image, masks, bboxes, track_ids, probs: Sequence[float], names: Sequence[str] - ): - """Generate an overlay visualization with segmentation results and object names.""" - return plot_results(image, masks, bboxes, track_ids, probs, names) - - def cleanup(self) -> None: - """Cleanup resources.""" - if self.use_analyzer: - self.analysis_executor.shutdown() - - -def main() -> None: - # Example usage with different configurations - cap = cv2.VideoCapture(0) - - # Example 1: Full functionality with rich labeling - segmenter = Sam2DSegmenter( - min_analysis_interval=4.0, - use_tracker=True, - use_analyzer=True, - use_rich_labeling=True, # Enable rich labeling - ) - - # Example 2: Full functionality with normal labeling - # segmenter = Sam2DSegmenter(min_analysis_interval=4.0, use_tracker=True, use_analyzer=True) - - # Example 3: Tracker only (analyzer disabled) - # segmenter = Sam2DSegmenter(use_analyzer=False) - - # Example 4: Basic segmentation only (both tracker and analyzer disabled) - # segmenter = Sam2DSegmenter(use_tracker=False, use_analyzer=False) - - # Example 5: Analyzer without tracker (new capability) - # segmenter = Sam2DSegmenter(use_tracker=False, use_analyzer=True) - - try: - while cap.isOpened(): - ret, frame = cap.read() - if not ret: - break - - time.time() - - # Process image and get results - masks, bboxes, target_ids, probs, names = segmenter.process_image(frame) # type: ignore[no-untyped-call] - - # Run analysis if enabled - if segmenter.use_analyzer: - segmenter.run_analysis(frame, bboxes, target_ids) - names = segmenter.get_object_names(target_ids, names) - - # processing_time = time.time() - start_time - # print(f"Processing time: {processing_time:.2f}s") - - overlay = segmenter.visualize_results(frame, masks, bboxes, target_ids, probs, names) - - cv2.imshow("Segmentation", overlay) - key = cv2.waitKey(1) - if key & 0xFF == ord("q"): - break - - finally: - segmenter.cleanup() - cap.release() - cv2.destroyAllWindows() - - -if __name__ == "__main__": - main() diff --git a/dimos/perception/segmentation/test_sam_2d_seg.py b/dimos/perception/segmentation/test_sam_2d_seg.py deleted file mode 100644 index a9222ed2f2..0000000000 --- a/dimos/perception/segmentation/test_sam_2d_seg.py +++ /dev/null @@ -1,210 +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 os -import time - -import numpy as np -import pytest -from reactivex import operators as ops - -from dimos.perception.segmentation.sam_2d_seg import Sam2DSegmenter -from dimos.perception.segmentation.utils import extract_masks_bboxes_probs_names -from dimos.stream.video_provider import VideoProvider - - -@pytest.mark.heavy -class TestSam2DSegmenter: - def test_sam_segmenter_initialization(self) -> None: - """Test FastSAM segmenter initializes correctly with default model path.""" - try: - # Try to initialize with the default model path and existing device setting - segmenter = Sam2DSegmenter(use_analyzer=False) - assert segmenter is not None - assert segmenter.model is not None - except Exception as e: - # If the model file doesn't exist, the test should still pass with a warning - pytest.skip(f"Skipping test due to model initialization error: {e}") - - def test_sam_segmenter_process_image(self) -> None: - """Test FastSAM segmenter can process video frames and return segmentation masks.""" - # Import get data inside method to avoid pytest fixture confusion - from dimos.utils.data import get_data - - # Get test video path directly - video_path = get_data("assets") / "trimmed_video_office.mov" - try: - # Initialize segmenter without analyzer for faster testing - segmenter = Sam2DSegmenter(use_analyzer=False) - - # Note: conf and iou are parameters for process_image, not constructor - # We'll monkey patch the process_image method to use lower thresholds - - def patched_process_image(image): - results = segmenter.model.track( - source=image, - device=segmenter.device, - retina_masks=True, - conf=0.1, # Lower confidence threshold for testing - iou=0.5, # Lower IoU threshold - persist=True, - verbose=False, - tracker=segmenter.tracker_config - if hasattr(segmenter, "tracker_config") - else None, - ) - - if len(results) > 0: - masks, bboxes, track_ids, probs, names, _areas = ( - extract_masks_bboxes_probs_names(results[0]) - ) - return masks, bboxes, track_ids, probs, names - return [], [], [], [], [] - - # Replace the method - segmenter.process_image = patched_process_image - - # Create video provider and directly get a video stream observable - assert os.path.exists(video_path), f"Test video not found: {video_path}" - video_provider = VideoProvider(dev_name="test_video", video_source=video_path) - - video_stream = video_provider.capture_video_as_observable(realtime=False, fps=1) - - # Use ReactiveX operators to process the stream - def process_frame(frame): - try: - # Process frame with FastSAM - masks, bboxes, track_ids, probs, names = segmenter.process_image(frame) - print( - f"SAM results - masks: {len(masks)}, bboxes: {len(bboxes)}, track_ids: {len(track_ids)}, names: {len(names)}" - ) - - return { - "frame": frame, - "masks": masks, - "bboxes": bboxes, - "track_ids": track_ids, - "probs": probs, - "names": names, - } - except Exception as e: - print(f"Error in process_frame: {e}") - return {} - - # Create the segmentation stream using pipe and map operator - segmentation_stream = video_stream.pipe(ops.map(process_frame)) - - # Collect results from the stream - results = [] - frames_processed = 0 - target_frames = 5 - - def on_next(result) -> None: - nonlocal frames_processed, results - if not result: - return - - results.append(result) - frames_processed += 1 - - # Stop processing after target frames - if frames_processed >= target_frames: - subscription.dispose() - - def on_error(error) -> None: - pytest.fail(f"Error in segmentation stream: {error}") - - def on_completed() -> None: - pass - - # Subscribe and wait for results - subscription = segmentation_stream.subscribe( - on_next=on_next, on_error=on_error, on_completed=on_completed - ) - - # Wait for frames to be processed - timeout = 30.0 # seconds - start_time = time.time() - while frames_processed < target_frames and time.time() - start_time < timeout: - time.sleep(0.5) - - # Clean up subscription - subscription.dispose() - video_provider.dispose_all() - - # Check if we have results - if len(results) == 0: - pytest.skip( - "No segmentation results found, but test connection established correctly" - ) - return - - print(f"Processed {len(results)} frames with segmentation results") - - # Analyze the first result - result = results[0] - - # Check that we have a frame - assert "frame" in result, "Result doesn't contain a frame" - assert isinstance(result["frame"], np.ndarray), "Frame is not a numpy array" - - # Check that segmentation results are valid - assert isinstance(result["masks"], list) - assert isinstance(result["bboxes"], list) - assert isinstance(result["track_ids"], list) - assert isinstance(result["probs"], list) - assert isinstance(result["names"], list) - - # All result lists should be the same length - assert ( - len(result["masks"]) - == len(result["bboxes"]) - == len(result["track_ids"]) - == len(result["probs"]) - == len(result["names"]) - ) - - # If we have masks, check that they have valid shape - if result.get("masks") and len(result["masks"]) > 0: - assert result["masks"][0].shape == ( - result["frame"].shape[0], - result["frame"].shape[1], - ), "Mask shape should match image dimensions" - print(f"Found {len(result['masks'])} masks in first frame") - else: - print("No masks found in first frame, but test connection established correctly") - - # Test visualization function - if result["masks"]: - vis_frame = segmenter.visualize_results( - result["frame"], - result["masks"], - result["bboxes"], - result["track_ids"], - result["probs"], - result["names"], - ) - assert isinstance(vis_frame, np.ndarray), "Visualization output should be an image" - assert vis_frame.shape == result["frame"].shape, ( - "Visualization should have same dimensions as input frame" - ) - - # We've already tested visualization above, so no need for a duplicate test - - except Exception as e: - pytest.skip(f"Skipping test due to error: {e}") - - -if __name__ == "__main__": - pytest.main(["-v", __file__]) diff --git a/dimos/perception/segmentation/utils.py b/dimos/perception/segmentation/utils.py deleted file mode 100644 index a23a256ca2..0000000000 --- a/dimos/perception/segmentation/utils.py +++ /dev/null @@ -1,343 +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. - -from collections.abc import Sequence - -import cv2 -import numpy as np -import torch - - -class SimpleTracker: - def __init__( - self, history_size: int = 100, min_count: int = 10, count_window: int = 20 - ) -> None: - """ - Simple temporal tracker that counts appearances in a fixed window. - :param history_size: Number of past frames to remember - :param min_count: Minimum number of appearances required - :param count_window: Number of latest frames to consider for counting - """ - self.history = [] # type: ignore[var-annotated] - self.history_size = history_size - self.min_count = min_count - self.count_window = count_window - self.total_counts = {} # type: ignore[var-annotated] - - def update(self, track_ids): # type: ignore[no-untyped-def] - # Add new frame's track IDs to history - self.history.append(track_ids) - if len(self.history) > self.history_size: - self.history.pop(0) - - # Consider only the latest `count_window` frames for counting - recent_history = self.history[-self.count_window :] - all_tracks = np.concatenate(recent_history) if recent_history else np.array([]) - - # Compute occurrences efficiently using numpy - unique_ids, counts = np.unique(all_tracks, return_counts=True) - id_counts = dict(zip(unique_ids, counts, strict=False)) - - # Update total counts but ensure it only contains IDs within the history size - total_tracked_ids = np.concatenate(self.history) if self.history else np.array([]) - unique_total_ids, total_counts = np.unique(total_tracked_ids, return_counts=True) - self.total_counts = dict(zip(unique_total_ids, total_counts, strict=False)) - - # Return IDs that appear often enough - return [track_id for track_id, count in id_counts.items() if count >= self.min_count] - - def get_total_counts(self): # type: ignore[no-untyped-def] - """Returns the total count of each tracking ID seen over time, limited to history size.""" - return self.total_counts - - -def extract_masks_bboxes_probs_names(result, max_size: float = 0.7): # type: ignore[no-untyped-def] - """ - Extracts masks, bounding boxes, probabilities, and class names from one Ultralytics result object. - - Parameters: - result: Ultralytics result object - max_size: float, maximum allowed size of object relative to image (0-1) - - Returns: - tuple: (masks, bboxes, track_ids, probs, names, areas) - """ - masks = [] # type: ignore[var-annotated] - bboxes = [] # type: ignore[var-annotated] - track_ids = [] # type: ignore[var-annotated] - probs = [] # type: ignore[var-annotated] - names = [] # type: ignore[var-annotated] - areas = [] # type: ignore[var-annotated] - - if result.masks is None: - return masks, bboxes, track_ids, probs, names, areas - - total_area = result.masks.orig_shape[0] * result.masks.orig_shape[1] - - for box, mask_data in zip(result.boxes, result.masks.data, strict=False): - mask_numpy = mask_data - - # Extract bounding box - x1, y1, x2, y2 = box.xyxy[0].tolist() - - # Extract track_id if available - track_id = -1 # default if no tracking - if hasattr(box, "id") and box.id is not None: - track_id = int(box.id[0].item()) - - # Extract probability and class index - conf = float(box.conf[0]) - cls_idx = int(box.cls[0]) - area = (x2 - x1) * (y2 - y1) - - if area / total_area > max_size: - continue - - masks.append(mask_numpy) - bboxes.append([x1, y1, x2, y2]) - track_ids.append(track_id) - probs.append(conf) - names.append(result.names[cls_idx]) - areas.append(area) - - return masks, bboxes, track_ids, probs, names, areas - - -def compute_texture_map(frame, blur_size: int = 3): # type: ignore[no-untyped-def] - """ - Compute texture map using gradient statistics. - Returns high values for textured regions and low values for smooth regions. - - Parameters: - frame: BGR image - blur_size: Size of Gaussian blur kernel for pre-processing - - Returns: - numpy array: Texture map with values normalized to [0,1] - """ - # Convert to grayscale - if len(frame.shape) == 3: - gray = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY) - else: - gray = frame - - # Pre-process with slight blur to reduce noise - if blur_size > 0: - gray = cv2.GaussianBlur(gray, (blur_size, blur_size), 0) - - # Compute gradients in x and y directions - grad_x = cv2.Sobel(gray, cv2.CV_32F, 1, 0, ksize=3) - grad_y = cv2.Sobel(gray, cv2.CV_32F, 0, 1, ksize=3) - - # Compute gradient magnitude and direction - magnitude = np.sqrt(grad_x**2 + grad_y**2) - - # Compute local standard deviation of gradient magnitude - texture_map = cv2.GaussianBlur(magnitude, (15, 15), 0) - - # Normalize to [0,1] - texture_map = (texture_map - texture_map.min()) / (texture_map.max() - texture_map.min() + 1e-8) - - return texture_map - - -def filter_segmentation_results( # type: ignore[no-untyped-def] - frame, - masks, - bboxes, - track_ids, - probs: Sequence[float], - names: Sequence[str], - areas, - texture_threshold: float = 0.07, - size_filter: int = 800, -): - """ - Filters segmentation results using both overlap and saliency detection. - Uses mask_sum tensor for efficient overlap detection. - - Parameters: - masks: list of torch.Tensor containing mask data - bboxes: list of bounding boxes [x1, y1, x2, y2] - track_ids: list of tracking IDs - probs: list of confidence scores - names: list of class names - areas: list of object areas - frame: BGR image for computing saliency - texture_threshold: Average texture value required for mask to be kept - size_filter: Minimum size of the object to be kept - - Returns: - tuple: (filtered_masks, filtered_bboxes, filtered_track_ids, filtered_probs, filtered_names, filtered_texture_values, texture_map) - """ - if len(masks) <= 1: - return masks, bboxes, track_ids, probs, names, [] - - # Compute texture map once and convert to tensor - texture_map = compute_texture_map(frame) - - # Sort by area (smallest to largest) - sorted_indices = torch.tensor(areas).argsort(descending=False) - - device = masks[0].device # Get the device of the first mask - - # Create mask_sum tensor where each pixel stores the index of the mask that claims it - mask_sum = torch.zeros_like(masks[0], dtype=torch.int32) - - texture_map = torch.from_numpy(texture_map).to( - device - ) # Convert texture_map to tensor and move to device - - filtered_texture_values = [] # List to store texture values of filtered masks - - for i, idx in enumerate(sorted_indices): - mask = masks[idx] - # Compute average texture value within mask - texture_value = torch.mean(texture_map[mask > 0]) if torch.any(mask > 0) else 0 - - # Only claim pixels if mask passes texture threshold - if texture_value >= texture_threshold: - mask_sum[mask > 0] = i - filtered_texture_values.append( - texture_value.item() # type: ignore[union-attr] - ) # Store the texture value as a Python float - - # Get indices that appear in mask_sum (these are the masks we want to keep) - keep_indices, counts = torch.unique(mask_sum[mask_sum > 0], return_counts=True) - size_indices = counts > size_filter - keep_indices = keep_indices[size_indices] - - sorted_indices = sorted_indices.cpu() - keep_indices = keep_indices.cpu() - - # Map back to original indices and filter - final_indices = sorted_indices[keep_indices].tolist() - - filtered_masks = [masks[i] for i in final_indices] - filtered_bboxes = [bboxes[i] for i in final_indices] - filtered_track_ids = [track_ids[i] for i in final_indices] - filtered_probs = [probs[i] for i in final_indices] - filtered_names = [names[i] for i in final_indices] - - return ( - filtered_masks, - filtered_bboxes, - filtered_track_ids, - filtered_probs, - filtered_names, - filtered_texture_values, - ) - - -def plot_results( # type: ignore[no-untyped-def] - image, - masks, - bboxes, - track_ids, - probs: Sequence[float], - names: Sequence[str], - alpha: float = 0.5, -): - """ - Draws bounding boxes, masks, and labels on the given image with enhanced visualization. - Includes object names in the overlay and improved text visibility. - """ - h, w = image.shape[:2] - overlay = image.copy() - - for mask, bbox, track_id, prob, name in zip( - masks, bboxes, track_ids, probs, names, strict=False - ): - # Convert mask tensor to numpy if needed - if isinstance(mask, torch.Tensor): - mask = mask.cpu().numpy() - - # Ensure mask is in proper format for OpenCV resize - if mask.dtype == bool: - mask = mask.astype(np.uint8) - elif mask.dtype != np.uint8 and mask.dtype != np.float32: - mask = mask.astype(np.float32) - - mask_resized = cv2.resize(mask, (w, h), interpolation=cv2.INTER_LINEAR) - - # Generate consistent color based on track_id - if track_id != -1: - np.random.seed(track_id) - color = np.random.randint(0, 255, (3,), dtype=np.uint8) - np.random.seed(None) - else: - color = np.random.randint(0, 255, (3,), dtype=np.uint8) - - # Apply mask color - overlay[mask_resized > 0.5] = color - - # Draw bounding box - x1, y1, x2, y2 = map(int, bbox) - cv2.rectangle(overlay, (x1, y1), (x2, y2), color.tolist(), 2) - - # Prepare label text - label = f"ID:{track_id} {prob:.2f}" - if name: # Add object name if available - label += f" {name}" - - # Calculate text size for background rectangle - (text_w, text_h), _ = cv2.getTextSize(label, cv2.FONT_HERSHEY_SIMPLEX, 0.5, 1) - - # Draw background rectangle for text - cv2.rectangle(overlay, (x1, y1 - text_h - 8), (x1 + text_w + 4, y1), color.tolist(), -1) - - # Draw text with white color for better visibility - cv2.putText( - overlay, - label, - (x1 + 2, y1 - 5), - cv2.FONT_HERSHEY_SIMPLEX, - 0.5, - (255, 255, 255), # White text - 1, - ) - - # Blend overlay with original image - result = cv2.addWeighted(overlay, alpha, image, 1 - alpha, 0) - return result - - -def crop_images_from_bboxes(image, bboxes, buffer: int = 0): # type: ignore[no-untyped-def] - """ - Crops regions from an image based on bounding boxes with an optional buffer. - - Parameters: - image (numpy array): Input image. - bboxes (list of lists): List of bounding boxes [x1, y1, x2, y2]. - buffer (int): Number of pixels to expand each bounding box. - - Returns: - list of numpy arrays: Cropped image regions. - """ - height, width, _ = image.shape - cropped_images = [] - - for bbox in bboxes: - x1, y1, x2, y2 = bbox - - # Apply buffer - x1 = max(0, x1 - buffer) - y1 = max(0, y1 - buffer) - x2 = min(width, x2 + buffer) - y2 = min(height, y2 + buffer) - - cropped_image = image[int(y1) : int(y2), int(x1) : int(x2)] - cropped_images.append(cropped_image) - - return cropped_images diff --git a/dimos/robot/agilex/README.md b/dimos/robot/agilex/README.md deleted file mode 100644 index 8342a6045e..0000000000 --- a/dimos/robot/agilex/README.md +++ /dev/null @@ -1,371 +0,0 @@ -# DIMOS Manipulator Robot Development Guide - -This guide explains how to create robot classes, integrate agents, and use the DIMOS module system with LCM transport. - -## Table of Contents -1. [Robot Class Architecture](#robot-class-architecture) -2. [Module System & LCM Transport](#module-system--lcm-transport) -3. [Agent Integration](#agent-integration) -4. [Complete Example](#complete-example) - -## Robot Class Architecture - -### Basic Robot Class Structure - -A DIMOS robot class should follow this pattern: - -```python -from typing import Optional, List -from dimos import core -from dimos.types.robot_capabilities import RobotCapability - -class YourRobot: - """Your robot implementation.""" - - def __init__(self, robot_capabilities: Optional[List[RobotCapability]] = None): - # Core components - self.dimos = None - self.modules = {} - self.skill_library = SkillLibrary() - - # Define capabilities - self.capabilities = robot_capabilities or [ - RobotCapability.VISION, - RobotCapability.MANIPULATION, - ] - - async def start(self): - """Start the robot modules.""" - # Initialize DIMOS with worker count - self.dimos = core.start(2) # Number of workers needed - - # Deploy modules - # ... (see Module System section) - - def stop(self): - """Stop all modules and clean up.""" - # Stop modules - # Close DIMOS - if self.dimos: - self.dimos.close() -``` - -### Key Components Explained - -1. **Initialization**: Store references to modules, skills, and capabilities -2. **Async Start**: Modules must be deployed asynchronously -3. **Proper Cleanup**: Always stop modules before closing DIMOS - -## Module System & LCM Transport - -### Understanding DIMOS Modules - -Modules are the building blocks of DIMOS robots. They: -- Process data streams (inputs) -- Produce outputs -- Can be connected together -- Communicate via LCM (Lightweight Communications and Marshalling) - -### Deploying a Module - -```python -# Deploy a camera module -self.camera = self.dimos.deploy( - ZEDModule, # Module class - camera_id=0, # Module parameters - resolution="HD720", - depth_mode="NEURAL", - fps=30, - publish_rate=30.0, - frame_id="camera_frame" -) -``` - -### Setting Up LCM Transport - -LCM transport enables inter-module communication: - -```python -# Enable LCM auto-configuration -from dimos.protocol import pubsub -pubsub.lcm.autoconf() - -# Configure output transport -self.camera.color_image.transport = core.LCMTransport( - "/camera/color_image", # Topic name - Image # Message type -) -self.camera.depth_image.transport = core.LCMTransport( - "/camera/depth_image", - Image -) -``` - -### Connecting Modules - -Connect module outputs to inputs: - -```python -# Connect manipulation module to camera outputs -self.manipulation.rgb_image.connect(self.camera.color_image) -self.manipulation.depth_image.connect(self.camera.depth_image) -self.manipulation.camera_info.connect(self.camera.camera_info) -``` - -### Module Communication Pattern - -``` -┌──────────────┐ LCM ┌────────────────┐ LCM ┌──────────────┐ -│ Camera │────────▶│ Manipulation │────────▶│ Visualization│ -│ Module │ Messages│ Module │ Messages│ Output │ -└──────────────┘ └────────────────┘ └──────────────┘ - ▲ ▲ - │ │ - └──────────────────────────┘ - Direct Connection via RPC call -``` - -## Agent Integration - -### Setting Up Agent with Robot - -The run file pattern for agent integration: - -```python -#!/usr/bin/env python3 -import asyncio -import reactivex as rx -from dimos.agents_deprecated.claude_agent import ClaudeAgent -from dimos.web.robot_web_interface import RobotWebInterface - -def main(): - # 1. Create and start robot - robot = YourRobot() - asyncio.run(robot.start()) - - # 2. Set up skills - skills = robot.get_skills() - skills.add(YourSkill) - skills.create_instance("YourSkill", robot=robot) - - # 3. Set up reactive streams - agent_response_subject = rx.subject.Subject() - agent_response_stream = agent_response_subject.pipe(ops.share()) - - # 4. Create web interface - web_interface = RobotWebInterface( - port=5555, - text_streams={"agent_responses": agent_response_stream}, - audio_subject=rx.subject.Subject() - ) - - # 5. Create agent - agent = ClaudeAgent( - dev_name="your_agent", - input_query_stream=web_interface.query_stream, - skills=skills, - system_query="Your system prompt here", - model_name="claude-3-5-haiku-latest" - ) - - # 6. Connect agent responses - agent.get_response_observable().subscribe( - lambda x: agent_response_subject.on_next(x) - ) - - # 7. Run interface - web_interface.run() -``` - -### Key Integration Points - -1. **Reactive Streams**: Use RxPy for event-driven communication -2. **Web Interface**: Provides user input/output -3. **Agent**: Processes natural language and executes skills -4. **Skills**: Define robot capabilities as executable actions - -## Complete Example - -### Step 1: Create Robot Class (`my_robot.py`) - -```python -import asyncio -from typing import Optional, List -from dimos import core -from dimos.hardware.camera import CameraModule -from dimos.manipulation.module import ManipulationModule -from dimos.skills.skills import SkillLibrary -from dimos.types.robot_capabilities import RobotCapability -from dimos_lcm.sensor_msgs import Image, CameraInfo -from dimos.protocol import pubsub - -class MyRobot: - def __init__(self, robot_capabilities: Optional[List[RobotCapability]] = None): - self.dimos = None - self.camera = None - self.manipulation = None - self.skill_library = SkillLibrary() - - self.capabilities = robot_capabilities or [ - RobotCapability.VISION, - RobotCapability.MANIPULATION, - ] - - async def start(self): - # Start DIMOS - self.dimos = core.start(2) - - # Enable LCM - pubsub.lcm.autoconf() - - # Deploy camera - self.camera = self.dimos.deploy( - CameraModule, - camera_id=0, - fps=30 - ) - - # Configure camera LCM - self.camera.color_image.transport = core.LCMTransport("/camera/rgb", Image) - self.camera.depth_image.transport = core.LCMTransport("/camera/depth", Image) - self.camera.camera_info.transport = core.LCMTransport("/camera/info", CameraInfo) - - # Deploy manipulation - self.manipulation = self.dimos.deploy(ManipulationModule) - - # Connect modules - self.manipulation.rgb_image.connect(self.camera.color_image) - self.manipulation.depth_image.connect(self.camera.depth_image) - self.manipulation.camera_info.connect(self.camera.camera_info) - - # Configure manipulation output - self.manipulation.viz_image.transport = core.LCMTransport("/viz/output", Image) - - # Start modules - self.camera.start() - self.manipulation.start() - - await asyncio.sleep(2) # Allow initialization - - def get_skills(self): - return self.skill_library - - def stop(self): - if self.manipulation: - self.manipulation.stop() - if self.camera: - self.camera.stop() - if self.dimos: - self.dimos.close() -``` - -### Step 2: Create Run Script (`run.py`) - -```python -#!/usr/bin/env python3 -import asyncio -import os -from my_robot import MyRobot -from dimos.agents_deprecated.claude_agent import ClaudeAgent -from dimos.skills.basic import BasicSkill -from dimos.web.robot_web_interface import RobotWebInterface -import reactivex as rx -import reactivex.operators as ops - -SYSTEM_PROMPT = """You are a helpful robot assistant.""" - -def main(): - # Check API key - if not os.getenv("ANTHROPIC_API_KEY"): - print("Please set ANTHROPIC_API_KEY") - return - - # Create robot - robot = MyRobot() - - try: - # Start robot - asyncio.run(robot.start()) - - # Set up skills - skills = robot.get_skills() - skills.add(BasicSkill) - skills.create_instance("BasicSkill", robot=robot) - - # Set up streams - agent_response_subject = rx.subject.Subject() - agent_response_stream = agent_response_subject.pipe(ops.share()) - - # Create web interface - web_interface = RobotWebInterface( - port=5555, - text_streams={"agent_responses": agent_response_stream} - ) - - # Create agent - agent = ClaudeAgent( - dev_name="my_agent", - input_query_stream=web_interface.query_stream, - skills=skills, - system_query=SYSTEM_PROMPT - ) - - # Connect responses - agent.get_response_observable().subscribe( - lambda x: agent_response_subject.on_next(x) - ) - - print("Robot ready at http://localhost:5555") - - # Run - web_interface.run() - - finally: - robot.stop() - -if __name__ == "__main__": - main() -``` - -### Step 3: Define Skills (`skills.py`) - -```python -from dimos.skills import Skill, skill - -@skill( - description="Perform a basic action", - parameters={ - "action": "The action to perform" - } -) -class BasicSkill(Skill): - def __init__(self, robot): - self.robot = robot - - def run(self, action: str): - # Implement skill logic - return f"Performed: {action}" -``` - -## Best Practices - -1. **Module Lifecycle**: Always start DIMOS before deploying modules -2. **LCM Topics**: Use descriptive topic names with namespaces -3. **Error Handling**: Wrap module operations in try-except blocks -4. **Resource Cleanup**: Ensure proper cleanup in stop() methods -5. **Async Operations**: Use asyncio for non-blocking operations -6. **Stream Management**: Use RxPy for reactive programming patterns - -## Debugging Tips - -1. **Check Module Status**: Print module.io().result() to see connections -2. **Monitor LCM**: Use Foxglove to visualize LCM messages -3. **Log Everything**: Use dimos.utils.logging_config.setup_logger() -4. **Test Modules Independently**: Deploy and test one module at a time - -## Common Issues - -1. **"Module not started"**: Ensure start() is called after deployment -2. **"No data received"**: Check LCM transport configuration -3. **"Connection failed"**: Verify input/output types match -4. **"Cleanup errors"**: Stop modules before closing DIMOS diff --git a/dimos/robot/agilex/README_CN.md b/dimos/robot/agilex/README_CN.md deleted file mode 100644 index a8d79ebec1..0000000000 --- a/dimos/robot/agilex/README_CN.md +++ /dev/null @@ -1,465 +0,0 @@ -# DIMOS 机械臂机器人开发指南 - -本指南介绍如何创建机器人类、集成智能体(Agent)以及使用 DIMOS 模块系统和 LCM 传输。 - -## 目录 -1. [机器人类架构](#机器人类架构) -2. [模块系统与 LCM 传输](#模块系统与-lcm-传输) -3. [智能体集成](#智能体集成) -4. [完整示例](#完整示例) - -## 机器人类架构 - -### 基本机器人类结构 - -DIMOS 机器人类应遵循以下模式: - -```python -from typing import Optional, List -from dimos import core -from dimos.types.robot_capabilities import RobotCapability - -class YourRobot: - """您的机器人实现。""" - - def __init__(self, robot_capabilities: Optional[List[RobotCapability]] = None): - # 核心组件 - self.dimos = None - self.modules = {} - self.skill_library = SkillLibrary() - - # 定义能力 - self.capabilities = robot_capabilities or [ - RobotCapability.VISION, - RobotCapability.MANIPULATION, - ] - - async def start(self): - """启动机器人模块。""" - # 初始化 DIMOS,指定工作线程数 - self.dimos = core.start(2) # 需要的工作线程数 - - # 部署模块 - # ... (参见模块系统章节) - - def stop(self): - """停止所有模块并清理资源。""" - # 停止模块 - # 关闭 DIMOS - if self.dimos: - self.dimos.close() -``` - -### 关键组件说明 - -1. **初始化**:存储模块、技能和能力的引用 -2. **异步启动**:模块必须异步部署 -3. **正确清理**:在关闭 DIMOS 之前始终停止模块 - -## 模块系统与 LCM 传输 - -### 理解 DIMOS 模块 - -模块是 DIMOS 机器人的构建块。它们: -- 处理数据流(输入) -- 产生输出 -- 可以相互连接 -- 通过 LCM(轻量级通信和编组)进行通信 - -### 部署模块 - -```python -# 部署相机模块 -self.camera = self.dimos.deploy( - ZEDModule, # 模块类 - camera_id=0, # 模块参数 - resolution="HD720", - depth_mode="NEURAL", - fps=30, - publish_rate=30.0, - frame_id="camera_frame" -) -``` - -### 设置 LCM 传输 - -LCM 传输实现模块间通信: - -```python -# 启用 LCM 自动配置 -from dimos.protocol import pubsub -pubsub.lcm.autoconf() - -# 配置输出传输 -self.camera.color_image.transport = core.LCMTransport( - "/camera/color_image", # 主题名称 - Image # 消息类型 -) -self.camera.depth_image.transport = core.LCMTransport( - "/camera/depth_image", - Image -) -``` - -### 连接模块 - -将模块输出连接到输入: - -```python -# 将操作模块连接到相机输出 -self.manipulation.rgb_image.connect(self.camera.color_image) # ROS set_callback -self.manipulation.depth_image.connect(self.camera.depth_image) -self.manipulation.camera_info.connect(self.camera.camera_info) -``` - -### 模块通信模式 - -``` -┌──────────────┐ LCM ┌────────────────┐ LCM ┌──────────────┐ -│ 相机模块 │────────▶│ 操作模块 │────────▶│ 可视化输出 │ -│ │ 消息 │ │ 消息 │ │ -└──────────────┘ └────────────────┘ └──────────────┘ - ▲ ▲ - │ │ - └──────────────────────────┘ - 直接连接(RPC指令) -``` - -## 智能体集成 - -### 设置智能体与机器人 - -运行文件的智能体集成模式: - -```python -#!/usr/bin/env python3 -import asyncio -import reactivex as rx -from dimos.agents_deprecated.claude_agent import ClaudeAgent -from dimos.web.robot_web_interface import RobotWebInterface - -def main(): - # 1. 创建并启动机器人 - robot = YourRobot() - asyncio.run(robot.start()) - - # 2. 设置技能 - skills = robot.get_skills() - skills.add(YourSkill) - skills.create_instance("YourSkill", robot=robot) - - # 3. 设置响应式流 - agent_response_subject = rx.subject.Subject() - agent_response_stream = agent_response_subject.pipe(ops.share()) - - # 4. 创建 Web 界面 - web_interface = RobotWebInterface( - port=5555, - text_streams={"agent_responses": agent_response_stream}, - audio_subject=rx.subject.Subject() - ) - - # 5. 创建智能体 - agent = ClaudeAgent( - dev_name="your_agent", - input_query_stream=web_interface.query_stream, - skills=skills, - system_query="您的系统提示词", - model_name="claude-3-5-haiku-latest" - ) - - # 6. 连接智能体响应 - agent.get_response_observable().subscribe( - lambda x: agent_response_subject.on_next(x) - ) - - # 7. 运行界面 - web_interface.run() -``` - -### 关键集成点 - -1. **响应式流**:使用 RxPy 进行事件驱动通信 -2. **Web 界面**:提供用户输入/输出 -3. **智能体**:处理自然语言并执行技能 -4. **技能**:将机器人能力定义为可执行动作 - -## 完整示例 - -### 步骤 1:创建机器人类(`my_robot.py`) - -```python -import asyncio -from typing import Optional, List -from dimos import core -from dimos.hardware.camera import CameraModule -from dimos.manipulation.module import ManipulationModule -from dimos.skills.skills import SkillLibrary -from dimos.types.robot_capabilities import RobotCapability -from dimos_lcm.sensor_msgs import Image, CameraInfo -from dimos.protocol import pubsub - -class MyRobot: - def __init__(self, robot_capabilities: Optional[List[RobotCapability]] = None): - self.dimos = None - self.camera = None - self.manipulation = None - self.skill_library = SkillLibrary() - - self.capabilities = robot_capabilities or [ - RobotCapability.VISION, - RobotCapability.MANIPULATION, - ] - - async def start(self): - # 启动 DIMOS - self.dimos = core.start(2) - - # 启用 LCM - pubsub.lcm.autoconf() - - # 部署相机 - self.camera = self.dimos.deploy( - CameraModule, - camera_id=0, - fps=30 - ) - - # 配置相机 LCM - self.camera.color_image.transport = core.LCMTransport("/camera/rgb", Image) - self.camera.depth_image.transport = core.LCMTransport("/camera/depth", Image) - self.camera.camera_info.transport = core.LCMTransport("/camera/info", CameraInfo) - - # 部署操作模块 - self.manipulation = self.dimos.deploy(ManipulationModule) - - # 连接模块 - self.manipulation.rgb_image.connect(self.camera.color_image) - self.manipulation.depth_image.connect(self.camera.depth_image) - self.manipulation.camera_info.connect(self.camera.camera_info) - - # 配置操作输出 - self.manipulation.viz_image.transport = core.LCMTransport("/viz/output", Image) - - # 启动模块 - self.camera.start() - self.manipulation.start() - - await asyncio.sleep(2) # 允许初始化 - - def get_skills(self): - return self.skill_library - - def stop(self): - if self.manipulation: - self.manipulation.stop() - if self.camera: - self.camera.stop() - if self.dimos: - self.dimos.close() -``` - -### 步骤 2:创建运行脚本(`run.py`) - -```python -#!/usr/bin/env python3 -import asyncio -import os -from my_robot import MyRobot -from dimos.agents_deprecated.claude_agent import ClaudeAgent -from dimos.skills.basic import BasicSkill -from dimos.web.robot_web_interface import RobotWebInterface -import reactivex as rx -import reactivex.operators as ops - -SYSTEM_PROMPT = """您是一个有用的机器人助手。""" - -def main(): - # 检查 API 密钥 - if not os.getenv("ANTHROPIC_API_KEY"): - print("请设置 ANTHROPIC_API_KEY") - return - - # 创建机器人 - robot = MyRobot() - - try: - # 启动机器人 - asyncio.run(robot.start()) - - # 设置技能 - skills = robot.get_skills() - skills.add(BasicSkill) - skills.create_instance("BasicSkill", robot=robot) - - # 设置流 - agent_response_subject = rx.subject.Subject() - agent_response_stream = agent_response_subject.pipe(ops.share()) - - # 创建 Web 界面 - web_interface = RobotWebInterface( - port=5555, - text_streams={"agent_responses": agent_response_stream} - ) - - # 创建智能体 - agent = ClaudeAgent( - dev_name="my_agent", - input_query_stream=web_interface.query_stream, - skills=skills, - system_query=SYSTEM_PROMPT - ) - - # 连接响应 - agent.get_response_observable().subscribe( - lambda x: agent_response_subject.on_next(x) - ) - - print("机器人就绪,访问 http://localhost:5555") - - # 运行 - web_interface.run() - - finally: - robot.stop() - -if __name__ == "__main__": - main() -``` - -### 步骤 3:定义技能(`skills.py`) - -```python -from dimos.skills import Skill, skill - -@skill( - description="执行一个基本动作", - parameters={ - "action": "要执行的动作" - } -) -class BasicSkill(Skill): - def __init__(self, robot): - self.robot = robot - - def run(self, action: str): - # 实现技能逻辑 - return f"已执行:{action}" -``` - -## 最佳实践 - -1. **模块生命周期**:在部署模块之前始终先启动 DIMOS -2. **LCM 主题**:使用带命名空间的描述性主题名称 -3. **错误处理**:用 try-except 块包装模块操作 -4. **资源清理**:确保在 stop() 方法中正确清理 -5. **异步操作**:使用 asyncio 进行非阻塞操作 -6. **流管理**:使用 RxPy 进行响应式编程模式 - -## 调试技巧 - -1. **检查模块状态**:打印 module.io().result() 查看连接 -2. **监控 LCM**:使用 Foxglove 可视化 LCM 消息 -3. **记录一切**:使用 dimos.utils.logging_config.setup_logger() -4. **独立测试模块**:一次部署和测试一个模块 - -## 常见问题 - -1. **"模块未启动"**:确保在部署后调用 start() -2. **"未收到数据"**:检查 LCM 传输配置 -3. **"连接失败"**:验证输入/输出类型是否匹配 -4. **"清理错误"**:在关闭 DIMOS 之前停止模块 - -## 高级主题 - -### 自定义模块开发 - -创建自定义模块的基本结构: - -```python -from dimos.core import Module, In, Out, rpc - -class CustomModule(Module): - # 定义输入 - input_data: In[DataType] - - # 定义输出 - output_data: Out[DataType] - - def __init__(self, param1, param2, **kwargs): - super().__init__(**kwargs) - self.param1 = param1 - self.param2 = param2 - - @rpc - def start(self): - """启动模块处理。""" - self.input_data.subscribe(self._process_data) - - def _process_data(self, data): - """处理输入数据。""" - # 处理逻辑 - result = self.process(data) - # 发布输出 - self.output_data.publish(result) - - @rpc - def stop(self): - """停止模块。""" - # 清理资源 - pass -``` - -### 技能开发指南 - -技能是机器人可执行的高级动作: - -```python -from dimos.skills import Skill, skill -from typing import Optional - -@skill( - description="复杂操作技能", - parameters={ - "target": "目标对象", - "location": "目标位置" - } -) -class ComplexSkill(Skill): - def __init__(self, robot, **kwargs): - super().__init__(**kwargs) - self.robot = robot - - def run(self, target: str, location: Optional[str] = None): - """执行技能逻辑。""" - try: - # 1. 感知阶段 - object_info = self.robot.detect_object(target) - - # 2. 规划阶段 - if location: - plan = self.robot.plan_movement(object_info, location) - - # 3. 执行阶段 - result = self.robot.execute_plan(plan) - - return { - "success": True, - "message": f"成功移动 {target} 到 {location}" - } - - except Exception as e: - return { - "success": False, - "error": str(e) - } -``` - -### 性能优化 - -1. **并行处理**:使用多个工作线程处理不同模块 -2. **数据缓冲**:为高频数据流实现缓冲机制 -3. **延迟加载**:仅在需要时初始化重型模块 -4. **资源池化**:重用昂贵的资源(如神经网络模型) - -希望本指南能帮助您快速上手 DIMOS 机器人开发! diff --git a/dimos/robot/agilex/piper_arm.py b/dimos/robot/agilex/piper_arm.py deleted file mode 100644 index 29624b9a4c..0000000000 --- a/dimos/robot/agilex/piper_arm.py +++ /dev/null @@ -1,181 +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 asyncio - -# Import LCM message types -from dimos_lcm.sensor_msgs import CameraInfo - -from dimos import core -from dimos.hardware.sensors.camera.zed import ZEDModule -from dimos.manipulation.visual_servoing.manipulation_module import ManipulationModule -from dimos.msgs.sensor_msgs import Image -from dimos.protocol import pubsub -from dimos.robot.foxglove_bridge import FoxgloveBridge -from dimos.robot.robot import Robot -from dimos.skills.skills import SkillLibrary -from dimos.types.robot_capabilities import RobotCapability -from dimos.utils.logging_config import setup_logger - -logger = setup_logger() - - -class PiperArmRobot(Robot): - """Piper Arm robot with ZED camera and manipulation capabilities.""" - - def __init__(self, robot_capabilities: list[RobotCapability] | None = None) -> None: - super().__init__() - self.dimos = None - self.stereo_camera = None - self.manipulation_interface = None - self.skill_library = SkillLibrary() # type: ignore[assignment] - - # Initialize capabilities - self.capabilities = robot_capabilities or [ - RobotCapability.VISION, - RobotCapability.MANIPULATION, - ] - - async def start(self) -> None: - """Start the robot modules.""" - # Start Dimos - self.dimos = core.start(2) # type: ignore[assignment] # Need 2 workers for ZED and manipulation modules - self.foxglove_bridge = FoxgloveBridge() - - # Enable LCM auto-configuration - pubsub.lcm.autoconf() # type: ignore[attr-defined] - - # Deploy ZED module - logger.info("Deploying ZED module...") - self.stereo_camera = self.dimos.deploy( # type: ignore[attr-defined] - ZEDModule, - camera_id=0, - resolution="HD720", - depth_mode="NEURAL", - fps=30, - enable_tracking=False, # We don't need tracking for manipulation - publish_rate=30.0, - frame_id="zed_camera", - ) - - # Configure ZED LCM transports - self.stereo_camera.color_image.transport = core.LCMTransport("/zed/color_image", Image) # type: ignore[attr-defined] - self.stereo_camera.depth_image.transport = core.LCMTransport("/zed/depth_image", Image) # type: ignore[attr-defined] - self.stereo_camera.camera_info.transport = core.LCMTransport("/zed/camera_info", CameraInfo) # type: ignore[attr-defined] - - # Deploy manipulation module - logger.info("Deploying manipulation module...") - self.manipulation_interface = self.dimos.deploy(ManipulationModule) # type: ignore[attr-defined] - - # Connect manipulation inputs to ZED outputs - self.manipulation_interface.rgb_image.connect(self.stereo_camera.color_image) # type: ignore[attr-defined] - self.manipulation_interface.depth_image.connect(self.stereo_camera.depth_image) # type: ignore[attr-defined] - self.manipulation_interface.camera_info.connect(self.stereo_camera.camera_info) # type: ignore[attr-defined] - - # Configure manipulation output - self.manipulation_interface.viz_image.transport = core.LCMTransport( # type: ignore[attr-defined] - "/manipulation/viz", Image - ) - - # Print module info - logger.info("Modules configured:") - print("\nZED Module:") - print(self.stereo_camera.io()) # type: ignore[attr-defined] - print("\nManipulation Module:") - print(self.manipulation_interface.io()) # type: ignore[attr-defined] - - # Start modules - logger.info("Starting modules...") - self.foxglove_bridge.start() - self.stereo_camera.start() # type: ignore[attr-defined] - self.manipulation_interface.start() # type: ignore[attr-defined] - - # Give modules time to initialize - await asyncio.sleep(2) - - logger.info("PiperArmRobot initialized and started") - - def pick_and_place( # type: ignore[no-untyped-def] - self, pick_x: int, pick_y: int, place_x: int | None = None, place_y: int | None = None - ): - """Execute pick and place task. - - Args: - pick_x: X coordinate for pick location - pick_y: Y coordinate for pick location - place_x: X coordinate for place location (optional) - place_y: Y coordinate for place location (optional) - - Returns: - Result of the pick and place operation - """ - if self.manipulation_interface: - return self.manipulation_interface.pick_and_place(pick_x, pick_y, place_x, place_y) - else: - logger.error("Manipulation module not initialized") - return False - - def handle_keyboard_command(self, key: str): # type: ignore[no-untyped-def] - """Pass keyboard commands to manipulation module. - - Args: - key: Keyboard key pressed - - Returns: - Action taken or None - """ - if self.manipulation_interface: - return self.manipulation_interface.handle_keyboard_command(key) - else: - logger.error("Manipulation module not initialized") - return None - - def stop(self) -> None: - """Stop all modules and clean up.""" - logger.info("Stopping PiperArmRobot...") - - try: - if self.manipulation_interface: - self.manipulation_interface.stop() - - if self.stereo_camera: - self.stereo_camera.stop() - except Exception as e: - logger.warning(f"Error stopping modules: {e}") - - # Close dimos last to ensure workers are available for cleanup - if self.dimos: - self.dimos.close() - - logger.info("PiperArmRobot stopped") - - -async def run_piper_arm() -> None: - """Run the Piper Arm robot.""" - robot = PiperArmRobot() # type: ignore[abstract] - - await robot.start() - - # Keep the robot running - try: - while True: - await asyncio.sleep(1) - except KeyboardInterrupt: - logger.info("Keyboard interrupt received") - finally: - await robot.stop() # type: ignore[func-returns-value] - - -if __name__ == "__main__": - asyncio.run(run_piper_arm()) diff --git a/dimos/robot/agilex/run.py b/dimos/robot/agilex/run.py deleted file mode 100644 index 64e0ae5470..0000000000 --- a/dimos/robot/agilex/run.py +++ /dev/null @@ -1,190 +0,0 @@ -#!/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. - -""" -Run script for Piper Arm robot with Claude agent integration. -Provides manipulation capabilities with natural language interface. -""" - -import asyncio -import os -import sys - -from dotenv import load_dotenv -import reactivex as rx -import reactivex.operators as ops - -from dimos.agents_deprecated.claude_agent import ClaudeAgent -from dimos.robot.agilex.piper_arm import PiperArmRobot -from dimos.skills.kill_skill import KillSkill -from dimos.skills.manipulation.pick_and_place import PickAndPlace -from dimos.stream.audio.pipelines import stt, tts -from dimos.utils.logging_config import setup_logger -from dimos.web.robot_web_interface import RobotWebInterface - -logger = setup_logger() - -# Load environment variables -load_dotenv() - -# System prompt for the Piper Arm manipulation agent -SYSTEM_PROMPT = """You are an intelligent robotic assistant controlling a Piper Arm robot with advanced manipulation capabilities. Your primary role is to help users with pick and place tasks using natural language understanding. - -## Your Capabilities: -1. **Visual Perception**: You have access to a ZED stereo camera that provides RGB and depth information -2. **Object Manipulation**: You can pick up and place objects using a 6-DOF robotic arm with a gripper -3. **Language Understanding**: You use the Qwen vision-language model to identify objects and locations from natural language descriptions - -## Available Skills: -- **PickAndPlace**: Execute pick and place operations based on object and location descriptions - - Pick only: "Pick up the red mug" - - Pick and place: "Move the book to the shelf" -- **KillSkill**: Stop any currently running skill - -## Guidelines: -1. **Safety First**: Always ensure safe operation. If unsure about an object's graspability or a placement location's stability, ask for clarification -2. **Clear Communication**: Explain what you're doing and ask for confirmation when needed -3. **Error Handling**: If a task fails, explain why and suggest alternatives -4. **Precision**: When users give specific object descriptions, use them exactly as provided to the vision model - -## Interaction Examples: -- User: "Pick up the coffee mug" - You: "I'll pick up the coffee mug for you." [Execute PickAndPlace with object_query="coffee mug"] - -- User: "Put the toy on the table" - You: "I'll place the toy on the table." [Execute PickAndPlace with object_query="toy", target_query="on the table"] - -- User: "What do you see?" - -Remember: You're here to assist with manipulation tasks. Be helpful, precise, and always prioritize safe operation of the robot.""" - - -def main(): # type: ignore[no-untyped-def] - """Main entry point.""" - print("\n" + "=" * 60) - print("Piper Arm Robot with Claude Agent") - print("=" * 60) - print("\nThis system integrates:") - print(" - Piper Arm 6-DOF robot") - print(" - ZED stereo camera") - print(" - Claude AI for natural language understanding") - print(" - Qwen VLM for visual object detection") - print(" - Web interface with text and voice input") - print(" - Foxglove visualization via LCM") - print("\nStarting system...\n") - - # Check for API key - if not os.getenv("ANTHROPIC_API_KEY"): - print("WARNING: ANTHROPIC_API_KEY not found in environment") - print("Please set your API key in .env file or environment") - sys.exit(1) - - logger.info("Starting Piper Arm Robot with Agent") - - # Create robot instance - robot = PiperArmRobot() # type: ignore[abstract] - - try: - # Start the robot (this is async, so we need asyncio.run) - logger.info("Initializing robot...") - asyncio.run(robot.start()) - logger.info("Robot initialized successfully") - - # Set up skill library - skills = robot.get_skills() # type: ignore[no-untyped-call] - skills.add(PickAndPlace) - skills.add(KillSkill) - - # Create skill instances - skills.create_instance("PickAndPlace", robot=robot) - skills.create_instance("KillSkill", robot=robot, skill_library=skills) - - logger.info(f"Skills registered: {[skill.__name__ for skill in skills.get_class_skills()]}") - - # Set up streams for agent and web interface - agent_response_subject = rx.subject.Subject() # type: ignore[var-annotated] - agent_response_stream = agent_response_subject.pipe(ops.share()) - audio_subject = rx.subject.Subject() # type: ignore[var-annotated] - - # Set up streams for web interface - streams = {} # type: ignore[var-annotated] - - text_streams = { - "agent_responses": agent_response_stream, - } - - # Create web interface first (needed for agent) - try: - web_interface = RobotWebInterface( - port=5555, text_streams=text_streams, audio_subject=audio_subject, **streams - ) - logger.info("Web interface created successfully") - except Exception as e: - logger.error(f"Failed to create web interface: {e}") - raise - - # Set up speech-to-text - stt_node = stt() # type: ignore[no-untyped-call] - stt_node.consume_audio(audio_subject.pipe(ops.share())) - - # Create Claude agent - agent = ClaudeAgent( - dev_name="piper_arm_agent", - input_query_stream=web_interface.query_stream, # Use text input from web interface - # input_query_stream=stt_node.emit_text(), # Uncomment to use voice input - skills=skills, - system_query=SYSTEM_PROMPT, - model_name="claude-3-5-haiku-latest", - thinking_budget_tokens=0, - max_output_tokens_per_request=4096, - ) - - # Subscribe to agent responses - agent.get_response_observable().subscribe(lambda x: agent_response_subject.on_next(x)) - - # Set up text-to-speech for agent responses - tts_node = tts() # type: ignore[no-untyped-call] - tts_node.consume_text(agent.get_response_observable()) - - logger.info("=" * 60) - logger.info("Piper Arm Agent Ready!") - logger.info("Web interface available at: http://localhost:5555") - logger.info("Foxglove visualization available at: ws://localhost:8765") - logger.info("You can:") - logger.info(" - Type commands in the web interface") - logger.info(" - Use voice commands") - logger.info(" - Ask the robot to pick up objects") - logger.info(" - Ask the robot to move objects to locations") - logger.info("=" * 60) - - # Run web interface (this blocks) - web_interface.run() - - except KeyboardInterrupt: - logger.info("Keyboard interrupt received") - except Exception as e: - logger.error(f"Error running robot: {e}") - import traceback - - traceback.print_exc() - finally: - logger.info("Shutting down...") - # Stop the robot (this is also async) - robot.stop() - logger.info("Robot stopped") - - -if __name__ == "__main__": - main() # type: ignore[no-untyped-call] diff --git a/dimos/robot/all_blueprints.py b/dimos/robot/all_blueprints.py index 05658e11c2..6dfa077498 100644 --- a/dimos/robot/all_blueprints.py +++ b/dimos/robot/all_blueprints.py @@ -49,9 +49,10 @@ # Demo blueprints "demo-camera": "dimos.hardware.sensors.camera.module:demo_camera", "demo-osm": "dimos.mapping.osm.demo_osm:demo_osm", - "demo-skill": "dimos.agents.skills.demo_skill:demo_skill", - "demo-gps-nav": "dimos.agents.skills.demo_gps_nav:demo_gps_nav_skill", - "demo-google-maps-skill": "dimos.agents.skills.demo_google_maps_skill:demo_google_maps_skill", + "demo-skill": "dimos.agents2.skills.demo_skill:demo_skill", + "demo-gps-nav": "dimos.agents2.skills.demo_gps_nav:demo_gps_nav_skill", + "demo-google-maps-skill": "dimos.agents2.skills.demo_google_maps_skill:demo_google_maps_skill", + "demo-object-scene-registration": "dimos.perception.demo_object_scene_registration:demo_object_scene_registration", "demo-remapping": "dimos.robot.unitree_webrtc.demo_remapping:remapping", "demo-remapping-transport": "dimos.robot.unitree_webrtc.demo_remapping:remapping_and_transport", "demo-error-on-name-conflicts": "dimos.robot.unitree_webrtc.demo_error_on_name_conflicts:blueprint", From 0ef413225b2451d659f4536f2f2b6b4b3ab3597a Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Thu, 8 Jan 2026 13:35:25 -0800 Subject: [PATCH 02/19] one last mypy fix --- dimos/perception/detection/person_tracker.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dimos/perception/detection/person_tracker.py b/dimos/perception/detection/person_tracker.py index ad37901408..147b5aa358 100644 --- a/dimos/perception/detection/person_tracker.py +++ b/dimos/perception/detection/person_tracker.py @@ -85,7 +85,7 @@ def detections_stream(self) -> Observable[ImageDetections2D[Any]]: ).pipe( ops.map( lambda pair: ImageDetections2D.from_ros_detection2d_array( - pair[0], + pair[0], # type: ignore[index, arg-type] pair[1], # type: ignore[index, arg-type] ) ) From 881ccff2ae320345716d6dcec06d038020ead7d3 Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Thu, 8 Jan 2026 13:48:30 -0800 Subject: [PATCH 03/19] added default to imagedetection2d to not set off mypy --- dimos/models/vl/base.py | 2 +- dimos/models/vl/moondream.py | 2 +- dimos/models/vl/moondream_hosted.py | 2 +- .../detection/detectors/person/yolo.py | 6 +- dimos/perception/detection/detectors/types.py | 3 +- dimos/perception/detection/detectors/yolo.py | 4 +- dimos/perception/detection/module2D.py | 8 +- dimos/perception/detection/module3D.py | 8 +- dimos/perception/detection/person_tracker.py | 9 +- dimos/perception/detection/reid/module.py | 8 +- dimos/perception/detection/reid/type.py | 3 +- .../type/detection2d/imageDetections2D.py | 2 +- .../type/detection3d/imageDetections3DPC.py | 165 +----------------- 13 files changed, 26 insertions(+), 196 deletions(-) diff --git a/dimos/models/vl/base.py b/dimos/models/vl/base.py index b2bd10480f..93caba4de7 100644 --- a/dimos/models/vl/base.py +++ b/dimos/models/vl/base.py @@ -261,7 +261,7 @@ def query_detections( Only respond with JSON, no other text. """ - image_detections: ImageDetections2D[Detection2DBBox] = ImageDetections2D(image) + image_detections = ImageDetections2D(image) # Get scaled image and scale factor for coordinate rescaling scaled_image, scale = self._prepare_image(image) diff --git a/dimos/models/vl/moondream.py b/dimos/models/vl/moondream.py index 60a38c0df8..f31611e867 100644 --- a/dimos/models/vl/moondream.py +++ b/dimos/models/vl/moondream.py @@ -144,7 +144,7 @@ def query_detections( result = self._model.detect(pil_image, query, settings=settings) # Convert to ImageDetections2D - image_detections: ImageDetections2D[Detection2DBBox] = ImageDetections2D(image) + image_detections = ImageDetections2D(image) # Get image dimensions for converting normalized coords to pixels height, width = image.height, image.width diff --git a/dimos/models/vl/moondream_hosted.py b/dimos/models/vl/moondream_hosted.py index 093c55441f..c28a12363f 100644 --- a/dimos/models/vl/moondream_hosted.py +++ b/dimos/models/vl/moondream_hosted.py @@ -74,7 +74,7 @@ def query_detections(self, image: Image, query: str, **kwargs) -> ImageDetection objects = result.get("objects", []) # Convert to ImageDetections2D - image_detections: ImageDetections2D[Detection2DBBox] = ImageDetections2D(image) + image_detections = ImageDetections2D(image) height, width = image.height, image.width for track_id, obj in enumerate(objects): diff --git a/dimos/perception/detection/detectors/person/yolo.py b/dimos/perception/detection/detectors/person/yolo.py index 75d9a47921..519f45f2f6 100644 --- a/dimos/perception/detection/detectors/person/yolo.py +++ b/dimos/perception/detection/detectors/person/yolo.py @@ -12,15 +12,13 @@ # See the License for the specific language governing permissions and # limitations under the License. -from typing import Any - from ultralytics import YOLO # type: ignore[attr-defined, import-not-found] from dimos.msgs.sensor_msgs import Image from dimos.perception.detection.detectors.types import Detector from dimos.perception.detection.type import ImageDetections2D from dimos.utils.data import get_data -from dimos.utils.gpu_utils import is_cuda_available # type: ignore[attr-defined] +from dimos.utils.gpu_utils import is_cuda_available from dimos.utils.logging_config import setup_logger logger = setup_logger() @@ -48,7 +46,7 @@ def __init__( self.device = "cpu" logger.info("Using CPU for YOLO person detector") - def process_image(self, image: Image) -> "ImageDetections2D[Any]": # type: ignore[override] + def process_image(self, image: Image) -> ImageDetections2D: """Process image and return detection results. Args: diff --git a/dimos/perception/detection/detectors/types.py b/dimos/perception/detection/detectors/types.py index 5c81feccc2..e85c5ae18e 100644 --- a/dimos/perception/detection/detectors/types.py +++ b/dimos/perception/detection/detectors/types.py @@ -13,7 +13,6 @@ # limitations under the License. from abc import ABC, abstractmethod -from typing import Any from dimos.msgs.sensor_msgs import Image from dimos.perception.detection.type import ImageDetections2D @@ -21,4 +20,4 @@ class Detector(ABC): @abstractmethod - def process_image(self, image: Image) -> ImageDetections2D[Any]: ... + def process_image(self, image: Image) -> ImageDetections2D: ... diff --git a/dimos/perception/detection/detectors/yolo.py b/dimos/perception/detection/detectors/yolo.py index 4a7ee1ff06..c9a65a120e 100644 --- a/dimos/perception/detection/detectors/yolo.py +++ b/dimos/perception/detection/detectors/yolo.py @@ -12,8 +12,6 @@ # See the License for the specific language governing permissions and # limitations under the License. -from typing import Any - from ultralytics import YOLO # type: ignore[attr-defined, import-not-found] from dimos.msgs.sensor_msgs import Image @@ -49,7 +47,7 @@ def __init__( self.device = "cpu" logger.debug("Using CPU for YOLO 2d detector") - def process_image(self, image: Image) -> ImageDetections2D[Any]: + def process_image(self, image: Image) -> ImageDetections2D: """ Process an image and return detection results. diff --git a/dimos/perception/detection/module2D.py b/dimos/perception/detection/module2D.py index 5eb479e03e..cfca3b2192 100644 --- a/dimos/perception/detection/module2D.py +++ b/dimos/perception/detection/module2D.py @@ -73,7 +73,7 @@ def __init__(self, *args, **kwargs) -> None: # type: ignore[no-untyped-def] self.vlm_detections_subject = Subject() # type: ignore[var-annotated] self.previous_detection_count = 0 - def process_image_frame(self, image: Image) -> ImageDetections2D[Any]: + def process_image_frame(self, image: Image) -> ImageDetections2D: imageDetections = self.detector.process_image(image) if not self.config.filter: return imageDetections @@ -88,10 +88,10 @@ def sharp_image_stream(self) -> Observable[Image]: ) @simple_mcache - def detection_stream_2d(self) -> Observable[ImageDetections2D[Any]]: + def detection_stream_2d(self) -> Observable[ImageDetections2D]: return backpressure(self.sharp_image_stream().pipe(ops.map(self.process_image_frame))) - def track(self, detections: ImageDetections2D[Any]) -> None: + def track(self, detections: ImageDetections2D) -> None: sensor_frame = self.tf.get("sensor", "camera_optical", detections.image.ts, 5.0) if not sensor_frame: @@ -144,7 +144,7 @@ def start(self) -> None: lambda det: self.annotations.publish(det.to_foxglove_annotations()) ) - def publish_cropped_images(detections: ImageDetections2D[Any]) -> None: + def publish_cropped_images(detections: ImageDetections2D) -> None: for index, detection in enumerate(detections[:3]): image_topic = getattr(self, "detected_image_" + str(index)) image_topic.publish(detection.cropped_image()) diff --git a/dimos/perception/detection/module3D.py b/dimos/perception/detection/module3D.py index 1804e0e9cd..037376f995 100644 --- a/dimos/perception/detection/module3D.py +++ b/dimos/perception/detection/module3D.py @@ -13,8 +13,6 @@ # limitations under the License. -from typing import Any - from dimos_lcm.foxglove_msgs.ImageAnnotations import ( ImageAnnotations, ) @@ -61,7 +59,7 @@ class Detection3DModule(Detection2DModule): def process_frame( self, - detections: ImageDetections2D[Any], + detections: ImageDetections2D, pointcloud: PointCloud2, transform: Transform, ) -> ImageDetections3DPC: @@ -140,7 +138,7 @@ def nav_vlm(self, question: str) -> str: if isinstance(result, str) or not result or not len(result): return None # type: ignore[return-value] - detections: ImageDetections2D[Any] = result + detections: ImageDetections2D = result print(detections) if not len(detections): @@ -150,7 +148,7 @@ def nav_vlm(self, question: str) -> str: pc = self.pointcloud.get_next() transform = self.tf.get("camera_optical", pc.frame_id, detections.image.ts, 5.0) - detections3d = self.process_frame(detections, pc, transform) # type: ignore[arg-type] + detections3d = self.process_frame(detections, pc, transform) if len(detections3d): return detections3d[0].pose # type: ignore[no-any-return] diff --git a/dimos/perception/detection/person_tracker.py b/dimos/perception/detection/person_tracker.py index 147b5aa358..6212080858 100644 --- a/dimos/perception/detection/person_tracker.py +++ b/dimos/perception/detection/person_tracker.py @@ -73,7 +73,7 @@ def center_to_3d( # Transformation: x_link = z_optical, y_link = -x_optical, z_link = -y_optical return Vector3(z_optical, -x_optical, -y_optical) - def detections_stream(self) -> Observable[ImageDetections2D[Any]]: + def detections_stream(self) -> Observable[ImageDetections2D]: return backpressure( align_timestamped( self.color_image.pure_observable(), @@ -84,9 +84,8 @@ def detections_stream(self) -> Observable[ImageDetections2D[Any]]: buffer_size=2.0, ).pipe( ops.map( - lambda pair: ImageDetections2D.from_ros_detection2d_array( - pair[0], # type: ignore[index, arg-type] - pair[1], # type: ignore[index, arg-type] + lambda pair: ImageDetections2D.from_ros_detection2d_array( # type: ignore[misc] + *pair ) ) ) @@ -100,7 +99,7 @@ def start(self) -> None: def stop(self) -> None: super().stop() - def track(self, detections2D: ImageDetections2D[Any]) -> None: + def track(self, detections2D: ImageDetections2D) -> None: if len(detections2D) == 0: return diff --git a/dimos/perception/detection/reid/module.py b/dimos/perception/detection/reid/module.py index 8d0acaebec..4e239da39a 100644 --- a/dimos/perception/detection/reid/module.py +++ b/dimos/perception/detection/reid/module.py @@ -12,8 +12,6 @@ # See the License for the specific language governing permissions and # limitations under the License. -from typing import Any - from dimos_lcm.foxglove_msgs.ImageAnnotations import ( ImageAnnotations, TextAnnotation, @@ -58,7 +56,7 @@ def __init__(self, idsystem: IDSystem | None = None, **kwargs) -> None: # type: self.idsystem = idsystem - def detections_stream(self) -> Observable[ImageDetections2D[Any]]: + def detections_stream(self) -> Observable[ImageDetections2D]: return backpressure( align_timestamped( self.image.pure_observable(), @@ -67,7 +65,7 @@ def detections_stream(self) -> Observable[ImageDetections2D[Any]]: ), match_tolerance=0.0, buffer_size=2.0, - ).pipe(ops.map(lambda pair: ImageDetections2D.from_ros_detection2d_array(*pair))) # type: ignore[misc, arg-type] + ).pipe(ops.map(lambda pair: ImageDetections2D.from_ros_detection2d_array(*pair))) # type: ignore[misc] ) @rpc @@ -78,7 +76,7 @@ def start(self) -> None: def stop(self) -> None: super().stop() - def ingress(self, imageDetections: ImageDetections2D[Any]) -> None: + def ingress(self, imageDetections: ImageDetections2D) -> None: text_annotations = [] for detection in imageDetections: diff --git a/dimos/perception/detection/reid/type.py b/dimos/perception/detection/reid/type.py index 62c7449578..28ea719f81 100644 --- a/dimos/perception/detection/reid/type.py +++ b/dimos/perception/detection/reid/type.py @@ -15,7 +15,6 @@ from __future__ import annotations from abc import ABC, abstractmethod -from typing import Any from dimos.perception.detection.type import Detection2DBBox, ImageDetections2D @@ -23,7 +22,7 @@ class IDSystem(ABC): """Abstract base class for ID assignment systems.""" - def register_detections(self, detections: ImageDetections2D[Any]) -> None: + def register_detections(self, detections: ImageDetections2D) -> None: """Register multiple detections.""" for detection in detections.detections: if isinstance(detection, Detection2DBBox): diff --git a/dimos/perception/detection/type/detection2d/imageDetections2D.py b/dimos/perception/detection/type/detection2d/imageDetections2D.py index aa57b45aa7..d07663f34e 100644 --- a/dimos/perception/detection/type/detection2d/imageDetections2D.py +++ b/dimos/perception/detection/type/detection2d/imageDetections2D.py @@ -32,7 +32,7 @@ from dimos.msgs.vision_msgs import Detection2DArray -T2D = TypeVar("T2D", bound=Detection2D) +T2D = TypeVar("T2D", bound=Detection2D, default=Detection2DBBox) class ImageDetections2D(ImageDetections[T2D], Generic[T2D]): diff --git a/dimos/perception/detection/type/detection3d/imageDetections3DPC.py b/dimos/perception/detection/type/detection3d/imageDetections3DPC.py index 2277d84634..0fbb1a7c59 100644 --- a/dimos/perception/detection/type/detection3d/imageDetections3DPC.py +++ b/dimos/perception/detection/type/detection3d/imageDetections3DPC.py @@ -14,174 +14,15 @@ from __future__ import annotations -from typing import TYPE_CHECKING +from lcm_msgs.foxglove_msgs import SceneUpdate # type: ignore[import-not-found] -from dimos_lcm.foxglove_msgs import SceneUpdate -import numpy as np -import open3d as o3d # type: ignore[import-untyped] - -try: - from geometry_msgs.msg import ( # type: ignore[attr-defined] - Point as ROSPoint, - Pose as ROSPose, - Quaternion as ROSQuaternion, - Vector3 as ROSVector3, - ) - from std_msgs.msg import Header as ROSHeader # type: ignore[attr-defined] - from vision_msgs.msg import ( # type: ignore[attr-defined, import-untyped] - BoundingBox3D as ROSBoundingBox3D, - Detection3D as ROSDetection3D, - Detection3DArray as ROSDetection3DArray, - ObjectHypothesisWithPose as ROSObjectHypothesisWithPose, - ) -except ImportError: - ROSPoint = None # type: ignore[assignment, misc] - ROSPose = None # type: ignore[assignment, misc] - ROSQuaternion = None # type: ignore[assignment, misc] - ROSVector3 = None # type: ignore[assignment, misc] - ROSHeader = None # type: ignore[assignment, misc] - ROSBoundingBox3D = None # type: ignore[assignment, misc] - ROSDetection3D = None # type: ignore[assignment, misc] - ROSDetection3DArray = None # type: ignore[assignment, misc] - ROSObjectHypothesisWithPose = None # type: ignore[assignment, misc] - -from dimos.msgs.sensor_msgs import PointCloud2 +from dimos.perception.detection.type.detection3d.pointcloud import Detection3DPC from dimos.perception.detection.type.imageDetections import ImageDetections -if TYPE_CHECKING: - from dimos.perception.detection.type.detection3d.pointcloud import Detection3DPC - -class ImageDetections3DPC(ImageDetections["Detection3DPC"]): +class ImageDetections3DPC(ImageDetections[Detection3DPC]): """Specialized class for 3D detections in an image.""" - def get_aggregated_objects_pointcloud(self) -> PointCloud2 | None: - """Aggregate all detection pointclouds into a single colored pointcloud. - - Each detection's points are colored based on a consistent color derived - from its track_id, similar to the 2D overlay visualization. - - Returns: - Combined PointCloud2 with all detection points colored by object, - or None if no detections. - """ - if not self.detections: - return None - - all_points = [] - all_colors = [] - - for i, det in enumerate(self.detections): - points, original_colors = det.pointcloud.as_numpy() - if len(points) == 0: - continue - - track_id = det.track_id if det.track_id >= 0 else i - np.random.seed(abs(track_id)) - track_color = np.random.randint(50, 255, 3) / 255.0 - - if original_colors is not None: - blended_colors = 0.6 * original_colors + 0.4 * track_color - blended_colors = np.clip(blended_colors, 0.0, 1.0) - else: - blended_colors = np.tile(track_color, (len(points), 1)) - - all_points.append(points) - all_colors.append(blended_colors) - - if not all_points: - return None - - # Combine all points and colors - combined_points = np.vstack(all_points) - combined_colors = np.vstack(all_colors) - - # Get frame_id and timestamp from first detection - frame_id = self.detections[0].frame_id - ts = self.detections[0].ts - - # Create combined pointcloud - combined_pc = PointCloud2.from_numpy( - combined_points, - frame_id=frame_id, - timestamp=ts, - ) - - combined_pc.pointcloud.colors = o3d.utility.Vector3dVector(combined_colors) - - return combined_pc - - def to_ros_detection3d_array(self) -> ROSDetection3DArray: - """Convert ImageDetections3DPC to ROS Detection3DArray message. - - Returns: - Detection3DArray ROS message containing all 3D detections - """ - detection_array = ROSDetection3DArray() - - # Set header from image or first detection - detection_array.header = ROSHeader() - if self.detections: - detection_array.header.frame_id = self.detections[0].frame_id or "" - ts = self.detections[0].ts - detection_array.header.stamp.sec = int(ts) - detection_array.header.stamp.nanosec = int((ts % 1) * 1_000_000_000) - elif self.image: - detection_array.header.frame_id = self.image.frame_id or "" - if self.image.ts: - detection_array.header.stamp.sec = int(self.image.ts) - detection_array.header.stamp.nanosec = int((self.image.ts % 1) * 1_000_000_000) - - # Convert each detection - for det in self.detections: - ros_detection = ROSDetection3D() - - # Set header - ros_detection.header = ROSHeader() - ros_detection.header.frame_id = det.frame_id or "" - ros_detection.header.stamp.sec = int(det.ts) - ros_detection.header.stamp.nanosec = int((det.ts % 1) * 1_000_000_000) - - # Set bounding box - ros_detection.bbox = ROSBoundingBox3D() - ros_detection.bbox.center = ROSPose() - ros_detection.bbox.center.position = ROSPoint() - - # Get center from pointcloud - center = det.center - ros_detection.bbox.center.position.x = float(center.x) - ros_detection.bbox.center.position.y = float(center.y) - ros_detection.bbox.center.position.z = float(center.z) - - # Identity orientation for axis-aligned bbox - ros_detection.bbox.center.orientation = ROSQuaternion() - ros_detection.bbox.center.orientation.x = 0.0 - ros_detection.bbox.center.orientation.y = 0.0 - ros_detection.bbox.center.orientation.z = 0.0 - ros_detection.bbox.center.orientation.w = 1.0 - - # Set size from bounding box dimensions - dims = det.get_bounding_box_dimensions() - ros_detection.bbox.size = ROSVector3() - ros_detection.bbox.size.x = float(dims[0]) - ros_detection.bbox.size.y = float(dims[1]) - ros_detection.bbox.size.z = float(dims[2]) - - # Add class hypothesis - if det.name: - hypothesis = ROSObjectHypothesisWithPose() - hypothesis.hypothesis.class_id = det.name - hypothesis.hypothesis.score = float(det.confidence) - ros_detection.results.append(hypothesis) - - # Set tracking ID - if det.track_id >= 0: - ros_detection.id = str(det.track_id) - - detection_array.detections.append(ros_detection) - - return detection_array - def to_foxglove_scene_update(self) -> SceneUpdate: """Convert all detections to a Foxglove SceneUpdate message. From dd4704cbdae45c9f94077dc51b94b791688f0b22 Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Thu, 8 Jan 2026 14:15:07 -0800 Subject: [PATCH 04/19] fixed bug and default to open vocab for detection --- .../demo_object_scene_registration.py | 2 +- dimos/perception/detection/objectDB.py | 2 +- .../type/detection2d/imageDetections2D.py | 4 ++-- .../detection/type/detection3d/object.py | 21 +++++-------------- 4 files changed, 9 insertions(+), 20 deletions(-) diff --git a/dimos/perception/demo_object_scene_registration.py b/dimos/perception/demo_object_scene_registration.py index 96b25c54f1..fe9c3100bb 100644 --- a/dimos/perception/demo_object_scene_registration.py +++ b/dimos/perception/demo_object_scene_registration.py @@ -34,7 +34,7 @@ demo_object_scene_registration = autoconnect( camera_module, - object_scene_registration_module(target_frame="world", prompt_mode=YoloePromptMode.PROMPT), + object_scene_registration_module(target_frame="world", prompt_mode=YoloePromptMode.LRPC), foxglove_bridge(), human_input(), llm_agent(), diff --git a/dimos/perception/detection/objectDB.py b/dimos/perception/detection/objectDB.py index 850ee367f0..362a543f30 100644 --- a/dimos/perception/detection/objectDB.py +++ b/dimos/perception/detection/objectDB.py @@ -41,7 +41,7 @@ class ObjectDB: def __init__( self, - distance_threshold: float = 0.15, + distance_threshold: float = 0.1, min_detections_for_permanent: int = 6, pending_ttl_s: float = 5.0, track_id_ttl_s: float = 2.0, diff --git a/dimos/perception/detection/type/detection2d/imageDetections2D.py b/dimos/perception/detection/type/detection2d/imageDetections2D.py index d07663f34e..2cab0d4314 100644 --- a/dimos/perception/detection/type/detection2d/imageDetections2D.py +++ b/dimos/perception/detection/type/detection2d/imageDetections2D.py @@ -14,7 +14,7 @@ from __future__ import annotations -from typing import TYPE_CHECKING, Generic +from typing import TYPE_CHECKING, Any, Generic import cv2 import numpy as np @@ -41,7 +41,7 @@ def from_ros_detection2d_array( # type: ignore[no-untyped-def] cls, image: Image, ros_detections: Detection2DArray, - **kwargs, # type: ignore[name-defined] + **kwargs, ) -> ImageDetections2D[Detection2DBBox]: """Convert from ROS Detection2DArray message to ImageDetections2D object.""" detections: list[Detection2DBBox] = [] diff --git a/dimos/perception/detection/type/detection3d/object.py b/dimos/perception/detection/type/detection3d/object.py index ce6e9df915..b4c15209c8 100644 --- a/dimos/perception/detection/type/detection3d/object.py +++ b/dimos/perception/detection/type/detection3d/object.py @@ -21,7 +21,6 @@ import cv2 from dimos_lcm.geometry_msgs import Pose -from dimos_lcm.vision_msgs import ObjectHypothesis, ObjectHypothesisWithPose import numpy as np import open3d as o3d # type: ignore[import-untyped] @@ -110,27 +109,17 @@ def scene_entity_label(self) -> str: def to_ros_detection3d(self) -> ROSDetection3D: """Convert to ROS Detection3D message.""" - msg = ROSDetection3D() - msg.header = Header(self.ts, self.frame_id) - msg.results = [ - ObjectHypothesisWithPose( - hypothesis=ObjectHypothesis( - class_id=str(self.class_id), - score=self.confidence, - ) - ) - ] - obb = self.get_oriented_bounding_box() # type: ignore[no-untyped-call] - obb_center = obb.center - obb_extent = obb.extent orientation = Quaternion.from_rotation_matrix(obb.R) + msg = ROSDetection3D() + msg.header = Header(self.ts, self.frame_id) + msg.id = str(self.track_id) msg.bbox.center = Pose( - position=Vector3(obb_center[0], obb_center[1], obb_center[2]), + position=Vector3(obb.center[0], obb.center[1], obb.center[2]), orientation=orientation, ) - msg.bbox.size = Vector3(obb_extent[0], obb_extent[1], obb_extent[2]) + msg.bbox.size = Vector3(obb.extent[0], obb.extent[1], obb.extent[2]) return msg From 0a4c9c8bdb835d8c328c8098c8ab74c5ff991dec Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Thu, 8 Jan 2026 14:25:55 -0800 Subject: [PATCH 05/19] mypy fixes --- dimos/perception/detection/person_tracker.py | 2 +- dimos/perception/detection/reid/module.py | 2 +- .../detection/type/detection2d/imageDetections2D.py | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/dimos/perception/detection/person_tracker.py b/dimos/perception/detection/person_tracker.py index 6212080858..d4f3ae123a 100644 --- a/dimos/perception/detection/person_tracker.py +++ b/dimos/perception/detection/person_tracker.py @@ -84,7 +84,7 @@ def detections_stream(self) -> Observable[ImageDetections2D]: buffer_size=2.0, ).pipe( ops.map( - lambda pair: ImageDetections2D.from_ros_detection2d_array( # type: ignore[misc] + lambda pair: ImageDetections2D.from_ros_detection2d_array( # type: ignore[misc, arg-type] *pair ) ) diff --git a/dimos/perception/detection/reid/module.py b/dimos/perception/detection/reid/module.py index 4e239da39a..f3f2a5a126 100644 --- a/dimos/perception/detection/reid/module.py +++ b/dimos/perception/detection/reid/module.py @@ -65,7 +65,7 @@ def detections_stream(self) -> Observable[ImageDetections2D]: ), match_tolerance=0.0, buffer_size=2.0, - ).pipe(ops.map(lambda pair: ImageDetections2D.from_ros_detection2d_array(*pair))) # type: ignore[misc] + ).pipe(ops.map(lambda pair: ImageDetections2D.from_ros_detection2d_array(*pair))) # type: ignore[misc, arg-type] ) @rpc diff --git a/dimos/perception/detection/type/detection2d/imageDetections2D.py b/dimos/perception/detection/type/detection2d/imageDetections2D.py index 2cab0d4314..7bfee59a61 100644 --- a/dimos/perception/detection/type/detection2d/imageDetections2D.py +++ b/dimos/perception/detection/type/detection2d/imageDetections2D.py @@ -37,11 +37,11 @@ class ImageDetections2D(ImageDetections[T2D], Generic[T2D]): @classmethod - def from_ros_detection2d_array( # type: ignore[no-untyped-def] + def from_ros_detection2d_array( cls, image: Image, ros_detections: Detection2DArray, - **kwargs, + **kwargs: Any, ) -> ImageDetections2D[Detection2DBBox]: """Convert from ROS Detection2DArray message to ImageDetections2D object.""" detections: list[Detection2DBBox] = [] From 2850b54da66167661339e00e1b02ef0603e07b70 Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Thu, 8 Jan 2026 19:12:33 -0800 Subject: [PATCH 06/19] fixed one last mypy error --- dimos/perception/detection/person_tracker.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/dimos/perception/detection/person_tracker.py b/dimos/perception/detection/person_tracker.py index d4f3ae123a..50082742f0 100644 --- a/dimos/perception/detection/person_tracker.py +++ b/dimos/perception/detection/person_tracker.py @@ -84,9 +84,7 @@ def detections_stream(self) -> Observable[ImageDetections2D]: buffer_size=2.0, ).pipe( ops.map( - lambda pair: ImageDetections2D.from_ros_detection2d_array( # type: ignore[misc, arg-type] - *pair - ) + lambda pair: ImageDetections2D.from_ros_detection2d_array(*pair) # type: ignore[misc, arg-type] ) ) ) From 6b532f6d578e5280c39ed7e71c84c86987836bf1 Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Mon, 12 Jan 2026 17:04:39 -0800 Subject: [PATCH 07/19] fixed all of Stash's comments --- dimos/msgs/sensor_msgs/PointCloud2.py | 2 + .../type/detection2d/imageDetections2D.py | 6 +- .../detection/type/detection3d/bbox.py | 6 +- .../detection/type/detection3d/object.py | 73 +++++++++---------- dimos/perception/object_scene_registration.py | 24 ++---- 5 files changed, 50 insertions(+), 61 deletions(-) diff --git a/dimos/msgs/sensor_msgs/PointCloud2.py b/dimos/msgs/sensor_msgs/PointCloud2.py index 772ddad7ab..d68c62f51d 100644 --- a/dimos/msgs/sensor_msgs/PointCloud2.py +++ b/dimos/msgs/sensor_msgs/PointCloud2.py @@ -354,6 +354,8 @@ def transform(self, tf: Transform) -> PointCloud2: def voxel_downsample(self, voxel_size: float = 0.025) -> PointCloud2: """Downsample the pointcloud with a voxel grid.""" + if voxel_size <= 0: + return self if len(self.pointcloud.points) < 20: return self downsampled = self._pcd_tensor.voxel_down_sample(voxel_size) diff --git a/dimos/perception/detection/type/detection2d/imageDetections2D.py b/dimos/perception/detection/type/detection2d/imageDetections2D.py index 7bfee59a61..8118f6fcd9 100644 --- a/dimos/perception/detection/type/detection2d/imageDetections2D.py +++ b/dimos/perception/detection/type/detection2d/imageDetections2D.py @@ -57,7 +57,7 @@ def from_ultralytics_result( cls, image: Image, results: list[Results], - ) -> ImageDetections2D[Detection2DBBox]: + ) -> ImageDetections2D[Detection2D]: """Create ImageDetections2D from ultralytics Results. Dispatches to appropriate Detection2D subclass based on result type: @@ -73,7 +73,7 @@ def from_ultralytics_result( ImageDetections2D containing appropriate detection types """ - detections: list[Detection2DBBox] = [] + detections: list[Detection2D] = [] for result in results: if result.boxes is None: continue @@ -93,7 +93,7 @@ def from_ultralytics_result( if detection.is_valid(): detections.append(detection) - return ImageDetections2D(image=image, detections=detections) # type: ignore[return-value] + return ImageDetections2D(image=image, detections=detections) def overlay(self, alpha: float = 0.4) -> Image: """Overlay detection bboxes and masks onto the image. diff --git a/dimos/perception/detection/type/detection3d/bbox.py b/dimos/perception/detection/type/detection3d/bbox.py index 764b207e75..15a23ce7c2 100644 --- a/dimos/perception/detection/type/detection3d/bbox.py +++ b/dimos/perception/detection/type/detection3d/bbox.py @@ -33,10 +33,10 @@ class Detection3DBBox(Detection2DBBox): Represents a 3D detection as an oriented bounding box in world space. """ + center: Vector3 # Center point in world frame + size: Vector3 # Width, height, depth transform: Transform | None = None # Camera to world transform frame_id: str = "" # Frame ID (e.g., "world", "map") - center: Vector3 | None = None # Center point in world frame - size: Vector3 | None = None # Width, height, depth orientation: Quaternion = field(default_factory=lambda: Quaternion(0.0, 0.0, 0.0, 1.0)) @functools.cached_property @@ -78,7 +78,7 @@ def to_ros_detection3d(self) -> Detection3D: def to_repr_dict(self) -> dict[str, Any]: # Calculate distance from camera - if self.transform is None or self.center is None or self.size is None: + if self.transform is None: return super().to_repr_dict() camera_pos = self.transform.translation distance = (self.center - camera_pos).magnitude() diff --git a/dimos/perception/detection/type/detection3d/object.py b/dimos/perception/detection/type/detection3d/object.py index b4c15209c8..eb2cb104e3 100644 --- a/dimos/perception/detection/type/detection3d/object.py +++ b/dimos/perception/detection/type/detection3d/object.py @@ -37,7 +37,7 @@ from dimos.perception.detection.type.detection2d import ImageDetections2D -@dataclass +@dataclass(kw_only=True) class Object(Detection3D): """3D object detection combining bounding box and pointcloud representations. @@ -46,11 +46,11 @@ class Object(Detection3D): """ object_id: str = field(default_factory=lambda: uuid.uuid4().hex[:8]) - pointcloud: PointCloud2 | None = None + center: Vector3 + size: Vector3 + pose: PoseStamped + pointcloud: PointCloud2 camera_transform: Transform | None = None - center: Vector3 | None = None - size: Vector3 | None = None - pose: PoseStamped | None = None mask: np.ndarray[Any, np.dtype[np.uint8]] | None = None detections_count: int = 1 @@ -64,12 +64,8 @@ def update_object(self, other: Object) -> None: Args: other: Another Object instance with newer detection data. """ - # Accumulate pointclouds if both exist and transforms are available - if ( - self.pointcloud is not None - and other.pointcloud is not None - and other.camera_transform is not None - ): + # Accumulate pointclouds if transforms are available + if other.camera_transform is not None: # Transform new pointcloud to world frame and add to existing # transformed_pc = other.pointcloud.transform(other.camera_transform) # self.pointcloud = self.pointcloud + transformed_pc @@ -84,6 +80,8 @@ def update_object(self, other: Object) -> None: self.center = other.center self.camera_transform = other.camera_transform + self.size = other.size + self.pose = other.pose self.track_id = other.track_id self.mask = other.mask self.name = other.name @@ -97,8 +95,6 @@ def update_object(self, other: Object) -> None: def get_oriented_bounding_box(self) -> Any: """Get oriented bounding box of the pointcloud.""" - if self.pointcloud is None: - raise ValueError("No pointcloud available") return self.pointcloud.get_oriented_bounding_box() def scene_entity_label(self) -> str: @@ -140,12 +136,12 @@ def to_dict(self) -> dict[str, Any]: "class_id": self.class_id, "name": self.name, "mask": self.mask, - "pointcloud": self.pointcloud.as_numpy() if self.pointcloud else None, + "pointcloud": self.pointcloud.as_numpy(), "image": self.image.as_numpy() if self.image else None, } @classmethod - def from_2d( # type: ignore[override] + def from_2d_to_list( cls, detections_2d: ImageDetections2D[Detection2DSeg], color_image: Image, @@ -229,21 +225,13 @@ def from_2d( # type: ignore[override] ) pcd = o3d.geometry.PointCloud.create_from_rgbd_image(rgbd, intrinsic_o3d) - if len(pcd.points) < 20: - continue - - if voxel_downsample > 0: - pcd = ( - PointCloud2( - pcd, - frame_id=depth_image.frame_id, - ts=depth_image.ts, - ) - .voxel_downsample(voxel_downsample) - .pointcloud - ) + pc0 = PointCloud2( + pcd, + frame_id=depth_image.frame_id, + ts=depth_image.ts, + ).voxel_downsample(voxel_downsample) - pcd_filtered, _ = pcd.remove_statistical_outlier( + pcd_filtered, _ = pc0.pointcloud.remove_statistical_outlier( nb_neighbors=statistical_nb_neighbors, std_ratio=statistical_std_ratio, ) @@ -265,8 +253,16 @@ def from_2d( # type: ignore[override] frame_id = depth_image.frame_id # Compute center from pointcloud - pc_center = pc.center - center = Vector3(pc_center.x, pc_center.y, pc_center.z) + obb = pc.pointcloud.get_oriented_bounding_box() + center = Vector3(obb.center[0], obb.center[1], obb.center[2]) + size = Vector3(obb.extent[0], obb.extent[1], obb.extent[2]) + orientation = Quaternion.from_rotation_matrix(obb.R) + pose = PoseStamped( + ts=det.ts, + frame_id=frame_id, + position=center, + orientation=orientation, + ) objects.append( cls( @@ -280,6 +276,8 @@ def from_2d( # type: ignore[override] frame_id=frame_id, pointcloud=pc, center=center, + size=size, + pose=pose, camera_transform=camera_transform, mask=store_mask, ) @@ -288,7 +286,7 @@ def from_2d( # type: ignore[override] return objects -def aggregate_pointclouds(objects: list[Object]) -> PointCloud2 | None: +def aggregate_pointclouds(objects: list[Object]) -> PointCloud2: """Aggregate all object pointclouds into a single colored pointcloud. Each object's points are colored based on its track_id. @@ -297,18 +295,15 @@ def aggregate_pointclouds(objects: list[Object]) -> PointCloud2 | None: objects: List of Object instances with pointclouds Returns: - Combined PointCloud2 with all points colored by object, or None if empty. + Combined PointCloud2 with all points colored by object (empty if no points). """ if not objects: - return None + return PointCloud2(pointcloud=o3d.geometry.PointCloud(), frame_id="", ts=0.0) all_points = [] all_colors = [] for _i, obj in enumerate(objects): - if obj.pointcloud is None: - continue - points, colors = obj.pointcloud.as_numpy() if len(points) == 0: continue @@ -329,7 +324,9 @@ def aggregate_pointclouds(objects: list[Object]) -> PointCloud2 | None: all_colors.append(blended) if not all_points: - return None + return PointCloud2( + pointcloud=o3d.geometry.PointCloud(), frame_id=objects[0].frame_id, ts=objects[0].ts + ) combined_points = np.vstack(all_points) combined_colors = np.vstack(all_colors) diff --git a/dimos/perception/object_scene_registration.py b/dimos/perception/object_scene_registration.py index 3c92da70dc..06d63eb664 100644 --- a/dimos/perception/object_scene_registration.py +++ b/dimos/perception/object_scene_registration.py @@ -63,11 +63,11 @@ def __init__( super().__init__() self._target_frame = target_frame self._prompt_mode = prompt_mode + self._object_db = ObjectDB() @rpc def start(self) -> None: super().start() - self._object_db = ObjectDB() if self._prompt_mode == YoloePromptMode.LRPC: model_name = "yoloe-11l-seg-pf.pt" @@ -97,18 +97,12 @@ def stop(self) -> None: self._detector.stop() self._detector = None - if self._object_db: - self._object_db.clear() - self._object_db = None + self._object_db.clear() + self._object_db = None logger.info("ObjectSceneRegistrationModule stopped") super().stop() - @property - def object_db(self) -> ObjectDB | None: - """Access the ObjectDB for querying detected objects.""" - return self._object_db - @rpc def set_prompts( self, @@ -133,8 +127,6 @@ def select_object(self, track_id: int) -> dict[str, Any] | None: @rpc def get_object_track_ids(self) -> list[int]: """Get track_ids of all permanent objects.""" - if self._object_db is None: - return [] return [obj.track_id for obj in self._object_db.get_all_objects()] @skill() @@ -230,7 +222,7 @@ def _process_3d_detections( logger.warning("Failed to lookup transform from camera frame to target frame") return - objects = Object.from_2d( + objects = Object.from_2d_to_list( detections_2d=detections_2d, color_image=color_image, depth_image=depth_image, @@ -241,16 +233,14 @@ def _process_3d_detections( return # Add objects to spatial memory database - if self._object_db is not None: - objects = self._object_db.add_objects(objects) + objects = self._object_db.add_objects(objects) detections_3d = to_detection3d_array(objects) self.detections_3d.publish(detections_3d) - objects_for_pc = self._object_db.get_objects() if self._object_db else objects + objects_for_pc = self._object_db.get_objects() aggregated_pc = aggregate_pointclouds(objects_for_pc) - if aggregated_pc is not None: - self.pointcloud.publish(aggregated_pc) + self.pointcloud.publish(aggregated_pc) return From fade0dc0fa7654ba8ce77444475f3e4cd3feff43 Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Mon, 12 Jan 2026 17:29:47 -0800 Subject: [PATCH 08/19] should pass mypy now --- dimos/perception/detection/detectors/person/yolo.py | 3 ++- dimos/perception/detection/detectors/yolo.py | 3 ++- dimos/perception/detection/objectDB.py | 10 ++++++++-- .../detection/type/detection2d/imageDetections2D.py | 2 +- .../type/detection2d/test_imageDetections2D.py | 4 +++- dimos/perception/detection/type/detection3d/object.py | 2 +- dimos/perception/object_scene_registration.py | 5 +---- 7 files changed, 18 insertions(+), 11 deletions(-) diff --git a/dimos/perception/detection/detectors/person/yolo.py b/dimos/perception/detection/detectors/person/yolo.py index 519f45f2f6..3f491a2c9a 100644 --- a/dimos/perception/detection/detectors/person/yolo.py +++ b/dimos/perception/detection/detectors/person/yolo.py @@ -17,6 +17,7 @@ from dimos.msgs.sensor_msgs import Image from dimos.perception.detection.detectors.types import Detector from dimos.perception.detection.type import ImageDetections2D +from dimos.perception.detection.type.detection2d.base import Detection2D from dimos.utils.data import get_data from dimos.utils.gpu_utils import is_cuda_available from dimos.utils.logging_config import setup_logger @@ -46,7 +47,7 @@ def __init__( self.device = "cpu" logger.info("Using CPU for YOLO person detector") - def process_image(self, image: Image) -> ImageDetections2D: + def process_image(self, image: Image) -> ImageDetections2D[Detection2D]: """Process image and return detection results. Args: diff --git a/dimos/perception/detection/detectors/yolo.py b/dimos/perception/detection/detectors/yolo.py index c9a65a120e..727d24f1d1 100644 --- a/dimos/perception/detection/detectors/yolo.py +++ b/dimos/perception/detection/detectors/yolo.py @@ -17,6 +17,7 @@ from dimos.msgs.sensor_msgs import Image from dimos.perception.detection.detectors.types import Detector from dimos.perception.detection.type import ImageDetections2D +from dimos.perception.detection.type.detection2d.base import Detection2D from dimos.utils.data import get_data from dimos.utils.gpu_utils import is_cuda_available from dimos.utils.logging_config import setup_logger @@ -47,7 +48,7 @@ def __init__( self.device = "cpu" logger.debug("Using CPU for YOLO 2d detector") - def process_image(self, image: Image) -> ImageDetections2D: + def process_image(self, image: Image) -> ImageDetections2D[Detection2D]: """ Process an image and return detection results. diff --git a/dimos/perception/detection/objectDB.py b/dimos/perception/detection/objectDB.py index 362a543f30..6ade2d8c8d 100644 --- a/dimos/perception/detection/objectDB.py +++ b/dimos/perception/detection/objectDB.py @@ -18,6 +18,9 @@ import time from typing import TYPE_CHECKING, Any +import open3d as o3d # type: ignore[import-untyped] + +from dimos.msgs.sensor_msgs import PointCloud2 from dimos.utils.logging_config import setup_logger if TYPE_CHECKING: @@ -167,8 +170,11 @@ def clear(self) -> None: with self._lock: # Drop Open3D pointcloud references before clearing to reduce shutdown warnings. for obj in list(self._pending_objects.values()) + list(self._objects.values()): - if obj.pointcloud is not None: - obj.pointcloud = None + obj.pointcloud = PointCloud2( + pointcloud=o3d.geometry.PointCloud(), + frame_id=obj.pointcloud.frame_id, + ts=obj.pointcloud.ts, + ) self._pending_objects.clear() self._objects.clear() self._track_id_map.clear() diff --git a/dimos/perception/detection/type/detection2d/imageDetections2D.py b/dimos/perception/detection/type/detection2d/imageDetections2D.py index 8118f6fcd9..92bd0bf506 100644 --- a/dimos/perception/detection/type/detection2d/imageDetections2D.py +++ b/dimos/perception/detection/type/detection2d/imageDetections2D.py @@ -16,7 +16,7 @@ from typing import TYPE_CHECKING, Any, Generic -import cv2 +import cv2 # type: ignore[import-untyped] import numpy as np from typing_extensions import TypeVar diff --git a/dimos/perception/detection/type/detection2d/test_imageDetections2D.py b/dimos/perception/detection/type/detection2d/test_imageDetections2D.py index 83487d2c25..93f75dc422 100644 --- a/dimos/perception/detection/type/detection2d/test_imageDetections2D.py +++ b/dimos/perception/detection/type/detection2d/test_imageDetections2D.py @@ -11,12 +11,14 @@ # 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 typing import Any + import pytest from dimos.perception.detection.type import ImageDetections2D -def test_from_ros_detection2d_array(get_moment_2d) -> None: +def test_from_ros_detection2d_array(get_moment_2d: Any) -> None: moment = get_moment_2d() detections2d = moment["detections2d"] diff --git a/dimos/perception/detection/type/detection3d/object.py b/dimos/perception/detection/type/detection3d/object.py index eb2cb104e3..955f16d61e 100644 --- a/dimos/perception/detection/type/detection3d/object.py +++ b/dimos/perception/detection/type/detection3d/object.py @@ -19,7 +19,7 @@ from typing import TYPE_CHECKING, Any import uuid -import cv2 +import cv2 # type: ignore[import-untyped] from dimos_lcm.geometry_msgs import Pose import numpy as np import open3d as o3d # type: ignore[import-untyped] diff --git a/dimos/perception/object_scene_registration.py b/dimos/perception/object_scene_registration.py index 06d63eb664..830f186bc0 100644 --- a/dimos/perception/object_scene_registration.py +++ b/dimos/perception/object_scene_registration.py @@ -53,7 +53,7 @@ class ObjectSceneRegistrationModule(SkillModule): _detector: Yoloe2DDetector | None = None _camera_info: CameraInfo | None = None - _object_db: ObjectDB | None = None + _object_db: ObjectDB def __init__( self, @@ -98,7 +98,6 @@ def stop(self) -> None: self._detector = None self._object_db.clear() - self._object_db = None logger.info("ObjectSceneRegistrationModule stopped") super().stop() @@ -116,8 +115,6 @@ def set_prompts( @rpc def select_object(self, track_id: int) -> dict[str, Any] | None: """Get object data by track_id and promote to permanent.""" - if self._object_db is None: - return None for obj in self._object_db.get_all_objects(): if obj.track_id == track_id: self._object_db.promote(obj.object_id) From bc566f35c3d6eed7dfa9aa31ba85a10dcdcb61ea Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Mon, 12 Jan 2026 17:32:04 -0800 Subject: [PATCH 09/19] added uv lock --- uv.lock | 630 +++++++++++++++++++++++++++++--------------------------- 1 file changed, 323 insertions(+), 307 deletions(-) diff --git a/uv.lock b/uv.lock index 841b0cccaf..c0caa2ae66 100644 --- a/uv.lock +++ b/uv.lock @@ -186,59 +186,59 @@ wheels = [ [[package]] name = "av" -version = "16.0.1" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/15/c3/fd72a0315bc6c943ced1105aaac6e0ec1be57c70d8a616bd05acaa21ffee/av-16.0.1.tar.gz", hash = "sha256:dd2ce779fa0b5f5889a6d9e00fbbbc39f58e247e52d31044272648fe16ff1dbf", size = 3904030, upload-time = "2025-10-13T12:28:51.082Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/e8/3c/eefa29b7d0f5afdf7af9197bbecad8ec2ad06bcb5ac7e909c05a624b00a6/av-16.0.1-cp310-cp310-macosx_11_0_x86_64.whl", hash = "sha256:8b141aaa29a3afc96a1d467d106790782c1914628b57309eaadb8c10c299c9c0", size = 27206679, upload-time = "2025-10-13T12:24:41.145Z" }, - { url = "https://files.pythonhosted.org/packages/ac/89/a474feb07d5b94aa5af3771b0fe328056e2e0a840039b329f4fa2a1fd13a/av-16.0.1-cp310-cp310-macosx_14_0_arm64.whl", hash = "sha256:4b8a08a59a5be0082af063d3f4b216e3950340121c6ea95b505a3f5f5cc8f21d", size = 21774556, upload-time = "2025-10-13T12:24:44.332Z" }, - { url = "https://files.pythonhosted.org/packages/be/e5/4361010dcac398bc224823e4b2a47803845e159af9f95164662c523770dc/av-16.0.1-cp310-cp310-manylinux_2_28_aarch64.whl", hash = "sha256:792e7fc3c08eae005ff36486983966476e553cbb55aaeb0ec99adc4909377320", size = 38176763, upload-time = "2025-10-13T12:24:46.98Z" }, - { url = "https://files.pythonhosted.org/packages/d4/db/b27bdd20c9dc80de5b8792dae16dd6f4edf16408c0c7b28070c6228a8057/av-16.0.1-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:4e8ef5df76d8d0ee56139789f80bb90ad1a82a7e6df6e080e2e95c06fa22aea7", size = 39696277, upload-time = "2025-10-13T12:24:50.951Z" }, - { url = "https://files.pythonhosted.org/packages/4e/c8/dd48e6a3ac1e922c141475a0dc30e2b6dfdef9751b3274829889a9281cce/av-16.0.1-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:4f7a6985784a7464f078e419c71f5528c3e550ee5d605e7149b4a37a111eb136", size = 39576660, upload-time = "2025-10-13T12:24:55.773Z" }, - { url = "https://files.pythonhosted.org/packages/b9/f0/223d047e2e60672a2fb5e51e28913de8d52195199f3e949cbfda1e6cd64b/av-16.0.1-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:3f45c8d7b803b6faa2a25a26de5964a0a897de68298d9c9672c7af9d65d8b48a", size = 40752775, upload-time = "2025-10-13T12:25:00.827Z" }, - { url = "https://files.pythonhosted.org/packages/18/73/73acad21c9203bc63d806e8baf42fe705eb5d36dafd1996b71ab5861a933/av-16.0.1-cp310-cp310-win_amd64.whl", hash = "sha256:58e6faf1d9328d8cc6be14c5aadacb7d2965ed6d6ae1af32696993096543ff00", size = 32302328, upload-time = "2025-10-13T12:25:06.042Z" }, - { url = "https://files.pythonhosted.org/packages/49/d3/f2a483c5273fccd556dfa1fce14fab3b5d6d213b46e28e54e254465a2255/av-16.0.1-cp311-cp311-macosx_11_0_x86_64.whl", hash = "sha256:e310d1fb42879df9bad2152a8db6d2ff8bf332c8c36349a09d62cc122f5070fb", size = 27191982, upload-time = "2025-10-13T12:25:10.622Z" }, - { url = "https://files.pythonhosted.org/packages/e0/39/dff28bd252131b3befd09d8587992fe18c09d5125eaefc83a6434d5f56ff/av-16.0.1-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:2f4b357e5615457a84e6b6290916b22864b76b43d5079e1a73bc27581a5b9bac", size = 21760305, upload-time = "2025-10-13T12:25:14.882Z" }, - { url = "https://files.pythonhosted.org/packages/4a/4d/2312d50a09c84a9b4269f7fea5de84f05dd2b7c7113dd961d31fad6c64c4/av-16.0.1-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:286665c77034c3a98080169b8b5586d5568a15da81fbcdaf8099252f2d232d7c", size = 38691616, upload-time = "2025-10-13T12:25:20.063Z" }, - { url = "https://files.pythonhosted.org/packages/15/9a/3d2d30b56252f998e53fced13720e2ce809c4db477110f944034e0fa4c9f/av-16.0.1-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:f88de8e5b8ea29e41af4d8d61df108323d050ccfbc90f15b13ec1f99ce0e841e", size = 40216464, upload-time = "2025-10-13T12:25:24.848Z" }, - { url = "https://files.pythonhosted.org/packages/98/cb/3860054794a47715b4be0006105158c7119a57be58d9e8882b72e4d4e1dd/av-16.0.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:0cdb71ebe4d1b241cf700f8f0c44a7d2a6602b921e16547dd68c0842113736e1", size = 40094077, upload-time = "2025-10-13T12:25:30.238Z" }, - { url = "https://files.pythonhosted.org/packages/41/58/79830fb8af0a89c015250f7864bbd427dff09c70575c97847055f8a302f7/av-16.0.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:28c27a65d40e8cf82b6db2543f8feeb8b56d36c1938f50773494cd3b073c7223", size = 41279948, upload-time = "2025-10-13T12:25:35.24Z" }, - { url = "https://files.pythonhosted.org/packages/83/79/6e1463b04382f379f857113b851cf5f9d580a2f7bd794211cd75352f4e04/av-16.0.1-cp311-cp311-win_amd64.whl", hash = "sha256:ffea39ac7574f234f5168f9b9602e8d4ecdd81853238ec4d661001f03a6d3f64", size = 32297586, upload-time = "2025-10-13T12:25:39.826Z" }, - { url = "https://files.pythonhosted.org/packages/44/78/12a11d7a44fdd8b26a65e2efa1d8a5826733c8887a989a78306ec4785956/av-16.0.1-cp312-cp312-macosx_11_0_x86_64.whl", hash = "sha256:e41a8fef85dfb2c717349f9ff74f92f9560122a9f1a94b1c6c9a8a9c9462ba71", size = 27206375, upload-time = "2025-10-13T12:25:44.423Z" }, - { url = "https://files.pythonhosted.org/packages/27/19/3a4d3882852a0ee136121979ce46f6d2867b974eb217a2c9a070939f55ad/av-16.0.1-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:6352a64b25c9f985d4f279c2902db9a92424e6f2c972161e67119616f0796cb9", size = 21752603, upload-time = "2025-10-13T12:25:49.122Z" }, - { url = "https://files.pythonhosted.org/packages/cb/6e/f7abefba6e008e2f69bebb9a17ba38ce1df240c79b36a5b5fcacf8c8fcfd/av-16.0.1-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:5201f7b4b5ed2128118cb90c2a6d64feedb0586ca7c783176896c78ffb4bbd5c", size = 38931978, upload-time = "2025-10-13T12:25:55.021Z" }, - { url = "https://files.pythonhosted.org/packages/b2/7a/1305243ab47f724fdd99ddef7309a594e669af7f0e655e11bdd2c325dfae/av-16.0.1-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:daecc2072b82b6a942acbdaa9a2e00c05234c61fef976b22713983c020b07992", size = 40549383, upload-time = "2025-10-13T12:26:00.897Z" }, - { url = "https://files.pythonhosted.org/packages/32/b2/357cc063185043eb757b4a48782bff780826103bcad1eb40c3ddfc050b7e/av-16.0.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:6573da96e8bebc3536860a7def108d7dbe1875c86517072431ced702447e6aea", size = 40241993, upload-time = "2025-10-13T12:26:06.993Z" }, - { url = "https://files.pythonhosted.org/packages/20/bb/ced42a4588ba168bf0ef1e9d016982e3ba09fde6992f1dda586fd20dcf71/av-16.0.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:4bc064e48a8de6c087b97dd27cf4ef8c13073f0793108fbce3ecd721201b2502", size = 41532235, upload-time = "2025-10-13T12:26:12.488Z" }, - { url = "https://files.pythonhosted.org/packages/15/37/c7811eca0f318d5fd3212f7e8c3d8335f75a54907c97a89213dc580b8056/av-16.0.1-cp312-cp312-win_amd64.whl", hash = "sha256:0c669b6b6668c8ae74451c15ec6d6d8a36e4c3803dc5d9910f607a174dd18f17", size = 32296912, upload-time = "2025-10-13T12:26:19.187Z" }, - { url = "https://files.pythonhosted.org/packages/86/59/972f199ccc4f8c9e51f59e0f8962a09407396b3f6d11355e2c697ba555f9/av-16.0.1-cp313-cp313-macosx_11_0_x86_64.whl", hash = "sha256:4c61c6c120f5c5d95c711caf54e2c4a9fb2f1e613ac0a9c273d895f6b2602e44", size = 27170433, upload-time = "2025-10-13T12:26:24.673Z" }, - { url = "https://files.pythonhosted.org/packages/53/9d/0514cbc185fb20353ab25da54197fbd169a233e39efcbb26533c36a9dbb9/av-16.0.1-cp313-cp313-macosx_14_0_arm64.whl", hash = "sha256:7ecc2e41320c69095f44aff93470a0d32c30892b2dbad0a08040441c81efa379", size = 21717654, upload-time = "2025-10-13T12:26:29.12Z" }, - { url = "https://files.pythonhosted.org/packages/32/8c/881409dd124b4e07d909d2b70568acb21126fc747656390840a2238651c9/av-16.0.1-cp313-cp313-manylinux_2_28_aarch64.whl", hash = "sha256:036f0554d6faef3f4a94acaeb0cedd388e3ab96eb0eb5a14ec27c17369c466c9", size = 38651601, upload-time = "2025-10-13T12:26:33.919Z" }, - { url = "https://files.pythonhosted.org/packages/35/fd/867ba4cc3ab504442dc89b0c117e6a994fc62782eb634c8f31304586f93e/av-16.0.1-cp313-cp313-manylinux_2_28_x86_64.whl", hash = "sha256:876415470a62e4a3550cc38db2fc0094c25e64eea34d7293b7454125d5958190", size = 40278604, upload-time = "2025-10-13T12:26:39.2Z" }, - { url = "https://files.pythonhosted.org/packages/b3/87/63cde866c0af09a1fa9727b4f40b34d71b0535785f5665c27894306f1fbc/av-16.0.1-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:56902a06bd0828d13f13352874c370670882048267191ff5829534b611ba3956", size = 39984854, upload-time = "2025-10-13T12:26:44.581Z" }, - { url = "https://files.pythonhosted.org/packages/71/3b/8f40a708bff0e6b0f957836e2ef1f4d4429041cf8d99a415a77ead8ac8a3/av-16.0.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:fe988c2bf0fc2d952858f791f18377ea4ae4e19ba3504793799cd6c2a2562edf", size = 41270352, upload-time = "2025-10-13T12:26:50.817Z" }, - { url = "https://files.pythonhosted.org/packages/1e/b5/c114292cb58a7269405ae13b7ba48c7d7bfeebbb2e4e66c8073c065a4430/av-16.0.1-cp313-cp313-win_amd64.whl", hash = "sha256:708a66c248848029bf518f0482b81c5803846f1b597ef8013b19c014470b620f", size = 32273242, upload-time = "2025-10-13T12:26:55.788Z" }, - { url = "https://files.pythonhosted.org/packages/ff/e9/a5b714bc078fdcca8b46c8a0b38484ae5c24cd81d9c1703d3e8ae2b57259/av-16.0.1-cp313-cp313t-macosx_11_0_x86_64.whl", hash = "sha256:79a77ee452537030c21a0b41139bedaf16629636bf764b634e93b99c9d5f4558", size = 27248984, upload-time = "2025-10-13T12:27:00.564Z" }, - { url = "https://files.pythonhosted.org/packages/06/ef/ff777aaf1f88e3f6ce94aca4c5806a0c360e68d48f9d9f0214e42650f740/av-16.0.1-cp313-cp313t-macosx_14_0_arm64.whl", hash = "sha256:080823a6ff712f81e7089ae9756fb1512ca1742a138556a852ce50f58e457213", size = 21828098, upload-time = "2025-10-13T12:27:05.433Z" }, - { url = "https://files.pythonhosted.org/packages/34/d7/a484358d24a42bedde97f61f5d6ee568a7dd866d9df6e33731378db92d9e/av-16.0.1-cp313-cp313t-manylinux_2_28_aarch64.whl", hash = "sha256:04e00124afa8b46a850ed48951ddda61de874407fb8307d6a875bba659d5727e", size = 40051697, upload-time = "2025-10-13T12:27:10.525Z" }, - { url = "https://files.pythonhosted.org/packages/73/87/6772d6080837da5d5c810a98a95bde6977e1f5a6e2e759e8c9292af9ec69/av-16.0.1-cp313-cp313t-manylinux_2_28_x86_64.whl", hash = "sha256:bc098c1c6dc4e7080629a7e9560e67bd4b5654951e17e5ddfd2b1515cfcd37db", size = 41352596, upload-time = "2025-10-13T12:27:16.217Z" }, - { url = "https://files.pythonhosted.org/packages/bd/58/fe448c60cf7f85640a0ed8936f16bac874846aa35e1baa521028949c1ea3/av-16.0.1-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:e6ffd3559a72c46a76aa622630751a821499ba5a780b0047ecc75105d43a6b61", size = 41183156, upload-time = "2025-10-13T12:27:21.574Z" }, - { url = "https://files.pythonhosted.org/packages/85/c6/a039a0979d0c278e1bed6758d5a6186416c3ccb8081970df893fdf9a0d99/av-16.0.1-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:7a3f1a36b550adadd7513f4f5ee956f9e06b01a88e59f3150ef5fec6879d6f79", size = 42302331, upload-time = "2025-10-13T12:27:26.953Z" }, - { url = "https://files.pythonhosted.org/packages/18/7b/2ca4a9e3609ff155436dac384e360f530919cb1e328491f7df294be0f0dc/av-16.0.1-cp313-cp313t-win_amd64.whl", hash = "sha256:c6de794abe52b8c0be55d8bb09ade05905efa74b1a5ab4860b4b9c2bfb6578bf", size = 32462194, upload-time = "2025-10-13T12:27:32.942Z" }, - { url = "https://files.pythonhosted.org/packages/14/9a/6d17e379906cf53a7a44dfac9cf7e4b2e7df2082ba2dbf07126055effcc1/av-16.0.1-cp314-cp314-macosx_11_0_x86_64.whl", hash = "sha256:4b55ba69a943ae592ad7900da67129422954789de9dc384685d6b529925f542e", size = 27167101, upload-time = "2025-10-13T12:27:38.886Z" }, - { url = "https://files.pythonhosted.org/packages/6c/34/891816cd82d5646cb5a51d201d20be0a578232536d083b7d939734258067/av-16.0.1-cp314-cp314-macosx_14_0_arm64.whl", hash = "sha256:d4a0c47b6c9bbadad8909b82847f5fe64a608ad392f0b01704e427349bcd9a47", size = 21722708, upload-time = "2025-10-13T12:27:43.29Z" }, - { url = "https://files.pythonhosted.org/packages/1d/20/c24ad34038423ab8c9728cef3301e0861727c188442dcfd70a4a10834c63/av-16.0.1-cp314-cp314-manylinux_2_28_aarch64.whl", hash = "sha256:8bba52f3035708456f6b1994d10b0371b45cfd8f917b5e84ff81aef4ec2f08bf", size = 38638842, upload-time = "2025-10-13T12:27:49.776Z" }, - { url = "https://files.pythonhosted.org/packages/d7/32/034412309572ba3ad713079d07a3ffc13739263321aece54a3055d7a4f1f/av-16.0.1-cp314-cp314-manylinux_2_28_x86_64.whl", hash = "sha256:08e34c7e7b5e55e29931180bbe21095e1874ac120992bf6b8615d39574487617", size = 40197789, upload-time = "2025-10-13T12:27:55.688Z" }, - { url = "https://files.pythonhosted.org/packages/fb/9c/40496298c32f9094e7df28641c5c58aa6fb07554dc232a9ac98a9894376f/av-16.0.1-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:0d6250ab9db80c641b299987027c987f14935ea837ea4c02c5f5182f6b69d9e5", size = 39980829, upload-time = "2025-10-13T12:28:01.507Z" }, - { url = "https://files.pythonhosted.org/packages/4a/7e/5c38268ac1d424f309b13b2de4597ad28daea6039ee5af061e62918b12a8/av-16.0.1-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:7b621f28d8bcbb07cdcd7b18943ddc040739ad304545715ae733873b6e1b739d", size = 41205928, upload-time = "2025-10-13T12:28:08.431Z" }, - { url = "https://files.pythonhosted.org/packages/e3/07/3176e02692d8753a6c4606021c60e4031341afb56292178eee633b6760a4/av-16.0.1-cp314-cp314-win_amd64.whl", hash = "sha256:92101f49082392580c9dba4ba2fe5b931b3bb0fb75a1a848bfb9a11ded68be91", size = 32272836, upload-time = "2025-10-13T12:28:13.405Z" }, - { url = "https://files.pythonhosted.org/packages/8a/47/10e03b88de097385d1550cbb6d8de96159131705c13adb92bd9b7e677425/av-16.0.1-cp314-cp314t-macosx_11_0_x86_64.whl", hash = "sha256:07c464bf2bc362a154eccc82e235ef64fd3aaf8d76fc8ed63d0ae520943c6d3f", size = 27248864, upload-time = "2025-10-13T12:28:17.467Z" }, - { url = "https://files.pythonhosted.org/packages/b1/60/7447f206bec3e55e81371f1989098baa2fe9adb7b46c149e6937b7e7c1ca/av-16.0.1-cp314-cp314t-macosx_14_0_arm64.whl", hash = "sha256:750da0673864b669c95882c7b25768cd93ece0e47010d74ebcc29dbb14d611f8", size = 21828185, upload-time = "2025-10-13T12:28:21.461Z" }, - { url = "https://files.pythonhosted.org/packages/68/48/ee2680e7a01bc4911bbe902b814346911fa2528697a44f3043ee68e0f07e/av-16.0.1-cp314-cp314t-manylinux_2_28_aarch64.whl", hash = "sha256:0b7c0d060863b2e341d07cd26851cb9057b7979814148b028fb7ee5d5eb8772d", size = 40040572, upload-time = "2025-10-13T12:28:26.585Z" }, - { url = "https://files.pythonhosted.org/packages/da/68/2c43d28871721ae07cde432d6e36ae2f7035197cbadb43764cc5bf3d4b33/av-16.0.1-cp314-cp314t-manylinux_2_28_x86_64.whl", hash = "sha256:e67c2eca6023ca7d76b0709c5f392b23a5defba499f4c262411f8155b1482cbd", size = 41344288, upload-time = "2025-10-13T12:28:32.512Z" }, - { url = "https://files.pythonhosted.org/packages/ec/7f/1d801bff43ae1af4758c45eee2eaae64f303bbb460e79f352f08587fd179/av-16.0.1-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:e3243d54d84986e8fbdc1946db634b0c41fe69b6de35a99fa8b763e18503d040", size = 41175142, upload-time = "2025-10-13T12:28:38.356Z" }, - { url = "https://files.pythonhosted.org/packages/e4/06/bb363138687066bbf8997c1433dbd9c81762bae120955ea431fb72d69d26/av-16.0.1-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:a1bcf73efab5379601e6510abd7afe5f397d0f6defe69b1610c2f37a4a17996b", size = 42293932, upload-time = "2025-10-13T12:28:43.442Z" }, - { url = "https://files.pythonhosted.org/packages/92/15/5e713098a085f970ccf88550194d277d244464d7b3a7365ad92acb4b6dc1/av-16.0.1-cp314-cp314t-win_amd64.whl", hash = "sha256:6368d4ff153d75469d2a3217bc403630dc870a72fe0a014d9135de550d731a86", size = 32460624, upload-time = "2025-10-13T12:28:48.767Z" }, +version = "16.1.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/78/cd/3a83ffbc3cc25b39721d174487fb0d51a76582f4a1703f98e46170ce83d4/av-16.1.0.tar.gz", hash = "sha256:a094b4fd87a3721dacf02794d3d2c82b8d712c85b9534437e82a8a978c175ffd", size = 4285203, upload-time = "2026-01-11T07:31:33.772Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/97/51/2217a9249409d2e88e16e3f16f7c0def9fd3e7ffc4238b2ec211f9935bdb/av-16.1.0-cp310-cp310-macosx_11_0_x86_64.whl", hash = "sha256:2395748b0c34fe3a150a1721e4f3d4487b939520991b13e7b36f8926b3b12295", size = 26942590, upload-time = "2026-01-09T20:17:58.588Z" }, + { url = "https://files.pythonhosted.org/packages/bf/cd/a7070f4febc76a327c38808e01e2ff6b94531fe0b321af54ea3915165338/av-16.1.0-cp310-cp310-macosx_14_0_arm64.whl", hash = "sha256:72d7ac832710a158eeb7a93242370aa024a7646516291c562ee7f14a7ea881fd", size = 21507910, upload-time = "2026-01-09T20:18:02.309Z" }, + { url = "https://files.pythonhosted.org/packages/ae/30/ec812418cd9b297f0238fe20eb0747d8a8b68d82c5f73c56fe519a274143/av-16.1.0-cp310-cp310-manylinux_2_28_aarch64.whl", hash = "sha256:6cbac833092e66b6b0ac4d81ab077970b8ca874951e9c3974d41d922aaa653ed", size = 38738309, upload-time = "2026-01-09T20:18:04.701Z" }, + { url = "https://files.pythonhosted.org/packages/3a/b8/6c5795bf1f05f45c5261f8bce6154e0e5e86b158a6676650ddd77c28805e/av-16.1.0-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:eb990672d97c18f99c02f31c8d5750236f770ffe354b5a52c5f4d16c5e65f619", size = 40293006, upload-time = "2026-01-09T20:18:07.238Z" }, + { url = "https://files.pythonhosted.org/packages/a7/44/5e183bcb9333fc3372ee6e683be8b0c9b515a506894b2d32ff465430c074/av-16.1.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:05ad70933ac3b8ef896a820ea64b33b6cca91a5fac5259cb9ba7fa010435be15", size = 40123516, upload-time = "2026-01-09T20:18:09.955Z" }, + { url = "https://files.pythonhosted.org/packages/12/1d/b5346d582a3c3d958b4d26a2cc63ce607233582d956121eb20d2bbe55c2e/av-16.1.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:d831a1062a3c47520bf99de6ec682bd1d64a40dfa958e5457bb613c5270e7ce3", size = 41463289, upload-time = "2026-01-09T20:18:12.459Z" }, + { url = "https://files.pythonhosted.org/packages/fa/31/acc946c0545f72b8d0d74584cb2a0ade9b7dfe2190af3ef9aa52a2e3c0b1/av-16.1.0-cp310-cp310-win_amd64.whl", hash = "sha256:358ab910fef3c5a806c55176f2b27e5663b33c4d0a692dafeb049c6ed71f8aff", size = 31754959, upload-time = "2026-01-09T20:18:14.718Z" }, + { url = "https://files.pythonhosted.org/packages/48/d0/b71b65d1b36520dcb8291a2307d98b7fc12329a45614a303ff92ada4d723/av-16.1.0-cp311-cp311-macosx_11_0_x86_64.whl", hash = "sha256:e88ad64ee9d2b9c4c5d891f16c22ae78e725188b8926eb88187538d9dd0b232f", size = 26927747, upload-time = "2026-01-09T20:18:16.976Z" }, + { url = "https://files.pythonhosted.org/packages/2f/79/720a5a6ccdee06eafa211b945b0a450e3a0b8fc3d12922f0f3c454d870d2/av-16.1.0-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:cb296073fa6935724de72593800ba86ae49ed48af03960a4aee34f8a611f442b", size = 21492232, upload-time = "2026-01-09T20:18:19.266Z" }, + { url = "https://files.pythonhosted.org/packages/8e/4f/a1ba8d922f2f6d1a3d52419463ef26dd6c4d43ee364164a71b424b5ae204/av-16.1.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:720edd4d25aa73723c1532bb0597806d7b9af5ee34fc02358782c358cfe2f879", size = 39291737, upload-time = "2026-01-09T20:18:21.513Z" }, + { url = "https://files.pythonhosted.org/packages/1a/31/fc62b9fe8738d2693e18d99f040b219e26e8df894c10d065f27c6b4f07e3/av-16.1.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:c7f2bc703d0df260a1fdf4de4253c7f5500ca9fc57772ea241b0cb241bcf972e", size = 40846822, upload-time = "2026-01-09T20:18:24.275Z" }, + { url = "https://files.pythonhosted.org/packages/53/10/ab446583dbce730000e8e6beec6ec3c2753e628c7f78f334a35cad0317f4/av-16.1.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:d69c393809babada7d54964d56099e4b30a3e1f8b5736ca5e27bd7be0e0f3c83", size = 40675604, upload-time = "2026-01-09T20:18:26.866Z" }, + { url = "https://files.pythonhosted.org/packages/31/d7/1003be685277005f6d63fd9e64904ee222fe1f7a0ea70af313468bb597db/av-16.1.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:441892be28582356d53f282873c5a951592daaf71642c7f20165e3ddcb0b4c63", size = 42015955, upload-time = "2026-01-09T20:18:29.461Z" }, + { url = "https://files.pythonhosted.org/packages/2f/4a/fa2a38ee9306bf4579f556f94ecbc757520652eb91294d2a99c7cf7623b9/av-16.1.0-cp311-cp311-win_amd64.whl", hash = "sha256:273a3e32de64819e4a1cd96341824299fe06f70c46f2288b5dc4173944f0fd62", size = 31750339, upload-time = "2026-01-09T20:18:32.249Z" }, + { url = "https://files.pythonhosted.org/packages/9c/84/2535f55edcd426cebec02eb37b811b1b0c163f26b8d3f53b059e2ec32665/av-16.1.0-cp312-cp312-macosx_11_0_x86_64.whl", hash = "sha256:640f57b93f927fba8689f6966c956737ee95388a91bd0b8c8b5e0481f73513d6", size = 26945785, upload-time = "2026-01-09T20:18:34.486Z" }, + { url = "https://files.pythonhosted.org/packages/b6/17/ffb940c9e490bf42e86db4db1ff426ee1559cd355a69609ec1efe4d3a9eb/av-16.1.0-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:ae3fb658eec00852ebd7412fdc141f17f3ddce8afee2d2e1cf366263ad2a3b35", size = 21481147, upload-time = "2026-01-09T20:18:36.716Z" }, + { url = "https://files.pythonhosted.org/packages/15/c1/e0d58003d2d83c3921887d5c8c9b8f5f7de9b58dc2194356a2656a45cfdc/av-16.1.0-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:27ee558d9c02a142eebcbe55578a6d817fedfde42ff5676275504e16d07a7f86", size = 39517197, upload-time = "2026-01-11T09:57:31.937Z" }, + { url = "https://files.pythonhosted.org/packages/32/77/787797b43475d1b90626af76f80bfb0c12cfec5e11eafcfc4151b8c80218/av-16.1.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:7ae547f6d5fa31763f73900d43901e8c5fa6367bb9a9840978d57b5a7ae14ed2", size = 41174337, upload-time = "2026-01-11T09:57:35.792Z" }, + { url = "https://files.pythonhosted.org/packages/8e/ac/d90df7f1e3b97fc5554cf45076df5045f1e0a6adf13899e10121229b826c/av-16.1.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:8cf065f9d438e1921dc31fc7aa045790b58aee71736897866420d80b5450f62a", size = 40817720, upload-time = "2026-01-11T09:57:39.039Z" }, + { url = "https://files.pythonhosted.org/packages/80/6f/13c3a35f9dbcebafd03fe0c4cbd075d71ac8968ec849a3cfce406c35a9d2/av-16.1.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:a345877a9d3cc0f08e2bc4ec163ee83176864b92587afb9d08dff50f37a9a829", size = 42267396, upload-time = "2026-01-11T09:57:42.115Z" }, + { url = "https://files.pythonhosted.org/packages/c8/b9/275df9607f7fb44317ccb1d4be74827185c0d410f52b6e2cd770fe209118/av-16.1.0-cp312-cp312-win_amd64.whl", hash = "sha256:f49243b1d27c91cd8c66fdba90a674e344eb8eb917264f36117bf2b6879118fd", size = 31752045, upload-time = "2026-01-11T09:57:45.106Z" }, + { url = "https://files.pythonhosted.org/packages/75/2a/63797a4dde34283dd8054219fcb29294ba1c25d68ba8c8c8a6ae53c62c45/av-16.1.0-cp313-cp313-macosx_11_0_x86_64.whl", hash = "sha256:ce2a1b3d8bf619f6c47a9f28cfa7518ff75ddd516c234a4ee351037b05e6a587", size = 26916715, upload-time = "2026-01-11T09:57:47.682Z" }, + { url = "https://files.pythonhosted.org/packages/d2/c4/0b49cf730d0ae8cda925402f18ae814aef351f5772d14da72dd87ff66448/av-16.1.0-cp313-cp313-macosx_14_0_arm64.whl", hash = "sha256:408dbe6a2573ca58a855eb8cd854112b33ea598651902c36709f5f84c991ed8e", size = 21452167, upload-time = "2026-01-11T09:57:50.606Z" }, + { url = "https://files.pythonhosted.org/packages/51/23/408806503e8d5d840975aad5699b153aaa21eb6de41ade75248a79b7a37f/av-16.1.0-cp313-cp313-manylinux_2_28_aarch64.whl", hash = "sha256:57f657f86652a160a8a01887aaab82282f9e629abf94c780bbdbb01595d6f0f7", size = 39215659, upload-time = "2026-01-11T09:57:53.757Z" }, + { url = "https://files.pythonhosted.org/packages/c4/19/a8528d5bba592b3903f44c28dab9cc653c95fcf7393f382d2751a1d1523e/av-16.1.0-cp313-cp313-manylinux_2_28_x86_64.whl", hash = "sha256:adbad2b355c2ee4552cac59762809d791bda90586d134a33c6f13727fb86cb3a", size = 40874970, upload-time = "2026-01-11T09:57:56.802Z" }, + { url = "https://files.pythonhosted.org/packages/e8/24/2dbcdf0e929ad56b7df078e514e7bd4ca0d45cba798aff3c8caac097d2f7/av-16.1.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:f42e1a68ec2aebd21f7eb6895be69efa6aa27eec1670536876399725bbda4b99", size = 40530345, upload-time = "2026-01-11T09:58:00.421Z" }, + { url = "https://files.pythonhosted.org/packages/54/27/ae91b41207f34e99602d1c72ab6ffd9c51d7c67e3fbcd4e3a6c0e54f882c/av-16.1.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:58fe47aeaef0f100c40ec8a5de9abbd37f118d3ca03829a1009cf288e9aef67c", size = 41972163, upload-time = "2026-01-11T09:58:03.756Z" }, + { url = "https://files.pythonhosted.org/packages/fc/7a/22158fb923b2a9a00dfab0e96ef2e8a1763a94dd89e666a5858412383d46/av-16.1.0-cp313-cp313-win_amd64.whl", hash = "sha256:565093ebc93b2f4b76782589564869dadfa83af5b852edebedd8fee746457d06", size = 31729230, upload-time = "2026-01-11T09:58:07.254Z" }, + { url = "https://files.pythonhosted.org/packages/7f/f1/878f8687d801d6c4565d57ebec08449c46f75126ebca8e0fed6986599627/av-16.1.0-cp313-cp313t-macosx_11_0_x86_64.whl", hash = "sha256:574081a24edb98343fd9f473e21ae155bf61443d4ec9d7708987fa597d6b04b2", size = 27008769, upload-time = "2026-01-11T09:58:10.266Z" }, + { url = "https://files.pythonhosted.org/packages/30/f1/bd4ce8c8b5cbf1d43e27048e436cbc9de628d48ede088a1d0a993768eb86/av-16.1.0-cp313-cp313t-macosx_14_0_arm64.whl", hash = "sha256:9ab00ea29c25ebf2ea1d1e928d7babb3532d562481c5d96c0829212b70756ad0", size = 21590588, upload-time = "2026-01-11T09:58:12.629Z" }, + { url = "https://files.pythonhosted.org/packages/1d/dd/c81f6f9209201ff0b5d5bed6da6c6e641eef52d8fbc930d738c3f4f6f75d/av-16.1.0-cp313-cp313t-manylinux_2_28_aarch64.whl", hash = "sha256:a84a91188c1071f238a9523fd42dbe567fb2e2607b22b779851b2ce0eac1b560", size = 40638029, upload-time = "2026-01-11T09:58:15.399Z" }, + { url = "https://files.pythonhosted.org/packages/15/4d/07edff82b78d0459a6e807e01cd280d3180ce832efc1543de80d77676722/av-16.1.0-cp313-cp313t-manylinux_2_28_x86_64.whl", hash = "sha256:c2cd0de4dd022a7225ff224fde8e7971496d700be41c50adaaa26c07bb50bf97", size = 41970776, upload-time = "2026-01-11T09:58:19.075Z" }, + { url = "https://files.pythonhosted.org/packages/da/9d/1f48b354b82fa135d388477cd1b11b81bdd4384bd6a42a60808e2ec2d66b/av-16.1.0-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:0816143530624a5a93bc5494f8c6eeaf77549b9366709c2ac8566c1e9bff6df5", size = 41764751, upload-time = "2026-01-11T09:58:22.788Z" }, + { url = "https://files.pythonhosted.org/packages/2f/c7/a509801e98db35ec552dd79da7bdbcff7104044bfeb4c7d196c1ce121593/av-16.1.0-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:e3a28053af29644696d0c007e897d19b1197585834660a54773e12a40b16974c", size = 43034355, upload-time = "2026-01-11T09:58:26.125Z" }, + { url = "https://files.pythonhosted.org/packages/36/8b/e5f530d9e8f640da5f5c5f681a424c65f9dd171c871cd255d8a861785a6e/av-16.1.0-cp313-cp313t-win_amd64.whl", hash = "sha256:2e3e67144a202b95ed299d165232533989390a9ea3119d37eccec697dc6dbb0c", size = 31947047, upload-time = "2026-01-11T09:58:31.867Z" }, + { url = "https://files.pythonhosted.org/packages/df/18/8812221108c27d19f7e5f486a82c827923061edf55f906824ee0fcaadf50/av-16.1.0-cp314-cp314-macosx_11_0_x86_64.whl", hash = "sha256:39a634d8e5a87e78ea80772774bfd20c0721f0d633837ff185f36c9d14ffede4", size = 26916179, upload-time = "2026-01-11T09:58:36.506Z" }, + { url = "https://files.pythonhosted.org/packages/38/ef/49d128a9ddce42a2766fe2b6595bd9c49e067ad8937a560f7838a541464e/av-16.1.0-cp314-cp314-macosx_14_0_arm64.whl", hash = "sha256:0ba32fb9e9300948a7fa9f8a3fc686e6f7f77599a665c71eb2118fdfd2c743f9", size = 21460168, upload-time = "2026-01-11T09:58:39.231Z" }, + { url = "https://files.pythonhosted.org/packages/e6/a9/b310d390844656fa74eeb8c2750e98030877c75b97551a23a77d3f982741/av-16.1.0-cp314-cp314-manylinux_2_28_aarch64.whl", hash = "sha256:ca04d17815182d34ce3edc53cbda78a4f36e956c0fd73e3bab249872a831c4d7", size = 39210194, upload-time = "2026-01-11T09:58:42.138Z" }, + { url = "https://files.pythonhosted.org/packages/0c/7b/e65aae179929d0f173af6e474ad1489b5b5ad4c968a62c42758d619e54cf/av-16.1.0-cp314-cp314-manylinux_2_28_x86_64.whl", hash = "sha256:ee0e8de2e124a9ef53c955fe2add6ee7c56cc8fd83318265549e44057db77142", size = 40811675, upload-time = "2026-01-11T09:58:45.871Z" }, + { url = "https://files.pythonhosted.org/packages/54/3f/5d7edefd26b6a5187d6fac0f5065ee286109934f3dea607ef05e53f05b31/av-16.1.0-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:22bf77a2f658827043a1e184b479c3bf25c4c43ab32353677df2d119f080e28f", size = 40543942, upload-time = "2026-01-11T09:58:49.759Z" }, + { url = "https://files.pythonhosted.org/packages/1b/24/f8b17897b67be0900a211142f5646a99d896168f54d57c81f3e018853796/av-16.1.0-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:2dd419d262e6a71cab206d80bbf28e0a10d0f227b671cdf5e854c028faa2d043", size = 41924336, upload-time = "2026-01-11T09:58:53.344Z" }, + { url = "https://files.pythonhosted.org/packages/1c/cf/d32bc6bbbcf60b65f6510c54690ed3ae1c4ca5d9fafbce835b6056858686/av-16.1.0-cp314-cp314-win_amd64.whl", hash = "sha256:53585986fd431cd436f290fba662cfb44d9494fbc2949a183de00acc5b33fa88", size = 31735077, upload-time = "2026-01-11T09:58:56.684Z" }, + { url = "https://files.pythonhosted.org/packages/53/f4/9b63dc70af8636399bd933e9df4f3025a0294609510239782c1b746fc796/av-16.1.0-cp314-cp314t-macosx_11_0_x86_64.whl", hash = "sha256:76f5ed8495cf41e1209a5775d3699dc63fdc1740b94a095e2485f13586593205", size = 27014423, upload-time = "2026-01-11T09:58:59.703Z" }, + { url = "https://files.pythonhosted.org/packages/d1/da/787a07a0d6ed35a0888d7e5cfb8c2ffa202f38b7ad2c657299fac08eb046/av-16.1.0-cp314-cp314t-macosx_14_0_arm64.whl", hash = "sha256:8d55397190f12a1a3ae7538be58c356cceb2bf50df1b33523817587748ce89e5", size = 21595536, upload-time = "2026-01-11T09:59:02.508Z" }, + { url = "https://files.pythonhosted.org/packages/d8/f4/9a7d8651a611be6e7e3ab7b30bb43779899c8cac5f7293b9fb634c44a3f3/av-16.1.0-cp314-cp314t-manylinux_2_28_aarch64.whl", hash = "sha256:9d51d9037437218261b4bbf9df78a95e216f83d7774fbfe8d289230b5b2e28e2", size = 40642490, upload-time = "2026-01-11T09:59:05.842Z" }, + { url = "https://files.pythonhosted.org/packages/6b/e4/eb79bc538a94b4ff93cd4237d00939cba797579f3272490dd0144c165a21/av-16.1.0-cp314-cp314t-manylinux_2_28_x86_64.whl", hash = "sha256:0ce07a89c15644407f49d942111ca046e323bbab0a9078ff43ee57c9b4a50dad", size = 41976905, upload-time = "2026-01-11T09:59:09.169Z" }, + { url = "https://files.pythonhosted.org/packages/5e/f5/f6db0dd86b70167a4d55ee0d9d9640983c570d25504f2bde42599f38241e/av-16.1.0-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:cac0c074892ea97113b53556ff41c99562db7b9f09f098adac1f08318c2acad5", size = 41770481, upload-time = "2026-01-11T09:59:12.74Z" }, + { url = "https://files.pythonhosted.org/packages/9e/8b/33651d658e45e16ab7671ea5fcf3d20980ea7983234f4d8d0c63c65581a5/av-16.1.0-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:7dec3dcbc35a187ce450f65a2e0dda820d5a9e6553eea8344a1459af11c98649", size = 43036824, upload-time = "2026-01-11T09:59:16.507Z" }, + { url = "https://files.pythonhosted.org/packages/83/41/7f13361db54d7e02f11552575c0384dadaf0918138f4eaa82ea03a9f9580/av-16.1.0-cp314-cp314t-win_amd64.whl", hash = "sha256:6f90dc082ff2068ddbe77618400b44d698d25d9c4edac57459e250c16b33d700", size = 31948164, upload-time = "2026-01-11T09:59:19.501Z" }, ] [[package]] @@ -424,7 +424,7 @@ dependencies = [ { name = "orbax-checkpoint" }, { name = "pillow" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "tensorboardx" }, { name = "trimesh" }, { name = "typing-extensions" }, @@ -1397,7 +1397,7 @@ dependencies = [ { name = "reactivex" }, { name = "rerun-sdk" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "sortedcontainers" }, { name = "structlog" }, { name = "terminaltexteffects" }, @@ -2074,11 +2074,11 @@ wheels = [ [[package]] name = "filelock" -version = "3.20.2" +version = "3.20.3" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/c1/e0/a75dbe4bca1e7d41307323dad5ea2efdd95408f74ab2de8bd7dba9b51a1a/filelock-3.20.2.tar.gz", hash = "sha256:a2241ff4ddde2a7cebddf78e39832509cb045d18ec1a09d7248d6bfc6bfbbe64", size = 19510, upload-time = "2026-01-02T15:33:32.582Z" } +sdist = { url = "https://files.pythonhosted.org/packages/1d/65/ce7f1b70157833bf3cb851b556a37d4547ceafc158aa9b34b36782f23696/filelock-3.20.3.tar.gz", hash = "sha256:18c57ee915c7ec61cff0ecf7f0f869936c7c30191bb0cf406f1341778d0834e1", size = 19485, upload-time = "2026-01-09T17:55:05.421Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/9a/30/ab407e2ec752aa541704ed8f93c11e2a5d92c168b8a755d818b74a3c5c2d/filelock-3.20.2-py3-none-any.whl", hash = "sha256:fbba7237d6ea277175a32c54bb71ef814a8546d8601269e1bfc388de333974e8", size = 16697, upload-time = "2026-01-02T15:33:31.133Z" }, + { url = "https://files.pythonhosted.org/packages/b5/36/7fb70f04bf00bc646cd5bb45aa9eddb15e19437a28b8fb2b4a5249fac770/filelock-3.20.3-py3-none-any.whl", hash = "sha256:4b0dda527ee31078689fc205ec4f1c1bf7d56cf88b6dc9426c4f230e46c2dce1", size = 16701, upload-time = "2026-01-09T17:55:04.334Z" }, ] [[package]] @@ -2090,7 +2090,7 @@ dependencies = [ { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/f6/1d/ac8914360460fafa1990890259b7fa5ef7ba4cd59014e782e4ab3ab144d8/filterpy-1.4.5.zip", hash = "sha256:4f2a4d39e4ea601b9ab42b2db08b5918a9538c168cff1c6895ae26646f3d73b1", size = 177985, upload-time = "2018-10-10T22:38:24.63Z" } @@ -2291,11 +2291,11 @@ wheels = [ [[package]] name = "fsspec" -version = "2025.12.0" +version = "2026.1.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/b6/27/954057b0d1f53f086f681755207dda6de6c660ce133c829158e8e8fe7895/fsspec-2025.12.0.tar.gz", hash = "sha256:c505de011584597b1060ff778bb664c1bc022e87921b0e4f10cc9c44f9635973", size = 309748, upload-time = "2025-12-03T15:23:42.687Z" } +sdist = { url = "https://files.pythonhosted.org/packages/d5/7d/5df2650c57d47c57232af5ef4b4fdbff182070421e405e0d62c6cdbfaa87/fsspec-2026.1.0.tar.gz", hash = "sha256:e987cb0496a0d81bba3a9d1cee62922fb395e7d4c3b575e57f547953334fe07b", size = 310496, upload-time = "2026-01-09T15:21:35.562Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/51/c7/b64cae5dba3a1b138d7123ec36bb5ccd39d39939f18454407e5468f4763f/fsspec-2025.12.0-py3-none-any.whl", hash = "sha256:8bf1fe301b7d8acfa6e8571e3b1c3d158f909666642431cc78a1b7b4dbc5ec5b", size = 201422, upload-time = "2025-12-03T15:23:41.434Z" }, + { url = "https://files.pythonhosted.org/packages/01/c9/97cc5aae1648dcb851958a3ddf73ccd7dbe5650d95203ecb4d7720b4cdbf/fsspec-2026.1.0-py3-none-any.whl", hash = "sha256:cb76aa913c2285a3b49bdd5fc55b1d7c708d7208126b60f2eb8194fe1b4cbdcc", size = 201838, upload-time = "2026-01-09T15:21:34.041Z" }, ] [[package]] @@ -2691,11 +2691,11 @@ wheels = [ [[package]] name = "identify" -version = "2.6.15" +version = "2.6.16" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/ff/e7/685de97986c916a6d93b3876139e00eef26ad5bbbd61925d670ae8013449/identify-2.6.15.tar.gz", hash = "sha256:e4f4864b96c6557ef2a1e1c951771838f4edc9df3a72ec7118b338801b11c7bf", size = 99311, upload-time = "2025-10-02T17:43:40.631Z" } +sdist = { url = "https://files.pythonhosted.org/packages/5b/8d/e8b97e6bd3fb6fb271346f7981362f1e04d6a7463abd0de79e1fda17c067/identify-2.6.16.tar.gz", hash = "sha256:846857203b5511bbe94d5a352a48ef2359532bc8f6727b5544077a0dcfb24980", size = 99360, upload-time = "2026-01-12T18:58:58.201Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/0f/1c/e5fd8f973d4f375adb21565739498e2e9a1e54c858a97b9a8ccfdc81da9b/identify-2.6.15-py2.py3-none-any.whl", hash = "sha256:1181ef7608e00704db228516541eb83a88a9f94433a8c80bb9b5bd54b1d81757", size = 99183, upload-time = "2025-10-02T17:43:39.137Z" }, + { url = "https://files.pythonhosted.org/packages/b8/58/40fbbcefeda82364720eba5cf2270f98496bdfa19ea75b4cccae79c698e6/identify-2.6.16-py2.py3-none-any.whl", hash = "sha256:391ee4d77741d994189522896270b787aed8670389bfd60f326d677d64a6dfb0", size = 99202, upload-time = "2026-01-12T18:58:56.627Z" }, ] [[package]] @@ -2915,7 +2915,7 @@ dependencies = [ { name = "ml-dtypes", marker = "python_full_version >= '3.11'" }, { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "opt-einsum", marker = "python_full_version >= '3.11'" }, - { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e6/25/5efb46e5492076622d9150ed394da97ef9aad393aa52f7dd7e980f836e1f/jax-0.8.2.tar.gz", hash = "sha256:1a685ded06a8223a7b52e45e668e406049dbbead02873f2b5a4d881ba7b421ae", size = 2505776, upload-time = "2025-12-18T18:41:59.274Z" } wheels = [ @@ -2979,7 +2979,7 @@ resolution-markers = [ dependencies = [ { name = "ml-dtypes", marker = "python_full_version >= '3.11'" }, { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, - { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/5f/87/0a44b1a5c558e6d8e4fd796d4f9efe5c8cac2b3013ab7349968c65931fa4/jaxlib-0.8.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:490bf0cb029c73c65c9431124b86cdc95082dbc1fb76fc549d24d75da33e5454", size = 55929353, upload-time = "2025-12-18T18:40:35.844Z" }, @@ -3018,7 +3018,7 @@ dependencies = [ { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/3a/da/ff7d7fbd13b8ed5e8458e80308d075fc649062b9f8676d3fc56f2dc99a82/jaxopt-0.8.5.tar.gz", hash = "sha256:2790bd68ef132b216c083a8bc7a2704eceb35a92c0fc0a1e652e79dfb1e9e9ab", size = 121709, upload-time = "2025-04-14T17:59:01.618Z" } wheels = [ @@ -3409,7 +3409,7 @@ wheels = [ [[package]] name = "langchain-core" -version = "1.2.6" +version = "1.2.7" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "jsonpatch" }, @@ -3421,9 +3421,9 @@ dependencies = [ { name = "typing-extensions" }, { name = "uuid-utils" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/b9/ce/ba5ed5ea6df22965b2893c2ed28ebb456204962723d408904c4acfa5e942/langchain_core-1.2.6.tar.gz", hash = "sha256:b4e7841dd7f8690375aa07c54739178dc2c635147d475e0c2955bf82a1afa498", size = 833343, upload-time = "2026-01-02T21:35:44.749Z" } +sdist = { url = "https://files.pythonhosted.org/packages/a2/0e/664d8d81b3493e09cbab72448d2f9d693d1fa5aa2bcc488602203a9b6da0/langchain_core-1.2.7.tar.gz", hash = "sha256:e1460639f96c352b4a41c375f25aeb8d16ffc1769499fb1c20503aad59305ced", size = 837039, upload-time = "2026-01-09T17:44:25.505Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/6f/40/0655892c245d8fbe6bca6d673ab5927e5c3ab7be143de40b52289a0663bc/langchain_core-1.2.6-py3-none-any.whl", hash = "sha256:aa6ed954b4b1f4504937fe75fdf674317027e9a91ba7a97558b0de3dc8004e34", size = 489096, upload-time = "2026-01-02T21:35:43.391Z" }, + { url = "https://files.pythonhosted.org/packages/6e/6f/34a9fba14d191a67f7e2ee3dbce3e9b86d2fa7310e2c7f2c713583481bd2/langchain_core-1.2.7-py3-none-any.whl", hash = "sha256:452f4fef7a3d883357b22600788d37e3d8854ef29da345b7ac7099f33c31828b", size = 490232, upload-time = "2026-01-09T17:44:24.236Z" }, ] [[package]] @@ -3481,7 +3481,7 @@ wheels = [ [[package]] name = "langgraph" -version = "1.0.5" +version = "1.0.6" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "langchain-core" }, @@ -3491,48 +3491,48 @@ dependencies = [ { name = "pydantic" }, { name = "xxhash" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/7d/47/28f4d4d33d88f69de26f7a54065961ac0c662cec2479b36a2db081ef5cb6/langgraph-1.0.5.tar.gz", hash = "sha256:7f6ae59622386b60fe9fa0ad4c53f42016b668455ed604329e7dc7904adbf3f8", size = 493969, upload-time = "2025-12-12T23:05:48.224Z" } +sdist = { url = "https://files.pythonhosted.org/packages/c2/9c/dac99ab1732e9fb2d3b673482ac28f02bee222c0319a3b8f8f73d90727e6/langgraph-1.0.6.tar.gz", hash = "sha256:dd8e754c76d34a07485308d7117221acf63990e7de8f46ddf5fe256b0a22e6c5", size = 495092, upload-time = "2026-01-12T20:33:30.778Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/23/1b/e318ee76e42d28f515d87356ac5bd7a7acc8bad3b8f54ee377bef62e1cbf/langgraph-1.0.5-py3-none-any.whl", hash = "sha256:b4cfd173dca3c389735b47228ad8b295e6f7b3df779aba3a1e0c23871f81281e", size = 157056, upload-time = "2025-12-12T23:05:46.499Z" }, + { url = "https://files.pythonhosted.org/packages/10/45/9960747781416bed4e531ed0c6b2f2c739bc7b5397d8e92155463735a40e/langgraph-1.0.6-py3-none-any.whl", hash = "sha256:bcfce190974519c72e29f6e5b17f0023914fd6f936bfab8894083215b271eb89", size = 157356, upload-time = "2026-01-12T20:33:29.191Z" }, ] [[package]] name = "langgraph-checkpoint" -version = "3.0.1" +version = "4.0.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "langchain-core" }, { name = "ormsgpack" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/0f/07/2b1c042fa87d40cf2db5ca27dc4e8dd86f9a0436a10aa4361a8982718ae7/langgraph_checkpoint-3.0.1.tar.gz", hash = "sha256:59222f875f85186a22c494aedc65c4e985a3df27e696e5016ba0b98a5ed2cee0", size = 137785, upload-time = "2025-11-04T21:55:47.774Z" } +sdist = { url = "https://files.pythonhosted.org/packages/98/76/55a18c59dedf39688d72c4b06af73a5e3ea0d1a01bc867b88fbf0659f203/langgraph_checkpoint-4.0.0.tar.gz", hash = "sha256:814d1bd050fac029476558d8e68d87bce9009a0262d04a2c14b918255954a624", size = 137320, upload-time = "2026-01-12T20:30:26.38Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/48/e3/616e3a7ff737d98c1bbb5700dd62278914e2a9ded09a79a1fa93cf24ce12/langgraph_checkpoint-3.0.1-py3-none-any.whl", hash = "sha256:9b04a8d0edc0474ce4eaf30c5d731cee38f11ddff50a6177eead95b5c4e4220b", size = 46249, upload-time = "2025-11-04T21:55:46.472Z" }, + { url = "https://files.pythonhosted.org/packages/4a/de/ddd53b7032e623f3c7bcdab2b44e8bf635e468f62e10e5ff1946f62c9356/langgraph_checkpoint-4.0.0-py3-none-any.whl", hash = "sha256:3fa9b2635a7c5ac28b338f631abf6a030c3b508b7b9ce17c22611513b589c784", size = 46329, upload-time = "2026-01-12T20:30:25.2Z" }, ] [[package]] name = "langgraph-prebuilt" -version = "1.0.5" +version = "1.0.6" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "langchain-core" }, { name = "langgraph-checkpoint" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/46/f9/54f8891b32159e4542236817aea2ee83de0de18bce28e9bdba08c7f93001/langgraph_prebuilt-1.0.5.tar.gz", hash = "sha256:85802675ad778cc7240fd02d47db1e0b59c0c86d8369447d77ce47623845db2d", size = 144453, upload-time = "2025-11-20T16:47:39.23Z" } +sdist = { url = "https://files.pythonhosted.org/packages/3c/f5/8c75dace0d729561dce2966e630c5e312193df7e5df41a7e10cd7378c3a7/langgraph_prebuilt-1.0.6.tar.gz", hash = "sha256:c5f6cf0f5a0ac47643d2e26ae6faa38cb28885ecde67911190df9e30c4f72361", size = 162623, upload-time = "2026-01-12T20:31:28.425Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/87/5e/aeba4a5b39fe6e874e0dd003a82da71c7153e671312671a8dacc5cb7c1af/langgraph_prebuilt-1.0.5-py3-none-any.whl", hash = "sha256:22369563e1848862ace53fbc11b027c28dd04a9ac39314633bb95f2a7e258496", size = 35072, upload-time = "2025-11-20T16:47:38.187Z" }, + { url = "https://files.pythonhosted.org/packages/26/6c/4045822b0630cfc0f8624c4499ceaf90644142143c063a8dc385a7424fc3/langgraph_prebuilt-1.0.6-py3-none-any.whl", hash = "sha256:9fdc35048ff4ac985a55bd2a019a86d45b8184551504aff6780d096c678b39ae", size = 35322, upload-time = "2026-01-12T20:31:27.161Z" }, ] [[package]] name = "langgraph-sdk" -version = "0.3.1" +version = "0.3.3" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "httpx" }, { name = "orjson" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/a9/d3/b6be0b0aba2a53a8920a2b0b4328a83121ec03eea9952e576d06a4182f6f/langgraph_sdk-0.3.1.tar.gz", hash = "sha256:f6dadfd2444eeff3e01405a9005c95fb3a028d4bd954ebec80ea6150084f92bb", size = 130312, upload-time = "2025-12-18T22:11:47.42Z" } +sdist = { url = "https://files.pythonhosted.org/packages/c3/0f/ed0634c222eed48a31ba48eab6881f94ad690d65e44fe7ca838240a260c1/langgraph_sdk-0.3.3.tar.gz", hash = "sha256:c34c3dce3b6848755eb61f0c94369d1ba04aceeb1b76015db1ea7362c544fb26", size = 130589, upload-time = "2026-01-13T00:30:43.894Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/ab/fe/0c1c9c01a154eba62b20b02fabe811fd94a2b810061ae9e4d8462b8cf85a/langgraph_sdk-0.3.1-py3-none-any.whl", hash = "sha256:0b856923bfd20bf3441ce9d03bef488aa333fb610e972618799a9d584436acad", size = 66517, upload-time = "2025-12-18T22:11:46.625Z" }, + { url = "https://files.pythonhosted.org/packages/6e/be/4ad511bacfdd854afb12974f407cb30010dceb982dc20c55491867b34526/langgraph_sdk-0.3.3-py3-none-any.whl", hash = "sha256:a52ebaf09d91143e55378bb2d0b033ed98f57f48c9ad35c8f81493b88705fc7b", size = 67021, upload-time = "2026-01-13T00:30:42.264Z" }, ] [[package]] @@ -4597,7 +4597,7 @@ dependencies = [ { name = "jaxlib", version = "0.8.2", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "mujoco" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "trimesh" }, ] sdist = { url = "https://files.pythonhosted.org/packages/cb/57/2cebcde17bdad9c575c71a301ea1524eb9dba76a974e24f07abf714050be/mujoco_mjx-3.4.0.tar.gz", hash = "sha256:10fa51a92c22affd27c9205c5fb965c14c256729ab58fd2021dc9e4df9bedec6", size = 6872370, upload-time = "2025-12-05T23:14:13.734Z" } @@ -5212,7 +5212,7 @@ wheels = [ [[package]] name = "onnx" -version = "1.20.0" +version = "1.20.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "ml-dtypes" }, @@ -5221,30 +5221,30 @@ dependencies = [ { name = "protobuf" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/bd/bf/824b13b7ea14c2d374b48a296cfa412442e5559326fbab5441a4fcb68924/onnx-1.20.0.tar.gz", hash = "sha256:1a93ec69996b4556062d552ed1aa0671978cfd3c17a40bf4c89a1ae169c6a4ad", size = 12049527, upload-time = "2025-12-01T18:14:34.679Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/23/18/8fd768f715a990d3b5786c9bffa6f158934cc1935f2774dd15b26c62f99f/onnx-1.20.0-cp310-cp310-macosx_12_0_universal2.whl", hash = "sha256:7e706470f8b731af6d0347c4f01b8e0e1810855d0c71c467066a5bd7fa21704b", size = 18341375, upload-time = "2025-12-01T18:13:29.481Z" }, - { url = "https://files.pythonhosted.org/packages/cf/47/9fdb6e8bde5f77f8bdcf7e584ad88ffa7a189338b92658351518c192bde0/onnx-1.20.0-cp310-cp310-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:3e941d0f3edd57e1d63e2562c74aec2803ead5b965e76ccc3d2b2bd4ae0ea054", size = 17899075, upload-time = "2025-12-01T18:13:32.375Z" }, - { url = "https://files.pythonhosted.org/packages/b2/17/7bb16372f95a8a8251c202018952a747ac7f796a9e6d5720ed7b36680834/onnx-1.20.0-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6930ed7795912c4298ec8642b33c99c51c026a57edf17788b8451fe22d11e674", size = 18118826, upload-time = "2025-12-01T18:13:35.077Z" }, - { url = "https://files.pythonhosted.org/packages/19/d8/19e3f599601195b1d8ff0bf9e9469065ebeefd9b5e5ec090344f031c38cb/onnx-1.20.0-cp310-cp310-win32.whl", hash = "sha256:f8424c95491de38ecc280f7d467b298cb0b7cdeb1cd892eb9b4b9541c00a600e", size = 16364286, upload-time = "2025-12-01T18:13:38.304Z" }, - { url = "https://files.pythonhosted.org/packages/5d/f9/11d2db50a6c56092bd2e22515fe6998309c7b2389ed67f8ffd27285c33b5/onnx-1.20.0-cp310-cp310-win_amd64.whl", hash = "sha256:1ecca1f963d69e002c03000f15844f8cac3b6d7b6639a934e73571ee02d59c35", size = 16487791, upload-time = "2025-12-01T18:13:41.062Z" }, - { url = "https://files.pythonhosted.org/packages/9e/9a/125ad5ed919d1782b26b0b4404e51adc44afd029be30d5a81b446dccd9c5/onnx-1.20.0-cp311-cp311-macosx_12_0_universal2.whl", hash = "sha256:00dc8ae2c7b283f79623961f450b5515bd2c4b47a7027e7a1374ba49cef27768", size = 18341929, upload-time = "2025-12-01T18:13:43.79Z" }, - { url = "https://files.pythonhosted.org/packages/4d/3c/85280dd05396493f3e1b4feb7a3426715e344b36083229437f31d9788a01/onnx-1.20.0-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f62978ecfb8f320faba6704abd20253a5a79aacc4e5d39a9c061dd63d3b7574f", size = 17899362, upload-time = "2025-12-01T18:13:46.496Z" }, - { url = "https://files.pythonhosted.org/packages/26/db/e11cf9aaa6ccbcd27ea94d321020fef3207cba388bff96111e6431f97d1a/onnx-1.20.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:71177f8fd5c0dd90697bc281f5035f73707bdac83257a5c54d74403a1100ace9", size = 18119129, upload-time = "2025-12-01T18:13:49.662Z" }, - { url = "https://files.pythonhosted.org/packages/ef/0b/1b99e7ba5ccfa8ecb3509ec579c8520098d09b903ccd520026d60faa7c75/onnx-1.20.0-cp311-cp311-win32.whl", hash = "sha256:1d3d0308e2c194f4b782f51e78461b567fac8ce6871c0cf5452ede261683cc8f", size = 16364604, upload-time = "2025-12-01T18:13:52.691Z" }, - { url = "https://files.pythonhosted.org/packages/51/ab/7399817821d0d18ff67292ac183383e41f4f4ddff2047902f1b7b51d2d40/onnx-1.20.0-cp311-cp311-win_amd64.whl", hash = "sha256:3a6de7dda77926c323b0e5a830dc9c2866ce350c1901229e193be1003a076c25", size = 16488019, upload-time = "2025-12-01T18:13:55.776Z" }, - { url = "https://files.pythonhosted.org/packages/fd/e0/23059c11d9c0fb1951acec504a5cc86e1dd03d2eef3a98cf1941839f5322/onnx-1.20.0-cp311-cp311-win_arm64.whl", hash = "sha256:afc4cf83ce5d547ebfbb276dae8eb0ec836254a8698d462b4ba5f51e717fd1ae", size = 16446841, upload-time = "2025-12-01T18:13:58.091Z" }, - { url = "https://files.pythonhosted.org/packages/5e/19/2caa972a31014a8cb4525f715f2a75d93caef9d4b9da2809cc05d0489e43/onnx-1.20.0-cp312-abi3-macosx_12_0_universal2.whl", hash = "sha256:31efe37d7d1d659091f34ddd6a31780334acf7c624176832db9a0a8ececa8fb5", size = 18340913, upload-time = "2025-12-01T18:14:00.477Z" }, - { url = "https://files.pythonhosted.org/packages/78/bb/b98732309f2f6beb4cdcf7b955d7bbfd75a191185370ee21233373db381e/onnx-1.20.0-cp312-abi3-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:d75da05e743eb9a11ff155a775cae5745e71f1cd0ca26402881b8f20e8d6e449", size = 17896118, upload-time = "2025-12-01T18:14:03.239Z" }, - { url = "https://files.pythonhosted.org/packages/84/a7/38aa564871d062c11538d65c575af9c7e057be880c09ecbd899dd1abfa83/onnx-1.20.0-cp312-abi3-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:02e0d72ab09a983fce46686b155a5049898558d9f3bc6e8515120d6c40666318", size = 18115415, upload-time = "2025-12-01T18:14:06.261Z" }, - { url = "https://files.pythonhosted.org/packages/3b/17/a600b62cf4ad72976c66f83ce9e324205af434706ad5ec0e35129e125aef/onnx-1.20.0-cp312-abi3-win32.whl", hash = "sha256:392ca68b34b97e172d33b507e1e7bfdf2eea96603e6e7ff109895b82ff009dc7", size = 16363019, upload-time = "2025-12-01T18:14:09.16Z" }, - { url = "https://files.pythonhosted.org/packages/9c/3b/5146ba0a89f73c026bb468c49612bab8d005aa28155ebf06cf5f2eb8d36c/onnx-1.20.0-cp312-abi3-win_amd64.whl", hash = "sha256:259b05758d41645f5545c09f887187662b350d40db8d707c33c94a4f398e1733", size = 16485934, upload-time = "2025-12-01T18:14:13.046Z" }, - { url = "https://files.pythonhosted.org/packages/f3/bc/d251b97395e721b3034e9578d4d4d9fb33aac4197ae16ce8c7ed79a26dce/onnx-1.20.0-cp312-abi3-win_arm64.whl", hash = "sha256:2d25a9e1fde44bc69988e50e2211f62d6afcd01b0fd6dfd23429fd978a35d32f", size = 16444946, upload-time = "2025-12-01T18:14:15.801Z" }, - { url = "https://files.pythonhosted.org/packages/8d/11/4d47409e257013951a17d08c31988e7c2e8638c91d4d5ce18cc57c6ea9d9/onnx-1.20.0-cp313-cp313t-macosx_12_0_universal2.whl", hash = "sha256:7646e700c0a53770a86d5a9a582999a625a3173c4323635960aec3cba8441c6a", size = 18348524, upload-time = "2025-12-01T18:14:18.102Z" }, - { url = "https://files.pythonhosted.org/packages/67/60/774d29a0f00f84a4ec624fe35e0c59e1dbd7f424adaab751977a45b60e05/onnx-1.20.0-cp313-cp313t-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:d0bdfd22fe92b87bf98424335ec1191ed79b08cd0f57fe396fab558b83b2c868", size = 17900987, upload-time = "2025-12-01T18:14:20.835Z" }, - { url = "https://files.pythonhosted.org/packages/9c/7c/6bd82b81b85b2680e3de8cf7b6cc49a7380674b121265bb6e1e2ff3bb0aa/onnx-1.20.0-cp313-cp313t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9d1a4e02148b2a7a4b82796d0ecdb6e49ba7abd34bb5a9de22af86aad556fb76", size = 18121332, upload-time = "2025-12-01T18:14:24.558Z" }, - { url = "https://files.pythonhosted.org/packages/d1/42/d2cd00c84def4e17b471e24d82a1d2e3c5be202e2c163420b0353ddf34df/onnx-1.20.0-cp313-cp313t-win_amd64.whl", hash = "sha256:2241c85fdaa25a66565fcd1d327c7bcd8f55165420ebaee1e9563c3b9bf961c9", size = 16492660, upload-time = "2025-12-01T18:14:27.456Z" }, - { url = "https://files.pythonhosted.org/packages/42/cd/1106de50a17f2a2dfbb4c8bb3cf2f99be2c7ac2e19abbbf9e07ab47b1b35/onnx-1.20.0-cp313-cp313t-win_arm64.whl", hash = "sha256:ee46cdc5abd851a007a4be81ee53e0e303cf9a0e46d74231d5d361333a1c9411", size = 16448588, upload-time = "2025-12-01T18:14:32.277Z" }, +sdist = { url = "https://files.pythonhosted.org/packages/3b/8a/335c03a8683a88a32f9a6bb98899ea6df241a41df64b37b9696772414794/onnx-1.20.1.tar.gz", hash = "sha256:ded16de1df563d51fbc1ad885f2a426f814039d8b5f4feb77febe09c0295ad67", size = 12048980, upload-time = "2026-01-10T01:40:03.043Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/79/cc/4ba3c80cfaffdb541dc5a23eaccb045a627361e94ecaeba30496270f15b3/onnx-1.20.1-cp310-cp310-macosx_12_0_universal2.whl", hash = "sha256:3fe243e83ad737637af6512708454e720d4b0864def2b28e6b0ee587b80a50be", size = 17904206, upload-time = "2026-01-10T01:38:58.574Z" }, + { url = "https://files.pythonhosted.org/packages/f3/fc/3a1c4ae2cd5cfab2d0ebc1842769b04b417fe13946144a7c8ce470dd9c85/onnx-1.20.1-cp310-cp310-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:e24e96b48f27e4d6b44cb0b195b367a2665da2d819621eec51903d575fc49d38", size = 17414849, upload-time = "2026-01-10T01:39:01.494Z" }, + { url = "https://files.pythonhosted.org/packages/a4/ab/5017945291b981f2681fb620f2d5b6070e02170c648770711ef1eac79d56/onnx-1.20.1-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:0903e6088ed5e8f59ebd381ab2a6e9b2a60b4c898f79aa2fe76bb79cf38a5031", size = 17513600, upload-time = "2026-01-10T01:39:04.348Z" }, + { url = "https://files.pythonhosted.org/packages/2e/b0/063e79dc365972af876d786bacc6acd8909691af2b9296615ff74ad182f3/onnx-1.20.1-cp310-cp310-win32.whl", hash = "sha256:17483e59082b2ca6cadd2b48fd8dce937e5b2c985ed5583fefc38af928be1826", size = 16239159, upload-time = "2026-01-10T01:39:07.254Z" }, + { url = "https://files.pythonhosted.org/packages/2a/73/a992271eb3683e676239d71b5a78ad3cf4d06d2223c387e701bf305da199/onnx-1.20.1-cp310-cp310-win_amd64.whl", hash = "sha256:e2b0cf797faedfd3b83491dc168ab5f1542511448c65ceb482f20f04420cbf3a", size = 16391718, upload-time = "2026-01-10T01:39:09.96Z" }, + { url = "https://files.pythonhosted.org/packages/0c/38/1a0e74d586c08833404100f5c052f92732fb5be417c0b2d7cb0838443bfe/onnx-1.20.1-cp311-cp311-macosx_12_0_universal2.whl", hash = "sha256:53426e1b458641e7a537e9f176330012ff59d90206cac1c1a9d03cdd73ed3095", size = 17904965, upload-time = "2026-01-10T01:39:13.532Z" }, + { url = "https://files.pythonhosted.org/packages/96/25/64b076e9684d17335f80b15b3bf502f7a8e1a89f08a6b208d4f2861b3011/onnx-1.20.1-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:ca7281f8c576adf396c338cf43fff26faee8d4d2e2577b8e73738f37ceccf945", size = 17415179, upload-time = "2026-01-10T01:39:16.516Z" }, + { url = "https://files.pythonhosted.org/packages/ac/d5/6743b409421ced20ad5af1b3a7b4c4e568689ffaca86db431692fca409a6/onnx-1.20.1-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:2297f428c51c7fc6d8fad0cf34384284dfeff3f86799f8e83ef905451348ade0", size = 17513672, upload-time = "2026-01-10T01:39:19.35Z" }, + { url = "https://files.pythonhosted.org/packages/9a/6b/dae82e6fdb2043302f29adca37522312ea2be55b75907b59be06fbdffe87/onnx-1.20.1-cp311-cp311-win32.whl", hash = "sha256:63d9cbcab8c96841eadeb7c930e07bfab4dde8081eb76fb68e0dfb222706b81e", size = 16239336, upload-time = "2026-01-10T01:39:22.506Z" }, + { url = "https://files.pythonhosted.org/packages/8e/17/a0d7863390c1f2067d7c02dcc1477034965c32aaa1407bfcf775305ffee4/onnx-1.20.1-cp311-cp311-win_amd64.whl", hash = "sha256:d78cde72d7ca8356a2d99c5dc0dbf67264254828cae2c5780184486c0cd7b3bf", size = 16392120, upload-time = "2026-01-10T01:39:25.106Z" }, + { url = "https://files.pythonhosted.org/packages/aa/72/9b879a46eb7a3322223791f36bf9c25d95da9ed93779eabb75a560f22e5b/onnx-1.20.1-cp311-cp311-win_arm64.whl", hash = "sha256:0104bb2d4394c179bcea3df7599a45a2932b80f4633840896fcf0d7d8daecea2", size = 16346923, upload-time = "2026-01-10T01:39:27.782Z" }, + { url = "https://files.pythonhosted.org/packages/7c/4c/4b17e82f91ab9aa07ff595771e935ca73547b035030dc5f5a76e63fbfea9/onnx-1.20.1-cp312-abi3-macosx_12_0_universal2.whl", hash = "sha256:1d923bb4f0ce1b24c6859222a7e6b2f123e7bfe7623683662805f2e7b9e95af2", size = 17903547, upload-time = "2026-01-10T01:39:31.015Z" }, + { url = "https://files.pythonhosted.org/packages/64/5e/1bfa100a9cb3f2d3d5f2f05f52f7e60323b0e20bb0abace1ae64dbc88f25/onnx-1.20.1-cp312-abi3-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:ddc0b7d8b5a94627dc86c533d5e415af94cbfd103019a582669dad1f56d30281", size = 17412021, upload-time = "2026-01-10T01:39:33.885Z" }, + { url = "https://files.pythonhosted.org/packages/fb/71/d3fec0dcf9a7a99e7368112d9c765154e81da70fcba1e3121131a45c245b/onnx-1.20.1-cp312-abi3-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9336b6b8e6efcf5c490a845f6afd7e041c89a56199aeda384ed7d58fb953b080", size = 17510450, upload-time = "2026-01-10T01:39:36.589Z" }, + { url = "https://files.pythonhosted.org/packages/74/a7/edce1403e05a46e59b502fae8e3350ceeac5841f8e8f1561e98562ed9b09/onnx-1.20.1-cp312-abi3-win32.whl", hash = "sha256:564c35a94811979808ab5800d9eb4f3f32c12daedba7e33ed0845f7c61ef2431", size = 16238216, upload-time = "2026-01-10T01:39:39.46Z" }, + { url = "https://files.pythonhosted.org/packages/8b/c7/8690c81200ae652ac550c1df52f89d7795e6cc941f3cb38c9ef821419e80/onnx-1.20.1-cp312-abi3-win_amd64.whl", hash = "sha256:9fe7f9a633979d50984b94bda8ceb7807403f59a341d09d19342dc544d0ca1d5", size = 16389207, upload-time = "2026-01-10T01:39:41.955Z" }, + { url = "https://files.pythonhosted.org/packages/01/a0/4fb0e6d36eaf079af366b2c1f68bafe92df6db963e2295da84388af64abc/onnx-1.20.1-cp312-abi3-win_arm64.whl", hash = "sha256:21d747348b1c8207406fa2f3e12b82f53e0d5bb3958bcd0288bd27d3cb6ebb00", size = 16344155, upload-time = "2026-01-10T01:39:45.536Z" }, + { url = "https://files.pythonhosted.org/packages/ea/bb/715fad292b255664f0e603f1b2ef7bf2b386281775f37406beb99fa05957/onnx-1.20.1-cp313-cp313t-macosx_12_0_universal2.whl", hash = "sha256:29197b768f5acdd1568ddeb0a376407a2817844f6ac1ef8c8dd2d974c9ab27c3", size = 17912296, upload-time = "2026-01-10T01:39:48.21Z" }, + { url = "https://files.pythonhosted.org/packages/2d/c3/541af12c3d45e159a94ee701100ba9e94b7bd8b7a8ac5ca6838569f894f8/onnx-1.20.1-cp313-cp313t-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:1f0371aa67f51917a09cc829ada0f9a79a58f833449e03d748f7f7f53787c43c", size = 17416925, upload-time = "2026-01-10T01:39:50.82Z" }, + { url = "https://files.pythonhosted.org/packages/2c/3b/d5660a7d2ddf14f531ca66d409239f543bb290277c3f14f4b4b78e32efa3/onnx-1.20.1-cp313-cp313t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:be1e5522200b203b34327b2cf132ddec20ab063469476e1f5b02bb7bd259a489", size = 17515602, upload-time = "2026-01-10T01:39:54.132Z" }, + { url = "https://files.pythonhosted.org/packages/9c/b4/47225ab2a92562eff87ba9a1a028e3535d659a7157d7cde659003998b8e3/onnx-1.20.1-cp313-cp313t-win_amd64.whl", hash = "sha256:15c815313bbc4b2fdc7e4daeb6e26b6012012adc4d850f4e3b09ed327a7ea92a", size = 16395729, upload-time = "2026-01-10T01:39:57.577Z" }, + { url = "https://files.pythonhosted.org/packages/aa/7d/1bbe626ff6b192c844d3ad34356840cc60fca02e2dea0db95e01645758b1/onnx-1.20.1-cp313-cp313t-win_arm64.whl", hash = "sha256:eb335d7bcf9abac82a0d6a0fda0363531ae0b22cfd0fc6304bff32ee29905def", size = 16348968, upload-time = "2026-01-10T01:40:00.491Z" }, ] [[package]] @@ -5365,7 +5365,7 @@ wheels = [ [[package]] name = "openai" -version = "2.14.0" +version = "2.15.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "anyio" }, @@ -5377,9 +5377,9 @@ dependencies = [ { name = "tqdm" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/d8/b1/12fe1c196bea326261718eb037307c1c1fe1dedc2d2d4de777df822e6238/openai-2.14.0.tar.gz", hash = "sha256:419357bedde9402d23bf8f2ee372fca1985a73348debba94bddff06f19459952", size = 626938, upload-time = "2025-12-19T03:28:45.742Z" } +sdist = { url = "https://files.pythonhosted.org/packages/94/f4/4690ecb5d70023ce6bfcfeabfe717020f654bde59a775058ec6ac4692463/openai-2.15.0.tar.gz", hash = "sha256:42eb8cbb407d84770633f31bf727d4ffb4138711c670565a41663d9439174fba", size = 627383, upload-time = "2026-01-09T22:10:08.603Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/27/4b/7c1a00c2c3fbd004253937f7520f692a9650767aa73894d7a34f0d65d3f4/openai-2.14.0-py3-none-any.whl", hash = "sha256:7ea40aca4ffc4c4a776e77679021b47eec1160e341f42ae086ba949c9dcc9183", size = 1067558, upload-time = "2025-12-19T03:28:43.727Z" }, + { url = "https://files.pythonhosted.org/packages/b5/df/c306f7375d42bafb379934c2df4c2fa3964656c8c782bac75ee10c102818/openai-2.15.0-py3-none-any.whl", hash = "sha256:6ae23b932cd7230f7244e52954daa6602716d6b9bf235401a107af731baea6c3", size = 1067879, upload-time = "2026-01-09T22:10:06.446Z" }, ] [[package]] @@ -5999,28 +5999,30 @@ wheels = [ [[package]] name = "polars" -version = "1.36.1" +version = "1.37.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "polars-runtime-32" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/9f/dc/56f2a90c79a2cb13f9e956eab6385effe54216ae7a2068b3a6406bae4345/polars-1.36.1.tar.gz", hash = "sha256:12c7616a2305559144711ab73eaa18814f7aa898c522e7645014b68f1432d54c", size = 711993, upload-time = "2025-12-10T01:14:53.033Z" } +sdist = { url = "https://files.pythonhosted.org/packages/84/ae/dfebf31b9988c20998140b54d5b521f64ce08879f2c13d9b4d44d7c87e32/polars-1.37.1.tar.gz", hash = "sha256:0309e2a4633e712513401964b4d95452f124ceabf7aec6db50affb9ced4a274e", size = 715572, upload-time = "2026-01-12T23:27:03.267Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/f6/c6/36a1b874036b49893ecae0ac44a2f63d1a76e6212631a5b2f50a86e0e8af/polars-1.36.1-py3-none-any.whl", hash = "sha256:853c1bbb237add6a5f6d133c15094a9b727d66dd6a4eb91dbb07cdb056b2b8ef", size = 802429, upload-time = "2025-12-10T01:13:53.838Z" }, + { url = "https://files.pythonhosted.org/packages/08/75/ec73e38812bca7c2240aff481b9ddff20d1ad2f10dee4b3353f5eeaacdab/polars-1.37.1-py3-none-any.whl", hash = "sha256:377fed8939a2f1223c1563cfabdc7b4a3d6ff846efa1f2ddeb8644fafd9b1aff", size = 805749, upload-time = "2026-01-12T23:25:48.595Z" }, ] [[package]] name = "polars-runtime-32" -version = "1.36.1" +version = "1.37.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/31/df/597c0ef5eb8d761a16d72327846599b57c5d40d7f9e74306fc154aba8c37/polars_runtime_32-1.36.1.tar.gz", hash = "sha256:201c2cfd80ceb5d5cd7b63085b5fd08d6ae6554f922bcb941035e39638528a09", size = 2788751, upload-time = "2025-12-10T01:14:54.172Z" } +sdist = { url = "https://files.pythonhosted.org/packages/40/0b/addabe5e8d28a5a4c9887a08907be7ddc3fce892dc38f37d14b055438a57/polars_runtime_32-1.37.1.tar.gz", hash = "sha256:68779d4a691da20a5eb767d74165a8f80a2bdfbde4b54acf59af43f7fa028d8f", size = 2818945, upload-time = "2026-01-12T23:27:04.653Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/e1/ea/871129a2d296966c0925b078a9a93c6c5e7facb1c5eebfcd3d5811aeddc1/polars_runtime_32-1.36.1-cp39-abi3-macosx_10_12_x86_64.whl", hash = "sha256:327b621ca82594f277751f7e23d4b939ebd1be18d54b4cdf7a2f8406cecc18b2", size = 43494311, upload-time = "2025-12-10T01:13:56.096Z" }, - { url = "https://files.pythonhosted.org/packages/d8/76/0038210ad1e526ce5bb2933b13760d6b986b3045eccc1338e661bd656f77/polars_runtime_32-1.36.1-cp39-abi3-macosx_11_0_arm64.whl", hash = "sha256:ab0d1f23084afee2b97de8c37aa3e02ec3569749ae39571bd89e7a8b11ae9e83", size = 39300602, upload-time = "2025-12-10T01:13:59.366Z" }, - { url = "https://files.pythonhosted.org/packages/54/1e/2707bee75a780a953a77a2c59829ee90ef55708f02fc4add761c579bf76e/polars_runtime_32-1.36.1-cp39-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:899b9ad2e47ceb31eb157f27a09dbc2047efbf4969a923a6b1ba7f0412c3e64c", size = 44511780, upload-time = "2025-12-10T01:14:02.285Z" }, - { url = "https://files.pythonhosted.org/packages/11/b2/3fede95feee441be64b4bcb32444679a8fbb7a453a10251583053f6efe52/polars_runtime_32-1.36.1-cp39-abi3-manylinux_2_24_aarch64.whl", hash = "sha256:d9d077bb9df711bc635a86540df48242bb91975b353e53ef261c6fae6cb0948f", size = 40688448, upload-time = "2025-12-10T01:14:05.131Z" }, - { url = "https://files.pythonhosted.org/packages/05/0f/e629713a72999939b7b4bfdbf030a32794db588b04fdf3dc977dd8ea6c53/polars_runtime_32-1.36.1-cp39-abi3-win_amd64.whl", hash = "sha256:cc17101f28c9a169ff8b5b8d4977a3683cd403621841623825525f440b564cf0", size = 44464898, upload-time = "2025-12-10T01:14:08.296Z" }, - { url = "https://files.pythonhosted.org/packages/d1/d8/a12e6aa14f63784cead437083319ec7cece0d5bb9a5bfe7678cc6578b52a/polars_runtime_32-1.36.1-cp39-abi3-win_arm64.whl", hash = "sha256:809e73857be71250141225ddd5d2b30c97e6340aeaa0d445f930e01bef6888dc", size = 39798896, upload-time = "2025-12-10T01:14:11.568Z" }, + { url = "https://files.pythonhosted.org/packages/2a/a2/e828ea9f845796de02d923edb790e408ca0b560cd68dbd74bb99a1b3c461/polars_runtime_32-1.37.1-cp310-abi3-macosx_10_12_x86_64.whl", hash = "sha256:0b8d4d73ea9977d3731927740e59d814647c5198bdbe359bcf6a8bfce2e79771", size = 43499912, upload-time = "2026-01-12T23:25:51.182Z" }, + { url = "https://files.pythonhosted.org/packages/7e/46/81b71b7aa9e3703ee6e4ef1f69a87e40f58ea7c99212bf49a95071e99c8c/polars_runtime_32-1.37.1-cp310-abi3-macosx_11_0_arm64.whl", hash = "sha256:c682bf83f5f352e5e02f5c16c652c48ca40442f07b236f30662b22217320ce76", size = 39695707, upload-time = "2026-01-12T23:25:54.289Z" }, + { url = "https://files.pythonhosted.org/packages/81/2e/20009d1fde7ee919e24040f5c87cb9d0e4f8e3f109b74ba06bc10c02459c/polars_runtime_32-1.37.1-cp310-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:fc82b5bbe70ca1a4b764eed1419f6336752d6ba9fc1245388d7f8b12438afa2c", size = 41467034, upload-time = "2026-01-12T23:25:56.925Z" }, + { url = "https://files.pythonhosted.org/packages/eb/21/9b55bea940524324625b1e8fd96233290303eb1bf2c23b54573487bbbc25/polars_runtime_32-1.37.1-cp310-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a8362d11ac5193b994c7e9048ffe22ccfb976699cfbf6e128ce0302e06728894", size = 45142711, upload-time = "2026-01-12T23:26:00.817Z" }, + { url = "https://files.pythonhosted.org/packages/8c/25/c5f64461aeccdac6834a89f826d051ccd3b4ce204075e562c87a06ed2619/polars_runtime_32-1.37.1-cp310-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:04f5d5a2f013dca7391b7d8e7672fa6d37573a87f1d45d3dd5f0d9b5565a4b0f", size = 41638564, upload-time = "2026-01-12T23:26:04.186Z" }, + { url = "https://files.pythonhosted.org/packages/35/af/509d3cf6c45e764ccf856beaae26fc34352f16f10f94a7839b1042920a73/polars_runtime_32-1.37.1-cp310-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:fbfde7c0ca8209eeaed546e4a32cca1319189aa61c5f0f9a2b4494262bd0c689", size = 44721136, upload-time = "2026-01-12T23:26:07.088Z" }, + { url = "https://files.pythonhosted.org/packages/af/d1/5c0a83a625f72beef59394bebc57d12637997632a4f9d3ab2ffc2cc62bbf/polars_runtime_32-1.37.1-cp310-abi3-win_amd64.whl", hash = "sha256:da3d3642ae944e18dd17109d2a3036cb94ce50e5495c5023c77b1599d4c861bc", size = 44948288, upload-time = "2026-01-12T23:26:10.214Z" }, + { url = "https://files.pythonhosted.org/packages/10/f3/061bb702465904b6502f7c9081daee34b09ccbaa4f8c94cf43a2a3b6dd6f/polars_runtime_32-1.37.1-cp310-abi3-win_arm64.whl", hash = "sha256:55f2c4847a8d2e267612f564de7b753a4bde3902eaabe7b436a0a4abf75949a0", size = 41001914, upload-time = "2026-01-12T23:26:12.997Z" }, ] [[package]] @@ -6069,17 +6071,17 @@ wheels = [ [[package]] name = "protobuf" -version = "6.33.2" +version = "6.33.4" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/34/44/e49ecff446afeec9d1a66d6bbf9adc21e3c7cea7803a920ca3773379d4f6/protobuf-6.33.2.tar.gz", hash = "sha256:56dc370c91fbb8ac85bc13582c9e373569668a290aa2e66a590c2a0d35ddb9e4", size = 444296, upload-time = "2025-12-06T00:17:53.311Z" } +sdist = { url = "https://files.pythonhosted.org/packages/53/b8/cda15d9d46d03d4aa3a67cb6bffe05173440ccf86a9541afaf7ac59a1b6b/protobuf-6.33.4.tar.gz", hash = "sha256:dc2e61bca3b10470c1912d166fe0af67bfc20eb55971dcef8dfa48ce14f0ed91", size = 444346, upload-time = "2026-01-12T18:33:40.109Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/bc/91/1e3a34881a88697a7354ffd177e8746e97a722e5e8db101544b47e84afb1/protobuf-6.33.2-cp310-abi3-win32.whl", hash = "sha256:87eb388bd2d0f78febd8f4c8779c79247b26a5befad525008e49a6955787ff3d", size = 425603, upload-time = "2025-12-06T00:17:41.114Z" }, - { url = "https://files.pythonhosted.org/packages/64/20/4d50191997e917ae13ad0a235c8b42d8c1ab9c3e6fd455ca16d416944355/protobuf-6.33.2-cp310-abi3-win_amd64.whl", hash = "sha256:fc2a0e8b05b180e5fc0dd1559fe8ebdae21a27e81ac77728fb6c42b12c7419b4", size = 436930, upload-time = "2025-12-06T00:17:43.278Z" }, - { url = "https://files.pythonhosted.org/packages/b2/ca/7e485da88ba45c920fb3f50ae78de29ab925d9e54ef0de678306abfbb497/protobuf-6.33.2-cp39-abi3-macosx_10_9_universal2.whl", hash = "sha256:d9b19771ca75935b3a4422957bc518b0cecb978b31d1dd12037b088f6bcc0e43", size = 427621, upload-time = "2025-12-06T00:17:44.445Z" }, - { url = "https://files.pythonhosted.org/packages/7d/4f/f743761e41d3b2b2566748eb76bbff2b43e14d5fcab694f494a16458b05f/protobuf-6.33.2-cp39-abi3-manylinux2014_aarch64.whl", hash = "sha256:b5d3b5625192214066d99b2b605f5783483575656784de223f00a8d00754fc0e", size = 324460, upload-time = "2025-12-06T00:17:45.678Z" }, - { url = "https://files.pythonhosted.org/packages/b1/fa/26468d00a92824020f6f2090d827078c09c9c587e34cbfd2d0c7911221f8/protobuf-6.33.2-cp39-abi3-manylinux2014_s390x.whl", hash = "sha256:8cd7640aee0b7828b6d03ae518b5b4806fdfc1afe8de82f79c3454f8aef29872", size = 339168, upload-time = "2025-12-06T00:17:46.813Z" }, - { url = "https://files.pythonhosted.org/packages/56/13/333b8f421738f149d4fe5e49553bc2a2ab75235486259f689b4b91f96cec/protobuf-6.33.2-cp39-abi3-manylinux2014_x86_64.whl", hash = "sha256:1f8017c48c07ec5859106533b682260ba3d7c5567b1ca1f24297ce03384d1b4f", size = 323270, upload-time = "2025-12-06T00:17:48.253Z" }, - { url = "https://files.pythonhosted.org/packages/0e/15/4f02896cc3df04fc465010a4c6a0cd89810f54617a32a70ef531ed75d61c/protobuf-6.33.2-py3-none-any.whl", hash = "sha256:7636aad9bb01768870266de5dc009de2d1b936771b38a793f73cbbf279c91c5c", size = 170501, upload-time = "2025-12-06T00:17:52.211Z" }, + { url = "https://files.pythonhosted.org/packages/e0/be/24ef9f3095bacdf95b458543334d0c4908ccdaee5130420bf064492c325f/protobuf-6.33.4-cp310-abi3-win32.whl", hash = "sha256:918966612c8232fc6c24c78e1cd89784307f5814ad7506c308ee3cf86662850d", size = 425612, upload-time = "2026-01-12T18:33:29.656Z" }, + { url = "https://files.pythonhosted.org/packages/31/ad/e5693e1974a28869e7cd244302911955c1cebc0161eb32dfa2b25b6e96f0/protobuf-6.33.4-cp310-abi3-win_amd64.whl", hash = "sha256:8f11ffae31ec67fc2554c2ef891dcb561dae9a2a3ed941f9e134c2db06657dbc", size = 436962, upload-time = "2026-01-12T18:33:31.345Z" }, + { url = "https://files.pythonhosted.org/packages/66/15/6ee23553b6bfd82670207ead921f4d8ef14c107e5e11443b04caeb5ab5ec/protobuf-6.33.4-cp39-abi3-macosx_10_9_universal2.whl", hash = "sha256:2fe67f6c014c84f655ee06f6f66213f9254b3a8b6bda6cda0ccd4232c73c06f0", size = 427612, upload-time = "2026-01-12T18:33:32.646Z" }, + { url = "https://files.pythonhosted.org/packages/2b/48/d301907ce6d0db75f959ca74f44b475a9caa8fcba102d098d3c3dd0f2d3f/protobuf-6.33.4-cp39-abi3-manylinux2014_aarch64.whl", hash = "sha256:757c978f82e74d75cba88eddec479df9b99a42b31193313b75e492c06a51764e", size = 324484, upload-time = "2026-01-12T18:33:33.789Z" }, + { url = "https://files.pythonhosted.org/packages/92/1c/e53078d3f7fe710572ab2dcffd993e1e3b438ae71cfc031b71bae44fcb2d/protobuf-6.33.4-cp39-abi3-manylinux2014_s390x.whl", hash = "sha256:c7c64f259c618f0bef7bee042075e390debbf9682334be2b67408ec7c1c09ee6", size = 339256, upload-time = "2026-01-12T18:33:35.231Z" }, + { url = "https://files.pythonhosted.org/packages/e8/8e/971c0edd084914f7ee7c23aa70ba89e8903918adca179319ee94403701d5/protobuf-6.33.4-cp39-abi3-manylinux2014_x86_64.whl", hash = "sha256:3df850c2f8db9934de4cf8f9152f8dc2558f49f298f37f90c517e8e5c84c30e9", size = 323311, upload-time = "2026-01-12T18:33:36.305Z" }, + { url = "https://files.pythonhosted.org/packages/75/b1/1dc83c2c661b4c62d56cc081706ee33a4fc2835bd90f965baa2663ef7676/protobuf-6.33.4-py3-none-any.whl", hash = "sha256:1fe3730068fcf2e595816a6c34fe66eeedd37d51d0400b72fabc848811fdc1bc", size = 170532, upload-time = "2026-01-12T18:33:39.199Z" }, ] [[package]] @@ -6846,7 +6848,7 @@ dependencies = [ { name = "pyglet" }, { name = "pyopengl" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "six" }, { name = "trimesh" }, ] @@ -7717,7 +7719,7 @@ resolution-markers = [ dependencies = [ { name = "joblib", marker = "python_full_version >= '3.11'" }, { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, - { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "threadpoolctl", marker = "python_full_version >= '3.11'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/0e/d4/40988bf3b8e34feec1d0e6a051446b1f66225f8529b9309becaeef62b6c4/scikit_learn-1.8.0.tar.gz", hash = "sha256:9bccbb3b40e3de10351f8f5068e105d0f4083b1a65fa07b6634fbc401a6287fd", size = 7335585, upload-time = "2025-12-10T07:08:53.618Z" } @@ -7824,7 +7826,7 @@ wheels = [ [[package]] name = "scipy" -version = "1.16.3" +version = "1.17.0" source = { registry = "https://pypi.org/simple" } resolution-markers = [ "python_full_version >= '3.13' and sys_platform == 'darwin'", @@ -7843,68 +7845,68 @@ resolution-markers = [ dependencies = [ { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/0a/ca/d8ace4f98322d01abcd52d381134344bf7b431eba7ed8b42bdea5a3c2ac9/scipy-1.16.3.tar.gz", hash = "sha256:01e87659402762f43bd2fee13370553a17ada367d42e7487800bf2916535aecb", size = 30597883, upload-time = "2025-10-28T17:38:54.068Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/9b/5f/6f37d7439de1455ce9c5a556b8d1db0979f03a796c030bafdf08d35b7bf9/scipy-1.16.3-cp311-cp311-macosx_10_14_x86_64.whl", hash = "sha256:40be6cf99e68b6c4321e9f8782e7d5ff8265af28ef2cd56e9c9b2638fa08ad97", size = 36630881, upload-time = "2025-10-28T17:31:47.104Z" }, - { url = "https://files.pythonhosted.org/packages/7c/89/d70e9f628749b7e4db2aa4cd89735502ff3f08f7b9b27d2e799485987cd9/scipy-1.16.3-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:8be1ca9170fcb6223cc7c27f4305d680ded114a1567c0bd2bfcbf947d1b17511", size = 28941012, upload-time = "2025-10-28T17:31:53.411Z" }, - { url = "https://files.pythonhosted.org/packages/a8/a8/0e7a9a6872a923505dbdf6bb93451edcac120363131c19013044a1e7cb0c/scipy-1.16.3-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:bea0a62734d20d67608660f69dcda23e7f90fb4ca20974ab80b6ed40df87a005", size = 20931935, upload-time = "2025-10-28T17:31:57.361Z" }, - { url = "https://files.pythonhosted.org/packages/bd/c7/020fb72bd79ad798e4dbe53938543ecb96b3a9ac3fe274b7189e23e27353/scipy-1.16.3-cp311-cp311-macosx_14_0_x86_64.whl", hash = "sha256:2a207a6ce9c24f1951241f4693ede2d393f59c07abc159b2cb2be980820e01fb", size = 23534466, upload-time = "2025-10-28T17:32:01.875Z" }, - { url = "https://files.pythonhosted.org/packages/be/a0/668c4609ce6dbf2f948e167836ccaf897f95fb63fa231c87da7558a374cd/scipy-1.16.3-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:532fb5ad6a87e9e9cd9c959b106b73145a03f04c7d57ea3e6f6bb60b86ab0876", size = 33593618, upload-time = "2025-10-28T17:32:06.902Z" }, - { url = "https://files.pythonhosted.org/packages/ca/6e/8942461cf2636cdae083e3eb72622a7fbbfa5cf559c7d13ab250a5dbdc01/scipy-1.16.3-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:0151a0749efeaaab78711c78422d413c583b8cdd2011a3c1d6c794938ee9fdb2", size = 35899798, upload-time = "2025-10-28T17:32:12.665Z" }, - { url = "https://files.pythonhosted.org/packages/79/e8/d0f33590364cdbd67f28ce79368b373889faa4ee959588beddf6daef9abe/scipy-1.16.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:b7180967113560cca57418a7bc719e30366b47959dd845a93206fbed693c867e", size = 36226154, upload-time = "2025-10-28T17:32:17.961Z" }, - { url = "https://files.pythonhosted.org/packages/39/c1/1903de608c0c924a1749c590064e65810f8046e437aba6be365abc4f7557/scipy-1.16.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:deb3841c925eeddb6afc1e4e4a45e418d19ec7b87c5df177695224078e8ec733", size = 38878540, upload-time = "2025-10-28T17:32:23.907Z" }, - { url = "https://files.pythonhosted.org/packages/f1/d0/22ec7036ba0b0a35bccb7f25ab407382ed34af0b111475eb301c16f8a2e5/scipy-1.16.3-cp311-cp311-win_amd64.whl", hash = "sha256:53c3844d527213631e886621df5695d35e4f6a75f620dca412bcd292f6b87d78", size = 38722107, upload-time = "2025-10-28T17:32:29.921Z" }, - { url = "https://files.pythonhosted.org/packages/7b/60/8a00e5a524bb3bf8898db1650d350f50e6cffb9d7a491c561dc9826c7515/scipy-1.16.3-cp311-cp311-win_arm64.whl", hash = "sha256:9452781bd879b14b6f055b26643703551320aa8d79ae064a71df55c00286a184", size = 25506272, upload-time = "2025-10-28T17:32:34.577Z" }, - { url = "https://files.pythonhosted.org/packages/40/41/5bf55c3f386b1643812f3a5674edf74b26184378ef0f3e7c7a09a7e2ca7f/scipy-1.16.3-cp312-cp312-macosx_10_14_x86_64.whl", hash = "sha256:81fc5827606858cf71446a5e98715ba0e11f0dbc83d71c7409d05486592a45d6", size = 36659043, upload-time = "2025-10-28T17:32:40.285Z" }, - { url = "https://files.pythonhosted.org/packages/1e/0f/65582071948cfc45d43e9870bf7ca5f0e0684e165d7c9ef4e50d783073eb/scipy-1.16.3-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:c97176013d404c7346bf57874eaac5187d969293bf40497140b0a2b2b7482e07", size = 28898986, upload-time = "2025-10-28T17:32:45.325Z" }, - { url = "https://files.pythonhosted.org/packages/96/5e/36bf3f0ac298187d1ceadde9051177d6a4fe4d507e8f59067dc9dd39e650/scipy-1.16.3-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:2b71d93c8a9936046866acebc915e2af2e292b883ed6e2cbe5c34beb094b82d9", size = 20889814, upload-time = "2025-10-28T17:32:49.277Z" }, - { url = "https://files.pythonhosted.org/packages/80/35/178d9d0c35394d5d5211bbff7ac4f2986c5488b59506fef9e1de13ea28d3/scipy-1.16.3-cp312-cp312-macosx_14_0_x86_64.whl", hash = "sha256:3d4a07a8e785d80289dfe66b7c27d8634a773020742ec7187b85ccc4b0e7b686", size = 23565795, upload-time = "2025-10-28T17:32:53.337Z" }, - { url = "https://files.pythonhosted.org/packages/fa/46/d1146ff536d034d02f83c8afc3c4bab2eddb634624d6529a8512f3afc9da/scipy-1.16.3-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:0553371015692a898e1aa858fed67a3576c34edefa6b7ebdb4e9dde49ce5c203", size = 33349476, upload-time = "2025-10-28T17:32:58.353Z" }, - { url = "https://files.pythonhosted.org/packages/79/2e/415119c9ab3e62249e18c2b082c07aff907a273741b3f8160414b0e9193c/scipy-1.16.3-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:72d1717fd3b5e6ec747327ce9bda32d5463f472c9dce9f54499e81fbd50245a1", size = 35676692, upload-time = "2025-10-28T17:33:03.88Z" }, - { url = "https://files.pythonhosted.org/packages/27/82/df26e44da78bf8d2aeaf7566082260cfa15955a5a6e96e6a29935b64132f/scipy-1.16.3-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:1fb2472e72e24d1530debe6ae078db70fb1605350c88a3d14bc401d6306dbffe", size = 36019345, upload-time = "2025-10-28T17:33:09.773Z" }, - { url = "https://files.pythonhosted.org/packages/82/31/006cbb4b648ba379a95c87262c2855cd0d09453e500937f78b30f02fa1cd/scipy-1.16.3-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:c5192722cffe15f9329a3948c4b1db789fbb1f05c97899187dcf009b283aea70", size = 38678975, upload-time = "2025-10-28T17:33:15.809Z" }, - { url = "https://files.pythonhosted.org/packages/c2/7f/acbd28c97e990b421af7d6d6cd416358c9c293fc958b8529e0bd5d2a2a19/scipy-1.16.3-cp312-cp312-win_amd64.whl", hash = "sha256:56edc65510d1331dae01ef9b658d428e33ed48b4f77b1d51caf479a0253f96dc", size = 38555926, upload-time = "2025-10-28T17:33:21.388Z" }, - { url = "https://files.pythonhosted.org/packages/ce/69/c5c7807fd007dad4f48e0a5f2153038dc96e8725d3345b9ee31b2b7bed46/scipy-1.16.3-cp312-cp312-win_arm64.whl", hash = "sha256:a8a26c78ef223d3e30920ef759e25625a0ecdd0d60e5a8818b7513c3e5384cf2", size = 25463014, upload-time = "2025-10-28T17:33:25.975Z" }, - { url = "https://files.pythonhosted.org/packages/72/f1/57e8327ab1508272029e27eeef34f2302ffc156b69e7e233e906c2a5c379/scipy-1.16.3-cp313-cp313-macosx_10_14_x86_64.whl", hash = "sha256:d2ec56337675e61b312179a1ad124f5f570c00f920cc75e1000025451b88241c", size = 36617856, upload-time = "2025-10-28T17:33:31.375Z" }, - { url = "https://files.pythonhosted.org/packages/44/13/7e63cfba8a7452eb756306aa2fd9b37a29a323b672b964b4fdeded9a3f21/scipy-1.16.3-cp313-cp313-macosx_12_0_arm64.whl", hash = "sha256:16b8bc35a4cc24db80a0ec836a9286d0e31b2503cb2fd7ff7fb0e0374a97081d", size = 28874306, upload-time = "2025-10-28T17:33:36.516Z" }, - { url = "https://files.pythonhosted.org/packages/15/65/3a9400efd0228a176e6ec3454b1fa998fbbb5a8defa1672c3f65706987db/scipy-1.16.3-cp313-cp313-macosx_14_0_arm64.whl", hash = "sha256:5803c5fadd29de0cf27fa08ccbfe7a9e5d741bf63e4ab1085437266f12460ff9", size = 20865371, upload-time = "2025-10-28T17:33:42.094Z" }, - { url = "https://files.pythonhosted.org/packages/33/d7/eda09adf009a9fb81827194d4dd02d2e4bc752cef16737cc4ef065234031/scipy-1.16.3-cp313-cp313-macosx_14_0_x86_64.whl", hash = "sha256:b81c27fc41954319a943d43b20e07c40bdcd3ff7cf013f4fb86286faefe546c4", size = 23524877, upload-time = "2025-10-28T17:33:48.483Z" }, - { url = "https://files.pythonhosted.org/packages/7d/6b/3f911e1ebc364cb81320223a3422aab7d26c9c7973109a9cd0f27c64c6c0/scipy-1.16.3-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:0c3b4dd3d9b08dbce0f3440032c52e9e2ab9f96ade2d3943313dfe51a7056959", size = 33342103, upload-time = "2025-10-28T17:33:56.495Z" }, - { url = "https://files.pythonhosted.org/packages/21/f6/4bfb5695d8941e5c570a04d9fcd0d36bce7511b7d78e6e75c8f9791f82d0/scipy-1.16.3-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:7dc1360c06535ea6116a2220f760ae572db9f661aba2d88074fe30ec2aa1ff88", size = 35697297, upload-time = "2025-10-28T17:34:04.722Z" }, - { url = "https://files.pythonhosted.org/packages/04/e1/6496dadbc80d8d896ff72511ecfe2316b50313bfc3ebf07a3f580f08bd8c/scipy-1.16.3-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:663b8d66a8748051c3ee9c96465fb417509315b99c71550fda2591d7dd634234", size = 36021756, upload-time = "2025-10-28T17:34:13.482Z" }, - { url = "https://files.pythonhosted.org/packages/fe/bd/a8c7799e0136b987bda3e1b23d155bcb31aec68a4a472554df5f0937eef7/scipy-1.16.3-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:eab43fae33a0c39006a88096cd7b4f4ef545ea0447d250d5ac18202d40b6611d", size = 38696566, upload-time = "2025-10-28T17:34:22.384Z" }, - { url = "https://files.pythonhosted.org/packages/cd/01/1204382461fcbfeb05b6161b594f4007e78b6eba9b375382f79153172b4d/scipy-1.16.3-cp313-cp313-win_amd64.whl", hash = "sha256:062246acacbe9f8210de8e751b16fc37458213f124bef161a5a02c7a39284304", size = 38529877, upload-time = "2025-10-28T17:35:51.076Z" }, - { url = "https://files.pythonhosted.org/packages/7f/14/9d9fbcaa1260a94f4bb5b64ba9213ceb5d03cd88841fe9fd1ffd47a45b73/scipy-1.16.3-cp313-cp313-win_arm64.whl", hash = "sha256:50a3dbf286dbc7d84f176f9a1574c705f277cb6565069f88f60db9eafdbe3ee2", size = 25455366, upload-time = "2025-10-28T17:35:59.014Z" }, - { url = "https://files.pythonhosted.org/packages/e2/a3/9ec205bd49f42d45d77f1730dbad9ccf146244c1647605cf834b3a8c4f36/scipy-1.16.3-cp313-cp313t-macosx_10_14_x86_64.whl", hash = "sha256:fb4b29f4cf8cc5a8d628bc8d8e26d12d7278cd1f219f22698a378c3d67db5e4b", size = 37027931, upload-time = "2025-10-28T17:34:31.451Z" }, - { url = "https://files.pythonhosted.org/packages/25/06/ca9fd1f3a4589cbd825b1447e5db3a8ebb969c1eaf22c8579bd286f51b6d/scipy-1.16.3-cp313-cp313t-macosx_12_0_arm64.whl", hash = "sha256:8d09d72dc92742988b0e7750bddb8060b0c7079606c0d24a8cc8e9c9c11f9079", size = 29400081, upload-time = "2025-10-28T17:34:39.087Z" }, - { url = "https://files.pythonhosted.org/packages/6a/56/933e68210d92657d93fb0e381683bc0e53a965048d7358ff5fbf9e6a1b17/scipy-1.16.3-cp313-cp313t-macosx_14_0_arm64.whl", hash = "sha256:03192a35e661470197556de24e7cb1330d84b35b94ead65c46ad6f16f6b28f2a", size = 21391244, upload-time = "2025-10-28T17:34:45.234Z" }, - { url = "https://files.pythonhosted.org/packages/a8/7e/779845db03dc1418e215726329674b40576879b91814568757ff0014ad65/scipy-1.16.3-cp313-cp313t-macosx_14_0_x86_64.whl", hash = "sha256:57d01cb6f85e34f0946b33caa66e892aae072b64b034183f3d87c4025802a119", size = 23929753, upload-time = "2025-10-28T17:34:51.793Z" }, - { url = "https://files.pythonhosted.org/packages/4c/4b/f756cf8161d5365dcdef9e5f460ab226c068211030a175d2fc7f3f41ca64/scipy-1.16.3-cp313-cp313t-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:96491a6a54e995f00a28a3c3badfff58fd093bf26cd5fb34a2188c8c756a3a2c", size = 33496912, upload-time = "2025-10-28T17:34:59.8Z" }, - { url = "https://files.pythonhosted.org/packages/09/b5/222b1e49a58668f23839ca1542a6322bb095ab8d6590d4f71723869a6c2c/scipy-1.16.3-cp313-cp313t-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:cd13e354df9938598af2be05822c323e97132d5e6306b83a3b4ee6724c6e522e", size = 35802371, upload-time = "2025-10-28T17:35:08.173Z" }, - { url = "https://files.pythonhosted.org/packages/c1/8d/5964ef68bb31829bde27611f8c9deeac13764589fe74a75390242b64ca44/scipy-1.16.3-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:63d3cdacb8a824a295191a723ee5e4ea7768ca5ca5f2838532d9f2e2b3ce2135", size = 36190477, upload-time = "2025-10-28T17:35:16.7Z" }, - { url = "https://files.pythonhosted.org/packages/ab/f2/b31d75cb9b5fa4dd39a0a931ee9b33e7f6f36f23be5ef560bf72e0f92f32/scipy-1.16.3-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:e7efa2681ea410b10dde31a52b18b0154d66f2485328830e45fdf183af5aefc6", size = 38796678, upload-time = "2025-10-28T17:35:26.354Z" }, - { url = "https://files.pythonhosted.org/packages/b4/1e/b3723d8ff64ab548c38d87055483714fefe6ee20e0189b62352b5e015bb1/scipy-1.16.3-cp313-cp313t-win_amd64.whl", hash = "sha256:2d1ae2cf0c350e7705168ff2429962a89ad90c2d49d1dd300686d8b2a5af22fc", size = 38640178, upload-time = "2025-10-28T17:35:35.304Z" }, - { url = "https://files.pythonhosted.org/packages/8e/f3/d854ff38789aca9b0cc23008d607ced9de4f7ab14fa1ca4329f86b3758ca/scipy-1.16.3-cp313-cp313t-win_arm64.whl", hash = "sha256:0c623a54f7b79dd88ef56da19bc2873afec9673a48f3b85b18e4d402bdd29a5a", size = 25803246, upload-time = "2025-10-28T17:35:42.155Z" }, - { url = "https://files.pythonhosted.org/packages/99/f6/99b10fd70f2d864c1e29a28bbcaa0c6340f9d8518396542d9ea3b4aaae15/scipy-1.16.3-cp314-cp314-macosx_10_14_x86_64.whl", hash = "sha256:875555ce62743e1d54f06cdf22c1e0bc47b91130ac40fe5d783b6dfa114beeb6", size = 36606469, upload-time = "2025-10-28T17:36:08.741Z" }, - { url = "https://files.pythonhosted.org/packages/4d/74/043b54f2319f48ea940dd025779fa28ee360e6b95acb7cd188fad4391c6b/scipy-1.16.3-cp314-cp314-macosx_12_0_arm64.whl", hash = "sha256:bb61878c18a470021fb515a843dc7a76961a8daceaaaa8bad1332f1bf4b54657", size = 28872043, upload-time = "2025-10-28T17:36:16.599Z" }, - { url = "https://files.pythonhosted.org/packages/4d/e1/24b7e50cc1c4ee6ffbcb1f27fe9f4c8b40e7911675f6d2d20955f41c6348/scipy-1.16.3-cp314-cp314-macosx_14_0_arm64.whl", hash = "sha256:f2622206f5559784fa5c4b53a950c3c7c1cf3e84ca1b9c4b6c03f062f289ca26", size = 20862952, upload-time = "2025-10-28T17:36:22.966Z" }, - { url = "https://files.pythonhosted.org/packages/dd/3a/3e8c01a4d742b730df368e063787c6808597ccb38636ed821d10b39ca51b/scipy-1.16.3-cp314-cp314-macosx_14_0_x86_64.whl", hash = "sha256:7f68154688c515cdb541a31ef8eb66d8cd1050605be9dcd74199cbd22ac739bc", size = 23508512, upload-time = "2025-10-28T17:36:29.731Z" }, - { url = "https://files.pythonhosted.org/packages/1f/60/c45a12b98ad591536bfe5330cb3cfe1850d7570259303563b1721564d458/scipy-1.16.3-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:8b3c820ddb80029fe9f43d61b81d8b488d3ef8ca010d15122b152db77dc94c22", size = 33413639, upload-time = "2025-10-28T17:36:37.982Z" }, - { url = "https://files.pythonhosted.org/packages/71/bc/35957d88645476307e4839712642896689df442f3e53b0fa016ecf8a3357/scipy-1.16.3-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:d3837938ae715fc0fe3c39c0202de3a8853aff22ca66781ddc2ade7554b7e2cc", size = 35704729, upload-time = "2025-10-28T17:36:46.547Z" }, - { url = "https://files.pythonhosted.org/packages/3b/15/89105e659041b1ca11c386e9995aefacd513a78493656e57789f9d9eab61/scipy-1.16.3-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:aadd23f98f9cb069b3bd64ddc900c4d277778242e961751f77a8cb5c4b946fb0", size = 36086251, upload-time = "2025-10-28T17:36:55.161Z" }, - { url = "https://files.pythonhosted.org/packages/1a/87/c0ea673ac9c6cc50b3da2196d860273bc7389aa69b64efa8493bdd25b093/scipy-1.16.3-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:b7c5f1bda1354d6a19bc6af73a649f8285ca63ac6b52e64e658a5a11d4d69800", size = 38716681, upload-time = "2025-10-28T17:37:04.1Z" }, - { url = "https://files.pythonhosted.org/packages/91/06/837893227b043fb9b0d13e4bd7586982d8136cb249ffb3492930dab905b8/scipy-1.16.3-cp314-cp314-win_amd64.whl", hash = "sha256:e5d42a9472e7579e473879a1990327830493a7047506d58d73fc429b84c1d49d", size = 39358423, upload-time = "2025-10-28T17:38:20.005Z" }, - { url = "https://files.pythonhosted.org/packages/95/03/28bce0355e4d34a7c034727505a02d19548549e190bedd13a721e35380b7/scipy-1.16.3-cp314-cp314-win_arm64.whl", hash = "sha256:6020470b9d00245926f2d5bb93b119ca0340f0d564eb6fbaad843eaebf9d690f", size = 26135027, upload-time = "2025-10-28T17:38:24.966Z" }, - { url = "https://files.pythonhosted.org/packages/b2/6f/69f1e2b682efe9de8fe9f91040f0cd32f13cfccba690512ba4c582b0bc29/scipy-1.16.3-cp314-cp314t-macosx_10_14_x86_64.whl", hash = "sha256:e1d27cbcb4602680a49d787d90664fa4974063ac9d4134813332a8c53dbe667c", size = 37028379, upload-time = "2025-10-28T17:37:14.061Z" }, - { url = "https://files.pythonhosted.org/packages/7c/2d/e826f31624a5ebbab1cd93d30fd74349914753076ed0593e1d56a98c4fb4/scipy-1.16.3-cp314-cp314t-macosx_12_0_arm64.whl", hash = "sha256:9b9c9c07b6d56a35777a1b4cc8966118fb16cfd8daf6743867d17d36cfad2d40", size = 29400052, upload-time = "2025-10-28T17:37:21.709Z" }, - { url = "https://files.pythonhosted.org/packages/69/27/d24feb80155f41fd1f156bf144e7e049b4e2b9dd06261a242905e3bc7a03/scipy-1.16.3-cp314-cp314t-macosx_14_0_arm64.whl", hash = "sha256:3a4c460301fb2cffb7f88528f30b3127742cff583603aa7dc964a52c463b385d", size = 21391183, upload-time = "2025-10-28T17:37:29.559Z" }, - { url = "https://files.pythonhosted.org/packages/f8/d3/1b229e433074c5738a24277eca520a2319aac7465eea7310ea6ae0e98ae2/scipy-1.16.3-cp314-cp314t-macosx_14_0_x86_64.whl", hash = "sha256:f667a4542cc8917af1db06366d3f78a5c8e83badd56409f94d1eac8d8d9133fa", size = 23930174, upload-time = "2025-10-28T17:37:36.306Z" }, - { url = "https://files.pythonhosted.org/packages/16/9d/d9e148b0ec680c0f042581a2be79a28a7ab66c0c4946697f9e7553ead337/scipy-1.16.3-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:f379b54b77a597aa7ee5e697df0d66903e41b9c85a6dd7946159e356319158e8", size = 33497852, upload-time = "2025-10-28T17:37:42.228Z" }, - { url = "https://files.pythonhosted.org/packages/2f/22/4e5f7561e4f98b7bea63cf3fd7934bff1e3182e9f1626b089a679914d5c8/scipy-1.16.3-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:4aff59800a3b7f786b70bfd6ab551001cb553244988d7d6b8299cb1ea653b353", size = 35798595, upload-time = "2025-10-28T17:37:48.102Z" }, - { url = "https://files.pythonhosted.org/packages/83/42/6644d714c179429fc7196857866f219fef25238319b650bb32dde7bf7a48/scipy-1.16.3-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:da7763f55885045036fabcebd80144b757d3db06ab0861415d1c3b7c69042146", size = 36186269, upload-time = "2025-10-28T17:37:53.72Z" }, - { url = "https://files.pythonhosted.org/packages/ac/70/64b4d7ca92f9cf2e6fc6aaa2eecf80bb9b6b985043a9583f32f8177ea122/scipy-1.16.3-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:ffa6eea95283b2b8079b821dc11f50a17d0571c92b43e2b5b12764dc5f9b285d", size = 38802779, upload-time = "2025-10-28T17:37:59.393Z" }, - { url = "https://files.pythonhosted.org/packages/61/82/8d0e39f62764cce5ffd5284131e109f07cf8955aef9ab8ed4e3aa5e30539/scipy-1.16.3-cp314-cp314t-win_amd64.whl", hash = "sha256:d9f48cafc7ce94cf9b15c6bffdc443a81a27bf7075cf2dcd5c8b40f85d10c4e7", size = 39471128, upload-time = "2025-10-28T17:38:05.259Z" }, - { url = "https://files.pythonhosted.org/packages/64/47/a494741db7280eae6dc033510c319e34d42dd41b7ac0c7ead39354d1a2b5/scipy-1.16.3-cp314-cp314t-win_arm64.whl", hash = "sha256:21d9d6b197227a12dcbf9633320a4e34c6b0e51c57268df255a0942983bac562", size = 26464127, upload-time = "2025-10-28T17:38:11.34Z" }, +sdist = { url = "https://files.pythonhosted.org/packages/56/3e/9cca699f3486ce6bc12ff46dc2031f1ec8eb9ccc9a320fdaf925f1417426/scipy-1.17.0.tar.gz", hash = "sha256:2591060c8e648d8b96439e111ac41fd8342fdeff1876be2e19dea3fe8930454e", size = 30396830, upload-time = "2026-01-10T21:34:23.009Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/1e/4b/c89c131aa87cad2b77a54eb0fb94d633a842420fa7e919dc2f922037c3d8/scipy-1.17.0-cp311-cp311-macosx_10_14_x86_64.whl", hash = "sha256:2abd71643797bd8a106dff97894ff7869eeeb0af0f7a5ce02e4227c6a2e9d6fd", size = 31381316, upload-time = "2026-01-10T21:24:33.42Z" }, + { url = "https://files.pythonhosted.org/packages/5e/5f/a6b38f79a07d74989224d5f11b55267714707582908a5f1ae854cf9a9b84/scipy-1.17.0-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:ef28d815f4d2686503e5f4f00edc387ae58dfd7a2f42e348bb53359538f01558", size = 27966760, upload-time = "2026-01-10T21:24:38.911Z" }, + { url = "https://files.pythonhosted.org/packages/c1/20/095ad24e031ee8ed3c5975954d816b8e7e2abd731e04f8be573de8740885/scipy-1.17.0-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:272a9f16d6bb4667e8b50d25d71eddcc2158a214df1b566319298de0939d2ab7", size = 20138701, upload-time = "2026-01-10T21:24:43.249Z" }, + { url = "https://files.pythonhosted.org/packages/89/11/4aad2b3858d0337756f3323f8960755704e530b27eb2a94386c970c32cbe/scipy-1.17.0-cp311-cp311-macosx_14_0_x86_64.whl", hash = "sha256:7204fddcbec2fe6598f1c5fdf027e9f259106d05202a959a9f1aecf036adc9f6", size = 22480574, upload-time = "2026-01-10T21:24:47.266Z" }, + { url = "https://files.pythonhosted.org/packages/85/bd/f5af70c28c6da2227e510875cadf64879855193a687fb19951f0f44cfd6b/scipy-1.17.0-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:fc02c37a5639ee67d8fb646ffded6d793c06c5622d36b35cfa8fe5ececb8f042", size = 32862414, upload-time = "2026-01-10T21:24:52.566Z" }, + { url = "https://files.pythonhosted.org/packages/ef/df/df1457c4df3826e908879fe3d76bc5b6e60aae45f4ee42539512438cfd5d/scipy-1.17.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:dac97a27520d66c12a34fd90a4fe65f43766c18c0d6e1c0a80f114d2260080e4", size = 35112380, upload-time = "2026-01-10T21:24:58.433Z" }, + { url = "https://files.pythonhosted.org/packages/5f/bb/88e2c16bd1dd4de19d80d7c5e238387182993c2fb13b4b8111e3927ad422/scipy-1.17.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:ebb7446a39b3ae0fe8f416a9a3fdc6fba3f11c634f680f16a239c5187bc487c0", size = 34922676, upload-time = "2026-01-10T21:25:04.287Z" }, + { url = "https://files.pythonhosted.org/packages/02/ba/5120242cc735f71fc002cff0303d536af4405eb265f7c60742851e7ccfe9/scipy-1.17.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:474da16199f6af66601a01546144922ce402cb17362e07d82f5a6cf8f963e449", size = 37507599, upload-time = "2026-01-10T21:25:09.851Z" }, + { url = "https://files.pythonhosted.org/packages/52/c8/08629657ac6c0da198487ce8cd3de78e02cfde42b7f34117d56a3fe249dc/scipy-1.17.0-cp311-cp311-win_amd64.whl", hash = "sha256:255c0da161bd7b32a6c898e7891509e8a9289f0b1c6c7d96142ee0d2b114c2ea", size = 36380284, upload-time = "2026-01-10T21:25:15.632Z" }, + { url = "https://files.pythonhosted.org/packages/6c/4a/465f96d42c6f33ad324a40049dfd63269891db9324aa66c4a1c108c6f994/scipy-1.17.0-cp311-cp311-win_arm64.whl", hash = "sha256:85b0ac3ad17fa3be50abd7e69d583d98792d7edc08367e01445a1e2076005379", size = 24370427, upload-time = "2026-01-10T21:25:20.514Z" }, + { url = "https://files.pythonhosted.org/packages/0b/11/7241a63e73ba5a516f1930ac8d5b44cbbfabd35ac73a2d08ca206df007c4/scipy-1.17.0-cp312-cp312-macosx_10_14_x86_64.whl", hash = "sha256:0d5018a57c24cb1dd828bcf51d7b10e65986d549f52ef5adb6b4d1ded3e32a57", size = 31364580, upload-time = "2026-01-10T21:25:25.717Z" }, + { url = "https://files.pythonhosted.org/packages/ed/1d/5057f812d4f6adc91a20a2d6f2ebcdb517fdbc87ae3acc5633c9b97c8ba5/scipy-1.17.0-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:88c22af9e5d5a4f9e027e26772cc7b5922fab8bcc839edb3ae33de404feebd9e", size = 27969012, upload-time = "2026-01-10T21:25:30.921Z" }, + { url = "https://files.pythonhosted.org/packages/e3/21/f6ec556c1e3b6ec4e088da667d9987bb77cc3ab3026511f427dc8451187d/scipy-1.17.0-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:f3cd947f20fe17013d401b64e857c6b2da83cae567adbb75b9dcba865abc66d8", size = 20140691, upload-time = "2026-01-10T21:25:34.802Z" }, + { url = "https://files.pythonhosted.org/packages/7a/fe/5e5ad04784964ba964a96f16c8d4676aa1b51357199014dce58ab7ec5670/scipy-1.17.0-cp312-cp312-macosx_14_0_x86_64.whl", hash = "sha256:e8c0b331c2c1f531eb51f1b4fc9ba709521a712cce58f1aa627bc007421a5306", size = 22463015, upload-time = "2026-01-10T21:25:39.277Z" }, + { url = "https://files.pythonhosted.org/packages/4a/69/7c347e857224fcaf32a34a05183b9d8a7aca25f8f2d10b8a698b8388561a/scipy-1.17.0-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:5194c445d0a1c7a6c1a4a4681b6b7c71baad98ff66d96b949097e7513c9d6742", size = 32724197, upload-time = "2026-01-10T21:25:44.084Z" }, + { url = "https://files.pythonhosted.org/packages/d1/fe/66d73b76d378ba8cc2fe605920c0c75092e3a65ae746e1e767d9d020a75a/scipy-1.17.0-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9eeb9b5f5997f75507814ed9d298ab23f62cf79f5a3ef90031b1ee2506abdb5b", size = 35009148, upload-time = "2026-01-10T21:25:50.591Z" }, + { url = "https://files.pythonhosted.org/packages/af/07/07dec27d9dc41c18d8c43c69e9e413431d20c53a0339c388bcf72f353c4b/scipy-1.17.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:40052543f7bbe921df4408f46003d6f01c6af109b9e2c8a66dd1cf6cf57f7d5d", size = 34798766, upload-time = "2026-01-10T21:25:59.41Z" }, + { url = "https://files.pythonhosted.org/packages/81/61/0470810c8a093cdacd4ba7504b8a218fd49ca070d79eca23a615f5d9a0b0/scipy-1.17.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:0cf46c8013fec9d3694dc572f0b54100c28405d55d3e2cb15e2895b25057996e", size = 37405953, upload-time = "2026-01-10T21:26:07.75Z" }, + { url = "https://files.pythonhosted.org/packages/92/ce/672ed546f96d5d41ae78c4b9b02006cedd0b3d6f2bf5bb76ea455c320c28/scipy-1.17.0-cp312-cp312-win_amd64.whl", hash = "sha256:0937a0b0d8d593a198cededd4c439a0ea216a3f36653901ea1f3e4be949056f8", size = 36328121, upload-time = "2026-01-10T21:26:16.509Z" }, + { url = "https://files.pythonhosted.org/packages/9d/21/38165845392cae67b61843a52c6455d47d0cc2a40dd495c89f4362944654/scipy-1.17.0-cp312-cp312-win_arm64.whl", hash = "sha256:f603d8a5518c7426414d1d8f82e253e454471de682ce5e39c29adb0df1efb86b", size = 24314368, upload-time = "2026-01-10T21:26:23.087Z" }, + { url = "https://files.pythonhosted.org/packages/0c/51/3468fdfd49387ddefee1636f5cf6d03ce603b75205bf439bbf0e62069bfd/scipy-1.17.0-cp313-cp313-macosx_10_14_x86_64.whl", hash = "sha256:65ec32f3d32dfc48c72df4291345dae4f048749bc8d5203ee0a3f347f96c5ce6", size = 31344101, upload-time = "2026-01-10T21:26:30.25Z" }, + { url = "https://files.pythonhosted.org/packages/b2/9a/9406aec58268d437636069419e6977af953d1e246df941d42d3720b7277b/scipy-1.17.0-cp313-cp313-macosx_12_0_arm64.whl", hash = "sha256:1f9586a58039d7229ce77b52f8472c972448cded5736eaf102d5658bbac4c269", size = 27950385, upload-time = "2026-01-10T21:26:36.801Z" }, + { url = "https://files.pythonhosted.org/packages/4f/98/e7342709e17afdfd1b26b56ae499ef4939b45a23a00e471dfb5375eea205/scipy-1.17.0-cp313-cp313-macosx_14_0_arm64.whl", hash = "sha256:9fad7d3578c877d606b1150135c2639e9de9cecd3705caa37b66862977cc3e72", size = 20122115, upload-time = "2026-01-10T21:26:42.107Z" }, + { url = "https://files.pythonhosted.org/packages/fd/0e/9eeeb5357a64fd157cbe0302c213517c541cc16b8486d82de251f3c68ede/scipy-1.17.0-cp313-cp313-macosx_14_0_x86_64.whl", hash = "sha256:423ca1f6584fc03936972b5f7c06961670dbba9f234e71676a7c7ccf938a0d61", size = 22442402, upload-time = "2026-01-10T21:26:48.029Z" }, + { url = "https://files.pythonhosted.org/packages/c9/10/be13397a0e434f98e0c79552b2b584ae5bb1c8b2be95db421533bbca5369/scipy-1.17.0-cp313-cp313-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:fe508b5690e9eaaa9467fc047f833af58f1152ae51a0d0aed67aa5801f4dd7d6", size = 32696338, upload-time = "2026-01-10T21:26:55.521Z" }, + { url = "https://files.pythonhosted.org/packages/63/1e/12fbf2a3bb240161651c94bb5cdd0eae5d4e8cc6eaeceb74ab07b12a753d/scipy-1.17.0-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6680f2dfd4f6182e7d6db161344537da644d1cf85cf293f015c60a17ecf08752", size = 34977201, upload-time = "2026-01-10T21:27:03.501Z" }, + { url = "https://files.pythonhosted.org/packages/19/5b/1a63923e23ccd20bd32156d7dd708af5bbde410daa993aa2500c847ab2d2/scipy-1.17.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:eec3842ec9ac9de5917899b277428886042a93db0b227ebbe3a333b64ec7643d", size = 34777384, upload-time = "2026-01-10T21:27:11.423Z" }, + { url = "https://files.pythonhosted.org/packages/39/22/b5da95d74edcf81e540e467202a988c50fef41bd2011f46e05f72ba07df6/scipy-1.17.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:d7425fcafbc09a03731e1bc05581f5fad988e48c6a861f441b7ab729a49a55ea", size = 37379586, upload-time = "2026-01-10T21:27:20.171Z" }, + { url = "https://files.pythonhosted.org/packages/b9/b6/8ac583d6da79e7b9e520579f03007cb006f063642afd6b2eeb16b890bf93/scipy-1.17.0-cp313-cp313-win_amd64.whl", hash = "sha256:87b411e42b425b84777718cc41516b8a7e0795abfa8e8e1d573bf0ef014f0812", size = 36287211, upload-time = "2026-01-10T21:28:43.122Z" }, + { url = "https://files.pythonhosted.org/packages/55/fb/7db19e0b3e52f882b420417644ec81dd57eeef1bd1705b6f689d8ff93541/scipy-1.17.0-cp313-cp313-win_arm64.whl", hash = "sha256:357ca001c6e37601066092e7c89cca2f1ce74e2a520ca78d063a6d2201101df2", size = 24312646, upload-time = "2026-01-10T21:28:49.893Z" }, + { url = "https://files.pythonhosted.org/packages/20/b6/7feaa252c21cc7aff335c6c55e1b90ab3e3306da3f048109b8b639b94648/scipy-1.17.0-cp313-cp313t-macosx_10_14_x86_64.whl", hash = "sha256:ec0827aa4d36cb79ff1b81de898e948a51ac0b9b1c43e4a372c0508c38c0f9a3", size = 31693194, upload-time = "2026-01-10T21:27:27.454Z" }, + { url = "https://files.pythonhosted.org/packages/76/bb/bbb392005abce039fb7e672cb78ac7d158700e826b0515cab6b5b60c26fb/scipy-1.17.0-cp313-cp313t-macosx_12_0_arm64.whl", hash = "sha256:819fc26862b4b3c73a60d486dbb919202f3d6d98c87cf20c223511429f2d1a97", size = 28365415, upload-time = "2026-01-10T21:27:34.26Z" }, + { url = "https://files.pythonhosted.org/packages/37/da/9d33196ecc99fba16a409c691ed464a3a283ac454a34a13a3a57c0d66f3a/scipy-1.17.0-cp313-cp313t-macosx_14_0_arm64.whl", hash = "sha256:363ad4ae2853d88ebcde3ae6ec46ccca903ea9835ee8ba543f12f575e7b07e4e", size = 20537232, upload-time = "2026-01-10T21:27:40.306Z" }, + { url = "https://files.pythonhosted.org/packages/56/9d/f4b184f6ddb28e9a5caea36a6f98e8ecd2a524f9127354087ce780885d83/scipy-1.17.0-cp313-cp313t-macosx_14_0_x86_64.whl", hash = "sha256:979c3a0ff8e5ba254d45d59ebd38cde48fce4f10b5125c680c7a4bfe177aab07", size = 22791051, upload-time = "2026-01-10T21:27:46.539Z" }, + { url = "https://files.pythonhosted.org/packages/9b/9d/025cccdd738a72140efc582b1641d0dd4caf2e86c3fb127568dc80444e6e/scipy-1.17.0-cp313-cp313t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:130d12926ae34399d157de777472bf82e9061c60cc081372b3118edacafe1d00", size = 32815098, upload-time = "2026-01-10T21:27:54.389Z" }, + { url = "https://files.pythonhosted.org/packages/48/5f/09b879619f8bca15ce392bfc1894bd9c54377e01d1b3f2f3b595a1b4d945/scipy-1.17.0-cp313-cp313t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6e886000eb4919eae3a44f035e63f0fd8b651234117e8f6f29bad1cd26e7bc45", size = 35031342, upload-time = "2026-01-10T21:28:03.012Z" }, + { url = "https://files.pythonhosted.org/packages/f2/9a/f0f0a9f0aa079d2f106555b984ff0fbb11a837df280f04f71f056ea9c6e4/scipy-1.17.0-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:13c4096ac6bc31d706018f06a49abe0485f96499deb82066b94d19b02f664209", size = 34893199, upload-time = "2026-01-10T21:28:10.832Z" }, + { url = "https://files.pythonhosted.org/packages/90/b8/4f0f5cf0c5ea4d7548424e6533e6b17d164f34a6e2fb2e43ffebb6697b06/scipy-1.17.0-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:cacbaddd91fcffde703934897c5cd2c7cb0371fac195d383f4e1f1c5d3f3bd04", size = 37438061, upload-time = "2026-01-10T21:28:19.684Z" }, + { url = "https://files.pythonhosted.org/packages/f9/cc/2bd59140ed3b2fa2882fb15da0a9cb1b5a6443d67cfd0d98d4cec83a57ec/scipy-1.17.0-cp313-cp313t-win_amd64.whl", hash = "sha256:edce1a1cf66298cccdc48a1bdf8fb10a3bf58e8b58d6c3883dd1530e103f87c0", size = 36328593, upload-time = "2026-01-10T21:28:28.007Z" }, + { url = "https://files.pythonhosted.org/packages/13/1b/c87cc44a0d2c7aaf0f003aef2904c3d097b422a96c7e7c07f5efd9073c1b/scipy-1.17.0-cp313-cp313t-win_arm64.whl", hash = "sha256:30509da9dbec1c2ed8f168b8d8aa853bc6723fede1dbc23c7d43a56f5ab72a67", size = 24625083, upload-time = "2026-01-10T21:28:35.188Z" }, + { url = "https://files.pythonhosted.org/packages/1a/2d/51006cd369b8e7879e1c630999a19d1fbf6f8b5ed3e33374f29dc87e53b3/scipy-1.17.0-cp314-cp314-macosx_10_14_x86_64.whl", hash = "sha256:c17514d11b78be8f7e6331b983a65a7f5ca1fd037b95e27b280921fe5606286a", size = 31346803, upload-time = "2026-01-10T21:28:57.24Z" }, + { url = "https://files.pythonhosted.org/packages/d6/2e/2349458c3ce445f53a6c93d4386b1c4c5c0c540917304c01222ff95ff317/scipy-1.17.0-cp314-cp314-macosx_12_0_arm64.whl", hash = "sha256:4e00562e519c09da34c31685f6acc3aa384d4d50604db0f245c14e1b4488bfa2", size = 27967182, upload-time = "2026-01-10T21:29:04.107Z" }, + { url = "https://files.pythonhosted.org/packages/5e/7c/df525fbfa77b878d1cfe625249529514dc02f4fd5f45f0f6295676a76528/scipy-1.17.0-cp314-cp314-macosx_14_0_arm64.whl", hash = "sha256:f7df7941d71314e60a481e02d5ebcb3f0185b8d799c70d03d8258f6c80f3d467", size = 20139125, upload-time = "2026-01-10T21:29:10.179Z" }, + { url = "https://files.pythonhosted.org/packages/33/11/fcf9d43a7ed1234d31765ec643b0515a85a30b58eddccc5d5a4d12b5f194/scipy-1.17.0-cp314-cp314-macosx_14_0_x86_64.whl", hash = "sha256:aabf057c632798832f071a8dde013c2e26284043934f53b00489f1773b33527e", size = 22443554, upload-time = "2026-01-10T21:29:15.888Z" }, + { url = "https://files.pythonhosted.org/packages/80/5c/ea5d239cda2dd3d31399424967a24d556cf409fbea7b5b21412b0fd0a44f/scipy-1.17.0-cp314-cp314-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:a38c3337e00be6fd8a95b4ed66b5d988bac4ec888fd922c2ea9fe5fb1603dd67", size = 32757834, upload-time = "2026-01-10T21:29:23.406Z" }, + { url = "https://files.pythonhosted.org/packages/b8/7e/8c917cc573310e5dc91cbeead76f1b600d3fb17cf0969db02c9cf92e3cfa/scipy-1.17.0-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:00fb5f8ec8398ad90215008d8b6009c9db9fa924fd4c7d6be307c6f945f9cd73", size = 34995775, upload-time = "2026-01-10T21:29:31.915Z" }, + { url = "https://files.pythonhosted.org/packages/c5/43/176c0c3c07b3f7df324e7cdd933d3e2c4898ca202b090bd5ba122f9fe270/scipy-1.17.0-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:f2a4942b0f5f7c23c7cd641a0ca1955e2ae83dedcff537e3a0259096635e186b", size = 34841240, upload-time = "2026-01-10T21:29:39.995Z" }, + { url = "https://files.pythonhosted.org/packages/44/8c/d1f5f4b491160592e7f084d997de53a8e896a3ac01cd07e59f43ca222744/scipy-1.17.0-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:dbf133ced83889583156566d2bdf7a07ff89228fe0c0cb727f777de92092ec6b", size = 37394463, upload-time = "2026-01-10T21:29:48.723Z" }, + { url = "https://files.pythonhosted.org/packages/9f/ec/42a6657f8d2d087e750e9a5dde0b481fd135657f09eaf1cf5688bb23c338/scipy-1.17.0-cp314-cp314-win_amd64.whl", hash = "sha256:3625c631a7acd7cfd929e4e31d2582cf00f42fcf06011f59281271746d77e061", size = 37053015, upload-time = "2026-01-10T21:30:51.418Z" }, + { url = "https://files.pythonhosted.org/packages/27/58/6b89a6afd132787d89a362d443a7bddd511b8f41336a1ae47f9e4f000dc4/scipy-1.17.0-cp314-cp314-win_arm64.whl", hash = "sha256:9244608d27eafe02b20558523ba57f15c689357c85bdcfe920b1828750aa26eb", size = 24951312, upload-time = "2026-01-10T21:30:56.771Z" }, + { url = "https://files.pythonhosted.org/packages/e9/01/f58916b9d9ae0112b86d7c3b10b9e685625ce6e8248df139d0fcb17f7397/scipy-1.17.0-cp314-cp314t-macosx_10_14_x86_64.whl", hash = "sha256:2b531f57e09c946f56ad0b4a3b2abee778789097871fc541e267d2eca081cff1", size = 31706502, upload-time = "2026-01-10T21:29:56.326Z" }, + { url = "https://files.pythonhosted.org/packages/59/8e/2912a87f94a7d1f8b38aabc0faf74b82d3b6c9e22be991c49979f0eceed8/scipy-1.17.0-cp314-cp314t-macosx_12_0_arm64.whl", hash = "sha256:13e861634a2c480bd237deb69333ac79ea1941b94568d4b0efa5db5e263d4fd1", size = 28380854, upload-time = "2026-01-10T21:30:01.554Z" }, + { url = "https://files.pythonhosted.org/packages/bd/1c/874137a52dddab7d5d595c1887089a2125d27d0601fce8c0026a24a92a0b/scipy-1.17.0-cp314-cp314t-macosx_14_0_arm64.whl", hash = "sha256:eb2651271135154aa24f6481cbae5cc8af1f0dd46e6533fb7b56aa9727b6a232", size = 20552752, upload-time = "2026-01-10T21:30:05.93Z" }, + { url = "https://files.pythonhosted.org/packages/3f/f0/7518d171cb735f6400f4576cf70f756d5b419a07fe1867da34e2c2c9c11b/scipy-1.17.0-cp314-cp314t-macosx_14_0_x86_64.whl", hash = "sha256:c5e8647f60679790c2f5c76be17e2e9247dc6b98ad0d3b065861e082c56e078d", size = 22803972, upload-time = "2026-01-10T21:30:10.651Z" }, + { url = "https://files.pythonhosted.org/packages/7c/74/3498563a2c619e8a3ebb4d75457486c249b19b5b04a30600dfd9af06bea5/scipy-1.17.0-cp314-cp314t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:5fb10d17e649e1446410895639f3385fd2bf4c3c7dfc9bea937bddcbc3d7b9ba", size = 32829770, upload-time = "2026-01-10T21:30:16.359Z" }, + { url = "https://files.pythonhosted.org/packages/48/d1/7b50cedd8c6c9d6f706b4b36fa8544d829c712a75e370f763b318e9638c1/scipy-1.17.0-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:8547e7c57f932e7354a2319fab613981cde910631979f74c9b542bb167a8b9db", size = 35051093, upload-time = "2026-01-10T21:30:22.987Z" }, + { url = "https://files.pythonhosted.org/packages/e2/82/a2d684dfddb87ba1b3ea325df7c3293496ee9accb3a19abe9429bce94755/scipy-1.17.0-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:33af70d040e8af9d5e7a38b5ed3b772adddd281e3062ff23fec49e49681c38cf", size = 34909905, upload-time = "2026-01-10T21:30:28.704Z" }, + { url = "https://files.pythonhosted.org/packages/ef/5e/e565bd73991d42023eb82bb99e51c5b3d9e2c588ca9d4b3e2cc1d3ca62a6/scipy-1.17.0-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:f9eb55bb97d00f8b7ab95cb64f873eb0bf54d9446264d9f3609130381233483f", size = 37457743, upload-time = "2026-01-10T21:30:34.819Z" }, + { url = "https://files.pythonhosted.org/packages/58/a8/a66a75c3d8f1fb2b83f66007d6455a06a6f6cf5618c3dc35bc9b69dd096e/scipy-1.17.0-cp314-cp314t-win_amd64.whl", hash = "sha256:1ff269abf702f6c7e67a4b7aad981d42871a11b9dd83c58d2d2ea624efbd1088", size = 37098574, upload-time = "2026-01-10T21:30:40.782Z" }, + { url = "https://files.pythonhosted.org/packages/56/a5/df8f46ef7da168f1bc52cd86e09a9de5c6f19cc1da04454d51b7d4f43408/scipy-1.17.0-cp314-cp314t-win_arm64.whl", hash = "sha256:031121914e295d9791319a1875444d55079885bbae5bdc9c5e0f2ee5f09d34ff", size = 25246266, upload-time = "2026-01-10T21:30:45.923Z" }, ] [[package]] @@ -7916,7 +7918,7 @@ dependencies = [ { name = "scikit-learn", version = "1.7.2", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, { name = "scikit-learn", version = "1.8.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "torch" }, { name = "tqdm" }, { name = "transformers" }, @@ -8471,51 +8473,56 @@ wheels = [ [[package]] name = "tomli" -version = "2.3.0" +version = "2.4.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/52/ed/3f73f72945444548f33eba9a87fc7a6e969915e7b1acc8260b30e1f76a2f/tomli-2.3.0.tar.gz", hash = "sha256:64be704a875d2a59753d80ee8a533c3fe183e3f06807ff7dc2232938ccb01549", size = 17392, upload-time = "2025-10-08T22:01:47.119Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/b3/2e/299f62b401438d5fe1624119c723f5d877acc86a4c2492da405626665f12/tomli-2.3.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:88bd15eb972f3664f5ed4b57c1634a97153b4bac4479dcb6a495f41921eb7f45", size = 153236, upload-time = "2025-10-08T22:01:00.137Z" }, - { url = "https://files.pythonhosted.org/packages/86/7f/d8fffe6a7aefdb61bced88fcb5e280cfd71e08939da5894161bd71bea022/tomli-2.3.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:883b1c0d6398a6a9d29b508c331fa56adbcdff647f6ace4dfca0f50e90dfd0ba", size = 148084, upload-time = "2025-10-08T22:01:01.63Z" }, - { url = "https://files.pythonhosted.org/packages/47/5c/24935fb6a2ee63e86d80e4d3b58b222dafaf438c416752c8b58537c8b89a/tomli-2.3.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:d1381caf13ab9f300e30dd8feadb3de072aeb86f1d34a8569453ff32a7dea4bf", size = 234832, upload-time = "2025-10-08T22:01:02.543Z" }, - { url = "https://files.pythonhosted.org/packages/89/da/75dfd804fc11e6612846758a23f13271b76d577e299592b4371a4ca4cd09/tomli-2.3.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a0e285d2649b78c0d9027570d4da3425bdb49830a6156121360b3f8511ea3441", size = 242052, upload-time = "2025-10-08T22:01:03.836Z" }, - { url = "https://files.pythonhosted.org/packages/70/8c/f48ac899f7b3ca7eb13af73bacbc93aec37f9c954df3c08ad96991c8c373/tomli-2.3.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:0a154a9ae14bfcf5d8917a59b51ffd5a3ac1fd149b71b47a3a104ca4edcfa845", size = 239555, upload-time = "2025-10-08T22:01:04.834Z" }, - { url = "https://files.pythonhosted.org/packages/ba/28/72f8afd73f1d0e7829bfc093f4cb98ce0a40ffc0cc997009ee1ed94ba705/tomli-2.3.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:74bf8464ff93e413514fefd2be591c3b0b23231a77f901db1eb30d6f712fc42c", size = 245128, upload-time = "2025-10-08T22:01:05.84Z" }, - { url = "https://files.pythonhosted.org/packages/b6/eb/a7679c8ac85208706d27436e8d421dfa39d4c914dcf5fa8083a9305f58d9/tomli-2.3.0-cp311-cp311-win32.whl", hash = "sha256:00b5f5d95bbfc7d12f91ad8c593a1659b6387b43f054104cda404be6bda62456", size = 96445, upload-time = "2025-10-08T22:01:06.896Z" }, - { url = "https://files.pythonhosted.org/packages/0a/fe/3d3420c4cb1ad9cb462fb52967080575f15898da97e21cb6f1361d505383/tomli-2.3.0-cp311-cp311-win_amd64.whl", hash = "sha256:4dc4ce8483a5d429ab602f111a93a6ab1ed425eae3122032db7e9acf449451be", size = 107165, upload-time = "2025-10-08T22:01:08.107Z" }, - { url = "https://files.pythonhosted.org/packages/ff/b7/40f36368fcabc518bb11c8f06379a0fd631985046c038aca08c6d6a43c6e/tomli-2.3.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:d7d86942e56ded512a594786a5ba0a5e521d02529b3826e7761a05138341a2ac", size = 154891, upload-time = "2025-10-08T22:01:09.082Z" }, - { url = "https://files.pythonhosted.org/packages/f9/3f/d9dd692199e3b3aab2e4e4dd948abd0f790d9ded8cd10cbaae276a898434/tomli-2.3.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:73ee0b47d4dad1c5e996e3cd33b8a76a50167ae5f96a2607cbe8cc773506ab22", size = 148796, upload-time = "2025-10-08T22:01:10.266Z" }, - { url = "https://files.pythonhosted.org/packages/60/83/59bff4996c2cf9f9387a0f5a3394629c7efa5ef16142076a23a90f1955fa/tomli-2.3.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:792262b94d5d0a466afb5bc63c7daa9d75520110971ee269152083270998316f", size = 242121, upload-time = "2025-10-08T22:01:11.332Z" }, - { url = "https://files.pythonhosted.org/packages/45/e5/7c5119ff39de8693d6baab6c0b6dcb556d192c165596e9fc231ea1052041/tomli-2.3.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:4f195fe57ecceac95a66a75ac24d9d5fbc98ef0962e09b2eddec5d39375aae52", size = 250070, upload-time = "2025-10-08T22:01:12.498Z" }, - { url = "https://files.pythonhosted.org/packages/45/12/ad5126d3a278f27e6701abde51d342aa78d06e27ce2bb596a01f7709a5a2/tomli-2.3.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:e31d432427dcbf4d86958c184b9bfd1e96b5b71f8eb17e6d02531f434fd335b8", size = 245859, upload-time = "2025-10-08T22:01:13.551Z" }, - { url = "https://files.pythonhosted.org/packages/fb/a1/4d6865da6a71c603cfe6ad0e6556c73c76548557a8d658f9e3b142df245f/tomli-2.3.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:7b0882799624980785240ab732537fcfc372601015c00f7fc367c55308c186f6", size = 250296, upload-time = "2025-10-08T22:01:14.614Z" }, - { url = "https://files.pythonhosted.org/packages/a0/b7/a7a7042715d55c9ba6e8b196d65d2cb662578b4d8cd17d882d45322b0d78/tomli-2.3.0-cp312-cp312-win32.whl", hash = "sha256:ff72b71b5d10d22ecb084d345fc26f42b5143c5533db5e2eaba7d2d335358876", size = 97124, upload-time = "2025-10-08T22:01:15.629Z" }, - { url = "https://files.pythonhosted.org/packages/06/1e/f22f100db15a68b520664eb3328fb0ae4e90530887928558112c8d1f4515/tomli-2.3.0-cp312-cp312-win_amd64.whl", hash = "sha256:1cb4ed918939151a03f33d4242ccd0aa5f11b3547d0cf30f7c74a408a5b99878", size = 107698, upload-time = "2025-10-08T22:01:16.51Z" }, - { url = "https://files.pythonhosted.org/packages/89/48/06ee6eabe4fdd9ecd48bf488f4ac783844fd777f547b8d1b61c11939974e/tomli-2.3.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:5192f562738228945d7b13d4930baffda67b69425a7f0da96d360b0a3888136b", size = 154819, upload-time = "2025-10-08T22:01:17.964Z" }, - { url = "https://files.pythonhosted.org/packages/f1/01/88793757d54d8937015c75dcdfb673c65471945f6be98e6a0410fba167ed/tomli-2.3.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:be71c93a63d738597996be9528f4abe628d1adf5e6eb11607bc8fe1a510b5dae", size = 148766, upload-time = "2025-10-08T22:01:18.959Z" }, - { url = "https://files.pythonhosted.org/packages/42/17/5e2c956f0144b812e7e107f94f1cc54af734eb17b5191c0bbfb72de5e93e/tomli-2.3.0-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c4665508bcbac83a31ff8ab08f424b665200c0e1e645d2bd9ab3d3e557b6185b", size = 240771, upload-time = "2025-10-08T22:01:20.106Z" }, - { url = "https://files.pythonhosted.org/packages/d5/f4/0fbd014909748706c01d16824eadb0307115f9562a15cbb012cd9b3512c5/tomli-2.3.0-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:4021923f97266babc6ccab9f5068642a0095faa0a51a246a6a02fccbb3514eaf", size = 248586, upload-time = "2025-10-08T22:01:21.164Z" }, - { url = "https://files.pythonhosted.org/packages/30/77/fed85e114bde5e81ecf9bc5da0cc69f2914b38f4708c80ae67d0c10180c5/tomli-2.3.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:a4ea38c40145a357d513bffad0ed869f13c1773716cf71ccaa83b0fa0cc4e42f", size = 244792, upload-time = "2025-10-08T22:01:22.417Z" }, - { url = "https://files.pythonhosted.org/packages/55/92/afed3d497f7c186dc71e6ee6d4fcb0acfa5f7d0a1a2878f8beae379ae0cc/tomli-2.3.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:ad805ea85eda330dbad64c7ea7a4556259665bdf9d2672f5dccc740eb9d3ca05", size = 248909, upload-time = "2025-10-08T22:01:23.859Z" }, - { url = "https://files.pythonhosted.org/packages/f8/84/ef50c51b5a9472e7265ce1ffc7f24cd4023d289e109f669bdb1553f6a7c2/tomli-2.3.0-cp313-cp313-win32.whl", hash = "sha256:97d5eec30149fd3294270e889b4234023f2c69747e555a27bd708828353ab606", size = 96946, upload-time = "2025-10-08T22:01:24.893Z" }, - { url = "https://files.pythonhosted.org/packages/b2/b7/718cd1da0884f281f95ccfa3a6cc572d30053cba64603f79d431d3c9b61b/tomli-2.3.0-cp313-cp313-win_amd64.whl", hash = "sha256:0c95ca56fbe89e065c6ead5b593ee64b84a26fca063b5d71a1122bf26e533999", size = 107705, upload-time = "2025-10-08T22:01:26.153Z" }, - { url = "https://files.pythonhosted.org/packages/19/94/aeafa14a52e16163008060506fcb6aa1949d13548d13752171a755c65611/tomli-2.3.0-cp314-cp314-macosx_10_13_x86_64.whl", hash = "sha256:cebc6fe843e0733ee827a282aca4999b596241195f43b4cc371d64fc6639da9e", size = 154244, upload-time = "2025-10-08T22:01:27.06Z" }, - { url = "https://files.pythonhosted.org/packages/db/e4/1e58409aa78eefa47ccd19779fc6f36787edbe7d4cd330eeeedb33a4515b/tomli-2.3.0-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:4c2ef0244c75aba9355561272009d934953817c49f47d768070c3c94355c2aa3", size = 148637, upload-time = "2025-10-08T22:01:28.059Z" }, - { url = "https://files.pythonhosted.org/packages/26/b6/d1eccb62f665e44359226811064596dd6a366ea1f985839c566cd61525ae/tomli-2.3.0-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c22a8bf253bacc0cf11f35ad9808b6cb75ada2631c2d97c971122583b129afbc", size = 241925, upload-time = "2025-10-08T22:01:29.066Z" }, - { url = "https://files.pythonhosted.org/packages/70/91/7cdab9a03e6d3d2bb11beae108da5bdc1c34bdeb06e21163482544ddcc90/tomli-2.3.0-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:0eea8cc5c5e9f89c9b90c4896a8deefc74f518db5927d0e0e8d4a80953d774d0", size = 249045, upload-time = "2025-10-08T22:01:31.98Z" }, - { url = "https://files.pythonhosted.org/packages/15/1b/8c26874ed1f6e4f1fcfeb868db8a794cbe9f227299402db58cfcc858766c/tomli-2.3.0-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:b74a0e59ec5d15127acdabd75ea17726ac4c5178ae51b85bfe39c4f8a278e879", size = 245835, upload-time = "2025-10-08T22:01:32.989Z" }, - { url = "https://files.pythonhosted.org/packages/fd/42/8e3c6a9a4b1a1360c1a2a39f0b972cef2cc9ebd56025168c4137192a9321/tomli-2.3.0-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:b5870b50c9db823c595983571d1296a6ff3e1b88f734a4c8f6fc6188397de005", size = 253109, upload-time = "2025-10-08T22:01:34.052Z" }, - { url = "https://files.pythonhosted.org/packages/22/0c/b4da635000a71b5f80130937eeac12e686eefb376b8dee113b4a582bba42/tomli-2.3.0-cp314-cp314-win32.whl", hash = "sha256:feb0dacc61170ed7ab602d3d972a58f14ee3ee60494292d384649a3dc38ef463", size = 97930, upload-time = "2025-10-08T22:01:35.082Z" }, - { url = "https://files.pythonhosted.org/packages/b9/74/cb1abc870a418ae99cd5c9547d6bce30701a954e0e721821df483ef7223c/tomli-2.3.0-cp314-cp314-win_amd64.whl", hash = "sha256:b273fcbd7fc64dc3600c098e39136522650c49bca95df2d11cf3b626422392c8", size = 107964, upload-time = "2025-10-08T22:01:36.057Z" }, - { url = "https://files.pythonhosted.org/packages/54/78/5c46fff6432a712af9f792944f4fcd7067d8823157949f4e40c56b8b3c83/tomli-2.3.0-cp314-cp314t-macosx_10_13_x86_64.whl", hash = "sha256:940d56ee0410fa17ee1f12b817b37a4d4e4dc4d27340863cc67236c74f582e77", size = 163065, upload-time = "2025-10-08T22:01:37.27Z" }, - { url = "https://files.pythonhosted.org/packages/39/67/f85d9bd23182f45eca8939cd2bc7050e1f90c41f4a2ecbbd5963a1d1c486/tomli-2.3.0-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:f85209946d1fe94416debbb88d00eb92ce9cd5266775424ff81bc959e001acaf", size = 159088, upload-time = "2025-10-08T22:01:38.235Z" }, - { url = "https://files.pythonhosted.org/packages/26/5a/4b546a0405b9cc0659b399f12b6adb750757baf04250b148d3c5059fc4eb/tomli-2.3.0-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:a56212bdcce682e56b0aaf79e869ba5d15a6163f88d5451cbde388d48b13f530", size = 268193, upload-time = "2025-10-08T22:01:39.712Z" }, - { url = "https://files.pythonhosted.org/packages/42/4f/2c12a72ae22cf7b59a7fe75b3465b7aba40ea9145d026ba41cb382075b0e/tomli-2.3.0-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:c5f3ffd1e098dfc032d4d3af5c0ac64f6d286d98bc148698356847b80fa4de1b", size = 275488, upload-time = "2025-10-08T22:01:40.773Z" }, - { url = "https://files.pythonhosted.org/packages/92/04/a038d65dbe160c3aa5a624e93ad98111090f6804027d474ba9c37c8ae186/tomli-2.3.0-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:5e01decd096b1530d97d5d85cb4dff4af2d8347bd35686654a004f8dea20fc67", size = 272669, upload-time = "2025-10-08T22:01:41.824Z" }, - { url = "https://files.pythonhosted.org/packages/be/2f/8b7c60a9d1612a7cbc39ffcca4f21a73bf368a80fc25bccf8253e2563267/tomli-2.3.0-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:8a35dd0e643bb2610f156cca8db95d213a90015c11fee76c946aa62b7ae7e02f", size = 279709, upload-time = "2025-10-08T22:01:43.177Z" }, - { url = "https://files.pythonhosted.org/packages/7e/46/cc36c679f09f27ded940281c38607716c86cf8ba4a518d524e349c8b4874/tomli-2.3.0-cp314-cp314t-win32.whl", hash = "sha256:a1f7f282fe248311650081faafa5f4732bdbfef5d45fe3f2e702fbc6f2d496e0", size = 107563, upload-time = "2025-10-08T22:01:44.233Z" }, - { url = "https://files.pythonhosted.org/packages/84/ff/426ca8683cf7b753614480484f6437f568fd2fda2edbdf57a2d3d8b27a0b/tomli-2.3.0-cp314-cp314t-win_amd64.whl", hash = "sha256:70a251f8d4ba2d9ac2542eecf008b3c8a9fc5c3f9f02c56a9d7952612be2fdba", size = 119756, upload-time = "2025-10-08T22:01:45.234Z" }, - { url = "https://files.pythonhosted.org/packages/77/b8/0135fadc89e73be292b473cb820b4f5a08197779206b33191e801feeae40/tomli-2.3.0-py3-none-any.whl", hash = "sha256:e95b1af3c5b07d9e643909b5abbec77cd9f1217e6d0bca72b0234736b9fb1f1b", size = 14408, upload-time = "2025-10-08T22:01:46.04Z" }, +sdist = { url = "https://files.pythonhosted.org/packages/82/30/31573e9457673ab10aa432461bee537ce6cef177667deca369efb79df071/tomli-2.4.0.tar.gz", hash = "sha256:aa89c3f6c277dd275d8e243ad24f3b5e701491a860d5121f2cdd399fbb31fc9c", size = 17477, upload-time = "2026-01-11T11:22:38.165Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/3c/d9/3dc2289e1f3b32eb19b9785b6a006b28ee99acb37d1d47f78d4c10e28bf8/tomli-2.4.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:b5ef256a3fd497d4973c11bf142e9ed78b150d36f5773f1ca6088c230ffc5867", size = 153663, upload-time = "2026-01-11T11:21:45.27Z" }, + { url = "https://files.pythonhosted.org/packages/51/32/ef9f6845e6b9ca392cd3f64f9ec185cc6f09f0a2df3db08cbe8809d1d435/tomli-2.4.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:5572e41282d5268eb09a697c89a7bee84fae66511f87533a6f88bd2f7b652da9", size = 148469, upload-time = "2026-01-11T11:21:46.873Z" }, + { url = "https://files.pythonhosted.org/packages/d6/c2/506e44cce89a8b1b1e047d64bd495c22c9f71f21e05f380f1a950dd9c217/tomli-2.4.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:551e321c6ba03b55676970b47cb1b73f14a0a4dce6a3e1a9458fd6d921d72e95", size = 236039, upload-time = "2026-01-11T11:21:48.503Z" }, + { url = "https://files.pythonhosted.org/packages/b3/40/e1b65986dbc861b7e986e8ec394598187fa8aee85b1650b01dd925ca0be8/tomli-2.4.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:5e3f639a7a8f10069d0e15408c0b96a2a828cfdec6fca05296ebcdcc28ca7c76", size = 243007, upload-time = "2026-01-11T11:21:49.456Z" }, + { url = "https://files.pythonhosted.org/packages/9c/6f/6e39ce66b58a5b7ae572a0f4352ff40c71e8573633deda43f6a379d56b3e/tomli-2.4.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:1b168f2731796b045128c45982d3a4874057626da0e2ef1fdd722848b741361d", size = 240875, upload-time = "2026-01-11T11:21:50.755Z" }, + { url = "https://files.pythonhosted.org/packages/aa/ad/cb089cb190487caa80204d503c7fd0f4d443f90b95cf4ef5cf5aa0f439b0/tomli-2.4.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:133e93646ec4300d651839d382d63edff11d8978be23da4cc106f5a18b7d0576", size = 246271, upload-time = "2026-01-11T11:21:51.81Z" }, + { url = "https://files.pythonhosted.org/packages/0b/63/69125220e47fd7a3a27fd0de0c6398c89432fec41bc739823bcc66506af6/tomli-2.4.0-cp311-cp311-win32.whl", hash = "sha256:b6c78bdf37764092d369722d9946cb65b8767bfa4110f902a1b2542d8d173c8a", size = 96770, upload-time = "2026-01-11T11:21:52.647Z" }, + { url = "https://files.pythonhosted.org/packages/1e/0d/a22bb6c83f83386b0008425a6cd1fa1c14b5f3dd4bad05e98cf3dbbf4a64/tomli-2.4.0-cp311-cp311-win_amd64.whl", hash = "sha256:d3d1654e11d724760cdb37a3d7691f0be9db5fbdaef59c9f532aabf87006dbaa", size = 107626, upload-time = "2026-01-11T11:21:53.459Z" }, + { url = "https://files.pythonhosted.org/packages/2f/6d/77be674a3485e75cacbf2ddba2b146911477bd887dda9d8c9dfb2f15e871/tomli-2.4.0-cp311-cp311-win_arm64.whl", hash = "sha256:cae9c19ed12d4e8f3ebf46d1a75090e4c0dc16271c5bce1c833ac168f08fb614", size = 94842, upload-time = "2026-01-11T11:21:54.831Z" }, + { url = "https://files.pythonhosted.org/packages/3c/43/7389a1869f2f26dba52404e1ef13b4784b6b37dac93bac53457e3ff24ca3/tomli-2.4.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:920b1de295e72887bafa3ad9f7a792f811847d57ea6b1215154030cf131f16b1", size = 154894, upload-time = "2026-01-11T11:21:56.07Z" }, + { url = "https://files.pythonhosted.org/packages/e9/05/2f9bf110b5294132b2edf13fe6ca6ae456204f3d749f623307cbb7a946f2/tomli-2.4.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:7d6d9a4aee98fac3eab4952ad1d73aee87359452d1c086b5ceb43ed02ddb16b8", size = 149053, upload-time = "2026-01-11T11:21:57.467Z" }, + { url = "https://files.pythonhosted.org/packages/e8/41/1eda3ca1abc6f6154a8db4d714a4d35c4ad90adc0bcf700657291593fbf3/tomli-2.4.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:36b9d05b51e65b254ea6c2585b59d2c4cb91c8a3d91d0ed0f17591a29aaea54a", size = 243481, upload-time = "2026-01-11T11:21:58.661Z" }, + { url = "https://files.pythonhosted.org/packages/d2/6d/02ff5ab6c8868b41e7d4b987ce2b5f6a51d3335a70aa144edd999e055a01/tomli-2.4.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:1c8a885b370751837c029ef9bc014f27d80840e48bac415f3412e6593bbc18c1", size = 251720, upload-time = "2026-01-11T11:22:00.178Z" }, + { url = "https://files.pythonhosted.org/packages/7b/57/0405c59a909c45d5b6f146107c6d997825aa87568b042042f7a9c0afed34/tomli-2.4.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:8768715ffc41f0008abe25d808c20c3d990f42b6e2e58305d5da280ae7d1fa3b", size = 247014, upload-time = "2026-01-11T11:22:01.238Z" }, + { url = "https://files.pythonhosted.org/packages/2c/0e/2e37568edd944b4165735687cbaf2fe3648129e440c26d02223672ee0630/tomli-2.4.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:7b438885858efd5be02a9a133caf5812b8776ee0c969fea02c45e8e3f296ba51", size = 251820, upload-time = "2026-01-11T11:22:02.727Z" }, + { url = "https://files.pythonhosted.org/packages/5a/1c/ee3b707fdac82aeeb92d1a113f803cf6d0f37bdca0849cb489553e1f417a/tomli-2.4.0-cp312-cp312-win32.whl", hash = "sha256:0408e3de5ec77cc7f81960c362543cbbd91ef883e3138e81b729fc3eea5b9729", size = 97712, upload-time = "2026-01-11T11:22:03.777Z" }, + { url = "https://files.pythonhosted.org/packages/69/13/c07a9177d0b3bab7913299b9278845fc6eaaca14a02667c6be0b0a2270c8/tomli-2.4.0-cp312-cp312-win_amd64.whl", hash = "sha256:685306e2cc7da35be4ee914fd34ab801a6acacb061b6a7abca922aaf9ad368da", size = 108296, upload-time = "2026-01-11T11:22:04.86Z" }, + { url = "https://files.pythonhosted.org/packages/18/27/e267a60bbeeee343bcc279bb9e8fbed0cbe224bc7b2a3dc2975f22809a09/tomli-2.4.0-cp312-cp312-win_arm64.whl", hash = "sha256:5aa48d7c2356055feef06a43611fc401a07337d5b006be13a30f6c58f869e3c3", size = 94553, upload-time = "2026-01-11T11:22:05.854Z" }, + { url = "https://files.pythonhosted.org/packages/34/91/7f65f9809f2936e1f4ce6268ae1903074563603b2a2bd969ebbda802744f/tomli-2.4.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:84d081fbc252d1b6a982e1870660e7330fb8f90f676f6e78b052ad4e64714bf0", size = 154915, upload-time = "2026-01-11T11:22:06.703Z" }, + { url = "https://files.pythonhosted.org/packages/20/aa/64dd73a5a849c2e8f216b755599c511badde80e91e9bc2271baa7b2cdbb1/tomli-2.4.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:9a08144fa4cba33db5255f9b74f0b89888622109bd2776148f2597447f92a94e", size = 149038, upload-time = "2026-01-11T11:22:07.56Z" }, + { url = "https://files.pythonhosted.org/packages/9e/8a/6d38870bd3d52c8d1505ce054469a73f73a0fe62c0eaf5dddf61447e32fa/tomli-2.4.0-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c73add4bb52a206fd0c0723432db123c0c75c280cbd67174dd9d2db228ebb1b4", size = 242245, upload-time = "2026-01-11T11:22:08.344Z" }, + { url = "https://files.pythonhosted.org/packages/59/bb/8002fadefb64ab2669e5b977df3f5e444febea60e717e755b38bb7c41029/tomli-2.4.0-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:1fb2945cbe303b1419e2706e711b7113da57b7db31ee378d08712d678a34e51e", size = 250335, upload-time = "2026-01-11T11:22:09.951Z" }, + { url = "https://files.pythonhosted.org/packages/a5/3d/4cdb6f791682b2ea916af2de96121b3cb1284d7c203d97d92d6003e91c8d/tomli-2.4.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:bbb1b10aa643d973366dc2cb1ad94f99c1726a02343d43cbc011edbfac579e7c", size = 245962, upload-time = "2026-01-11T11:22:11.27Z" }, + { url = "https://files.pythonhosted.org/packages/f2/4a/5f25789f9a460bd858ba9756ff52d0830d825b458e13f754952dd15fb7bb/tomli-2.4.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:4cbcb367d44a1f0c2be408758b43e1ffb5308abe0ea222897d6bfc8e8281ef2f", size = 250396, upload-time = "2026-01-11T11:22:12.325Z" }, + { url = "https://files.pythonhosted.org/packages/aa/2f/b73a36fea58dfa08e8b3a268750e6853a6aac2a349241a905ebd86f3047a/tomli-2.4.0-cp313-cp313-win32.whl", hash = "sha256:7d49c66a7d5e56ac959cb6fc583aff0651094ec071ba9ad43df785abc2320d86", size = 97530, upload-time = "2026-01-11T11:22:13.865Z" }, + { url = "https://files.pythonhosted.org/packages/3b/af/ca18c134b5d75de7e8dc551c5234eaba2e8e951f6b30139599b53de9c187/tomli-2.4.0-cp313-cp313-win_amd64.whl", hash = "sha256:3cf226acb51d8f1c394c1b310e0e0e61fecdd7adcb78d01e294ac297dd2e7f87", size = 108227, upload-time = "2026-01-11T11:22:15.224Z" }, + { url = "https://files.pythonhosted.org/packages/22/c3/b386b832f209fee8073c8138ec50f27b4460db2fdae9ffe022df89a57f9b/tomli-2.4.0-cp313-cp313-win_arm64.whl", hash = "sha256:d20b797a5c1ad80c516e41bc1fb0443ddb5006e9aaa7bda2d71978346aeb9132", size = 94748, upload-time = "2026-01-11T11:22:16.009Z" }, + { url = "https://files.pythonhosted.org/packages/f3/c4/84047a97eb1004418bc10bdbcfebda209fca6338002eba2dc27cc6d13563/tomli-2.4.0-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:26ab906a1eb794cd4e103691daa23d95c6919cc2fa9160000ac02370cc9dd3f6", size = 154725, upload-time = "2026-01-11T11:22:17.269Z" }, + { url = "https://files.pythonhosted.org/packages/a8/5d/d39038e646060b9d76274078cddf146ced86dc2b9e8bbf737ad5983609a0/tomli-2.4.0-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:20cedb4ee43278bc4f2fee6cb50daec836959aadaf948db5172e776dd3d993fc", size = 148901, upload-time = "2026-01-11T11:22:18.287Z" }, + { url = "https://files.pythonhosted.org/packages/73/e5/383be1724cb30f4ce44983d249645684a48c435e1cd4f8b5cded8a816d3c/tomli-2.4.0-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:39b0b5d1b6dd03684b3fb276407ebed7090bbec989fa55838c98560c01113b66", size = 243375, upload-time = "2026-01-11T11:22:19.154Z" }, + { url = "https://files.pythonhosted.org/packages/31/f0/bea80c17971c8d16d3cc109dc3585b0f2ce1036b5f4a8a183789023574f2/tomli-2.4.0-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a26d7ff68dfdb9f87a016ecfd1e1c2bacbe3108f4e0f8bcd2228ef9a766c787d", size = 250639, upload-time = "2026-01-11T11:22:20.168Z" }, + { url = "https://files.pythonhosted.org/packages/2c/8f/2853c36abbb7608e3f945d8a74e32ed3a74ee3a1f468f1ffc7d1cb3abba6/tomli-2.4.0-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:20ffd184fb1df76a66e34bd1b36b4a4641bd2b82954befa32fe8163e79f1a702", size = 246897, upload-time = "2026-01-11T11:22:21.544Z" }, + { url = "https://files.pythonhosted.org/packages/49/f0/6c05e3196ed5337b9fe7ea003e95fd3819a840b7a0f2bf5a408ef1dad8ed/tomli-2.4.0-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:75c2f8bbddf170e8effc98f5e9084a8751f8174ea6ccf4fca5398436e0320bc8", size = 254697, upload-time = "2026-01-11T11:22:23.058Z" }, + { url = "https://files.pythonhosted.org/packages/f3/f5/2922ef29c9f2951883525def7429967fc4d8208494e5ab524234f06b688b/tomli-2.4.0-cp314-cp314-win32.whl", hash = "sha256:31d556d079d72db7c584c0627ff3a24c5d3fb4f730221d3444f3efb1b2514776", size = 98567, upload-time = "2026-01-11T11:22:24.033Z" }, + { url = "https://files.pythonhosted.org/packages/7b/31/22b52e2e06dd2a5fdbc3ee73226d763b184ff21fc24e20316a44ccc4d96b/tomli-2.4.0-cp314-cp314-win_amd64.whl", hash = "sha256:43e685b9b2341681907759cf3a04e14d7104b3580f808cfde1dfdb60ada85475", size = 108556, upload-time = "2026-01-11T11:22:25.378Z" }, + { url = "https://files.pythonhosted.org/packages/48/3d/5058dff3255a3d01b705413f64f4306a141a8fd7a251e5a495e3f192a998/tomli-2.4.0-cp314-cp314-win_arm64.whl", hash = "sha256:3d895d56bd3f82ddd6faaff993c275efc2ff38e52322ea264122d72729dca2b2", size = 96014, upload-time = "2026-01-11T11:22:26.138Z" }, + { url = "https://files.pythonhosted.org/packages/b8/4e/75dab8586e268424202d3a1997ef6014919c941b50642a1682df43204c22/tomli-2.4.0-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:5b5807f3999fb66776dbce568cc9a828544244a8eb84b84b9bafc080c99597b9", size = 163339, upload-time = "2026-01-11T11:22:27.143Z" }, + { url = "https://files.pythonhosted.org/packages/06/e3/b904d9ab1016829a776d97f163f183a48be6a4deb87304d1e0116a349519/tomli-2.4.0-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:c084ad935abe686bd9c898e62a02a19abfc9760b5a79bc29644463eaf2840cb0", size = 159490, upload-time = "2026-01-11T11:22:28.399Z" }, + { url = "https://files.pythonhosted.org/packages/e3/5a/fc3622c8b1ad823e8ea98a35e3c632ee316d48f66f80f9708ceb4f2a0322/tomli-2.4.0-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0f2e3955efea4d1cfbcb87bc321e00dc08d2bcb737fd1d5e398af111d86db5df", size = 269398, upload-time = "2026-01-11T11:22:29.345Z" }, + { url = "https://files.pythonhosted.org/packages/fd/33/62bd6152c8bdd4c305ad9faca48f51d3acb2df1f8791b1477d46ff86e7f8/tomli-2.4.0-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:0e0fe8a0b8312acf3a88077a0802565cb09ee34107813bba1c7cd591fa6cfc8d", size = 276515, upload-time = "2026-01-11T11:22:30.327Z" }, + { url = "https://files.pythonhosted.org/packages/4b/ff/ae53619499f5235ee4211e62a8d7982ba9e439a0fb4f2f351a93d67c1dd2/tomli-2.4.0-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:413540dce94673591859c4c6f794dfeaa845e98bf35d72ed59636f869ef9f86f", size = 273806, upload-time = "2026-01-11T11:22:32.56Z" }, + { url = "https://files.pythonhosted.org/packages/47/71/cbca7787fa68d4d0a9f7072821980b39fbb1b6faeb5f5cf02f4a5559fa28/tomli-2.4.0-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:0dc56fef0e2c1c470aeac5b6ca8cc7b640bb93e92d9803ddaf9ea03e198f5b0b", size = 281340, upload-time = "2026-01-11T11:22:33.505Z" }, + { url = "https://files.pythonhosted.org/packages/f5/00/d595c120963ad42474cf6ee7771ad0d0e8a49d0f01e29576ee9195d9ecdf/tomli-2.4.0-cp314-cp314t-win32.whl", hash = "sha256:d878f2a6707cc9d53a1be1414bbb419e629c3d6e67f69230217bb663e76b5087", size = 108106, upload-time = "2026-01-11T11:22:34.451Z" }, + { url = "https://files.pythonhosted.org/packages/de/69/9aa0c6a505c2f80e519b43764f8b4ba93b5a0bbd2d9a9de6e2b24271b9a5/tomli-2.4.0-cp314-cp314t-win_amd64.whl", hash = "sha256:2add28aacc7425117ff6364fe9e06a183bb0251b03f986df0e78e974047571fd", size = 120504, upload-time = "2026-01-11T11:22:35.764Z" }, + { url = "https://files.pythonhosted.org/packages/b3/9f/f1668c281c58cfae01482f7114a4b88d345e4c140386241a1a24dcc9e7bc/tomli-2.4.0-cp314-cp314t-win_arm64.whl", hash = "sha256:2b1e3b80e1d5e52e40e9b924ec43d81570f0e7d09d11081b797bc4692765a3d4", size = 99561, upload-time = "2026-01-11T11:22:36.624Z" }, + { url = "https://files.pythonhosted.org/packages/23/d1/136eb2cb77520a31e1f64cbae9d33ec6df0d78bdf4160398e86eec8a8754/tomli-2.4.0-py3-none-any.whl", hash = "sha256:1f776e7d669ebceb01dee46484485f43a4048746235e683bcdffacdf1fb4785a", size = 14477, upload-time = "2026-01-11T11:22:37.446Z" }, ] [[package]] @@ -8821,14 +8828,14 @@ wheels = [ [[package]] name = "types-jsonschema" -version = "4.25.1.20251009" +version = "4.26.0.20260109" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "referencing" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/ef/da/5b901088da5f710690b422137e8ae74197fb1ca471e4aa84dd3ef0d6e295/types_jsonschema-4.25.1.20251009.tar.gz", hash = "sha256:75d0f5c5dd18dc23b664437a0c1a625743e8d2e665ceaf3aecb29841f3a5f97f", size = 15661, upload-time = "2025-10-09T02:54:36.963Z" } +sdist = { url = "https://files.pythonhosted.org/packages/04/03/a1509b0c13fc7a1fca1494c84bde8cce8a5c0582b6255b9640ebd3034017/types_jsonschema-4.26.0.20260109.tar.gz", hash = "sha256:340fe91e6ea517900d6ababb6262a86c176473b5bf8455b96e85a89e3cfb5daa", size = 15886, upload-time = "2026-01-09T03:21:45.464Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/7f/6a/e5146754c0dfc272f176db9c245bc43cc19030262d891a5a85d472797e60/types_jsonschema-4.25.1.20251009-py3-none-any.whl", hash = "sha256:f30b329037b78e7a60146b1146feb0b6fb0b71628637584409bada83968dad3e", size = 15925, upload-time = "2025-10-09T02:54:35.847Z" }, + { url = "https://files.pythonhosted.org/packages/2f/d6/3db3134f35f1e4bf9a13517d759c1ae64086eddb8ad0047caee140021e64/types_jsonschema-4.26.0.20260109-py3-none-any.whl", hash = "sha256:e0276640d228732fb75d883905d607359b24a4ff745ba7f9a5f50e6fda891926", size = 15923, upload-time = "2026-01-09T03:21:43.828Z" }, ] [[package]] @@ -8987,7 +8994,7 @@ wheels = [ [[package]] name = "ultralytics" -version = "8.3.250" +version = "8.3.252" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "matplotlib" }, @@ -9000,14 +9007,14 @@ dependencies = [ { name = "pyyaml" }, { name = "requests" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "torch" }, { name = "torchvision" }, { name = "ultralytics-thop" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/d7/80/b59ee8aac9b46f0cd933a571d10925a7ce9def0d41dc9ddba335143bf520/ultralytics-8.3.250.tar.gz", hash = "sha256:af1a99afbfc23d8c888811bebe7930b0bdc2ae7a2f71ee9f412b77568bfc0297", size = 992533, upload-time = "2026-01-08T18:48:38.45Z" } +sdist = { url = "https://files.pythonhosted.org/packages/d9/6e/77cbcc445edfc51e9e5278f52757625ec57455a4ef163ea698f827521a6c/ultralytics-8.3.252.tar.gz", hash = "sha256:0973d55c84e77bc729d49217da183914401954cb61e8c0ff059082963d88fa73", size = 993056, upload-time = "2026-01-10T16:36:12.307Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/cb/7e/17af4263d4e139a0153bdf60b590ecad079df992545af35ea356a602548a/ultralytics-8.3.250-py3-none-any.whl", hash = "sha256:3578a10095b54b8707c622ad15588140eb5bcf4ff99629cff544faa04b39b7b3", size = 1156491, upload-time = "2026-01-08T18:48:35.335Z" }, + { url = "https://files.pythonhosted.org/packages/57/2c/84f61b8fd8a594c2c3e54560575af2580da17d4647de7bc1ca7c55bf37f6/ultralytics-8.3.252-py3-none-any.whl", hash = "sha256:7b30f8fd5ac03e6bf91a2bf8e27e20814d7e8efad431cd6cd25c7b950c397ccc", size = 1157267, upload-time = "2026-01-10T16:36:07.876Z" }, ] [[package]] @@ -9157,7 +9164,7 @@ wheels = [ [[package]] name = "virtualenv" -version = "20.36.0" +version = "20.36.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "distlib" }, @@ -9165,9 +9172,9 @@ dependencies = [ { name = "platformdirs" }, { name = "typing-extensions", marker = "python_full_version < '3.11'" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/78/49/87e23d8f742f10f965bce5d6b285fc88a4f436b11daf6b6225d4d66f8492/virtualenv-20.36.0.tar.gz", hash = "sha256:a3601f540b515a7983508113f14e78993841adc3d83710fa70f0ac50f43b23ed", size = 6032237, upload-time = "2026-01-07T17:20:04.975Z" } +sdist = { url = "https://files.pythonhosted.org/packages/aa/a3/4d310fa5f00863544e1d0f4de93bddec248499ccf97d4791bc3122c9d4f3/virtualenv-20.36.1.tar.gz", hash = "sha256:8befb5c81842c641f8ee658481e42641c68b5eab3521d8e092d18320902466ba", size = 6032239, upload-time = "2026-01-09T18:21:01.296Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/eb/6a/0af36875e0023a1f2d0b66b4051721fc26740e947696922df1665b75e5d3/virtualenv-20.36.0-py3-none-any.whl", hash = "sha256:e7ded577f3af534fd0886d4ca03277f5542053bedb98a70a989d3c22cfa5c9ac", size = 6008261, upload-time = "2026-01-07T17:20:02.87Z" }, + { url = "https://files.pythonhosted.org/packages/6a/2a/dc2228b2888f51192c7dc766106cd475f1b768c10caaf9727659726f7391/virtualenv-20.36.1-py3-none-any.whl", hash = "sha256:575a8d6b124ef88f6f51d56d656132389f961062a9177016a50e4f507bbcc19f", size = 6008258, upload-time = "2026-01-09T18:20:59.425Z" }, ] [[package]] @@ -9359,61 +9366,70 @@ wheels = [ [[package]] name = "websockets" -version = "15.0.1" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/21/e6/26d09fab466b7ca9c7737474c52be4f76a40301b08362eb2dbc19dcc16c1/websockets-15.0.1.tar.gz", hash = "sha256:82544de02076bafba038ce055ee6412d68da13ab47f0c60cab827346de828dee", size = 177016, upload-time = "2025-03-05T20:03:41.606Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/1e/da/6462a9f510c0c49837bbc9345aca92d767a56c1fb2939e1579df1e1cdcf7/websockets-15.0.1-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:d63efaa0cd96cf0c5fe4d581521d9fa87744540d4bc999ae6e08595a1014b45b", size = 175423, upload-time = "2025-03-05T20:01:35.363Z" }, - { url = "https://files.pythonhosted.org/packages/1c/9f/9d11c1a4eb046a9e106483b9ff69bce7ac880443f00e5ce64261b47b07e7/websockets-15.0.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:ac60e3b188ec7574cb761b08d50fcedf9d77f1530352db4eef1707fe9dee7205", size = 173080, upload-time = "2025-03-05T20:01:37.304Z" }, - { url = "https://files.pythonhosted.org/packages/d5/4f/b462242432d93ea45f297b6179c7333dd0402b855a912a04e7fc61c0d71f/websockets-15.0.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:5756779642579d902eed757b21b0164cd6fe338506a8083eb58af5c372e39d9a", size = 173329, upload-time = "2025-03-05T20:01:39.668Z" }, - { url = "https://files.pythonhosted.org/packages/6e/0c/6afa1f4644d7ed50284ac59cc70ef8abd44ccf7d45850d989ea7310538d0/websockets-15.0.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0fdfe3e2a29e4db3659dbd5bbf04560cea53dd9610273917799f1cde46aa725e", size = 182312, upload-time = "2025-03-05T20:01:41.815Z" }, - { url = "https://files.pythonhosted.org/packages/dd/d4/ffc8bd1350b229ca7a4db2a3e1c482cf87cea1baccd0ef3e72bc720caeec/websockets-15.0.1-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:4c2529b320eb9e35af0fa3016c187dffb84a3ecc572bcee7c3ce302bfeba52bf", size = 181319, upload-time = "2025-03-05T20:01:43.967Z" }, - { url = "https://files.pythonhosted.org/packages/97/3a/5323a6bb94917af13bbb34009fac01e55c51dfde354f63692bf2533ffbc2/websockets-15.0.1-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ac1e5c9054fe23226fb11e05a6e630837f074174c4c2f0fe442996112a6de4fb", size = 181631, upload-time = "2025-03-05T20:01:46.104Z" }, - { url = "https://files.pythonhosted.org/packages/a6/cc/1aeb0f7cee59ef065724041bb7ed667b6ab1eeffe5141696cccec2687b66/websockets-15.0.1-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:5df592cd503496351d6dc14f7cdad49f268d8e618f80dce0cd5a36b93c3fc08d", size = 182016, upload-time = "2025-03-05T20:01:47.603Z" }, - { url = "https://files.pythonhosted.org/packages/79/f9/c86f8f7af208e4161a7f7e02774e9d0a81c632ae76db2ff22549e1718a51/websockets-15.0.1-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:0a34631031a8f05657e8e90903e656959234f3a04552259458aac0b0f9ae6fd9", size = 181426, upload-time = "2025-03-05T20:01:48.949Z" }, - { url = "https://files.pythonhosted.org/packages/c7/b9/828b0bc6753db905b91df6ae477c0b14a141090df64fb17f8a9d7e3516cf/websockets-15.0.1-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:3d00075aa65772e7ce9e990cab3ff1de702aa09be3940d1dc88d5abf1ab8a09c", size = 181360, upload-time = "2025-03-05T20:01:50.938Z" }, - { url = "https://files.pythonhosted.org/packages/89/fb/250f5533ec468ba6327055b7d98b9df056fb1ce623b8b6aaafb30b55d02e/websockets-15.0.1-cp310-cp310-win32.whl", hash = "sha256:1234d4ef35db82f5446dca8e35a7da7964d02c127b095e172e54397fb6a6c256", size = 176388, upload-time = "2025-03-05T20:01:52.213Z" }, - { url = "https://files.pythonhosted.org/packages/1c/46/aca7082012768bb98e5608f01658ff3ac8437e563eca41cf068bd5849a5e/websockets-15.0.1-cp310-cp310-win_amd64.whl", hash = "sha256:39c1fec2c11dc8d89bba6b2bf1556af381611a173ac2b511cf7231622058af41", size = 176830, upload-time = "2025-03-05T20:01:53.922Z" }, - { url = "https://files.pythonhosted.org/packages/9f/32/18fcd5919c293a398db67443acd33fde142f283853076049824fc58e6f75/websockets-15.0.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:823c248b690b2fd9303ba00c4f66cd5e2d8c3ba4aa968b2779be9532a4dad431", size = 175423, upload-time = "2025-03-05T20:01:56.276Z" }, - { url = "https://files.pythonhosted.org/packages/76/70/ba1ad96b07869275ef42e2ce21f07a5b0148936688c2baf7e4a1f60d5058/websockets-15.0.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:678999709e68425ae2593acf2e3ebcbcf2e69885a5ee78f9eb80e6e371f1bf57", size = 173082, upload-time = "2025-03-05T20:01:57.563Z" }, - { url = "https://files.pythonhosted.org/packages/86/f2/10b55821dd40eb696ce4704a87d57774696f9451108cff0d2824c97e0f97/websockets-15.0.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d50fd1ee42388dcfb2b3676132c78116490976f1300da28eb629272d5d93e905", size = 173330, upload-time = "2025-03-05T20:01:59.063Z" }, - { url = "https://files.pythonhosted.org/packages/a5/90/1c37ae8b8a113d3daf1065222b6af61cc44102da95388ac0018fcb7d93d9/websockets-15.0.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d99e5546bf73dbad5bf3547174cd6cb8ba7273062a23808ffea025ecb1cf8562", size = 182878, upload-time = "2025-03-05T20:02:00.305Z" }, - { url = "https://files.pythonhosted.org/packages/8e/8d/96e8e288b2a41dffafb78e8904ea7367ee4f891dafc2ab8d87e2124cb3d3/websockets-15.0.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:66dd88c918e3287efc22409d426c8f729688d89a0c587c88971a0faa2c2f3792", size = 181883, upload-time = "2025-03-05T20:02:03.148Z" }, - { url = "https://files.pythonhosted.org/packages/93/1f/5d6dbf551766308f6f50f8baf8e9860be6182911e8106da7a7f73785f4c4/websockets-15.0.1-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8dd8327c795b3e3f219760fa603dcae1dcc148172290a8ab15158cf85a953413", size = 182252, upload-time = "2025-03-05T20:02:05.29Z" }, - { url = "https://files.pythonhosted.org/packages/d4/78/2d4fed9123e6620cbf1706c0de8a1632e1a28e7774d94346d7de1bba2ca3/websockets-15.0.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:8fdc51055e6ff4adeb88d58a11042ec9a5eae317a0a53d12c062c8a8865909e8", size = 182521, upload-time = "2025-03-05T20:02:07.458Z" }, - { url = "https://files.pythonhosted.org/packages/e7/3b/66d4c1b444dd1a9823c4a81f50231b921bab54eee2f69e70319b4e21f1ca/websockets-15.0.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:693f0192126df6c2327cce3baa7c06f2a117575e32ab2308f7f8216c29d9e2e3", size = 181958, upload-time = "2025-03-05T20:02:09.842Z" }, - { url = "https://files.pythonhosted.org/packages/08/ff/e9eed2ee5fed6f76fdd6032ca5cd38c57ca9661430bb3d5fb2872dc8703c/websockets-15.0.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:54479983bd5fb469c38f2f5c7e3a24f9a4e70594cd68cd1fa6b9340dadaff7cf", size = 181918, upload-time = "2025-03-05T20:02:11.968Z" }, - { url = "https://files.pythonhosted.org/packages/d8/75/994634a49b7e12532be6a42103597b71098fd25900f7437d6055ed39930a/websockets-15.0.1-cp311-cp311-win32.whl", hash = "sha256:16b6c1b3e57799b9d38427dda63edcbe4926352c47cf88588c0be4ace18dac85", size = 176388, upload-time = "2025-03-05T20:02:13.32Z" }, - { url = "https://files.pythonhosted.org/packages/98/93/e36c73f78400a65f5e236cd376713c34182e6663f6889cd45a4a04d8f203/websockets-15.0.1-cp311-cp311-win_amd64.whl", hash = "sha256:27ccee0071a0e75d22cb35849b1db43f2ecd3e161041ac1ee9d2352ddf72f065", size = 176828, upload-time = "2025-03-05T20:02:14.585Z" }, - { url = "https://files.pythonhosted.org/packages/51/6b/4545a0d843594f5d0771e86463606a3988b5a09ca5123136f8a76580dd63/websockets-15.0.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:3e90baa811a5d73f3ca0bcbf32064d663ed81318ab225ee4f427ad4e26e5aff3", size = 175437, upload-time = "2025-03-05T20:02:16.706Z" }, - { url = "https://files.pythonhosted.org/packages/f4/71/809a0f5f6a06522af902e0f2ea2757f71ead94610010cf570ab5c98e99ed/websockets-15.0.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:592f1a9fe869c778694f0aa806ba0374e97648ab57936f092fd9d87f8bc03665", size = 173096, upload-time = "2025-03-05T20:02:18.832Z" }, - { url = "https://files.pythonhosted.org/packages/3d/69/1a681dd6f02180916f116894181eab8b2e25b31e484c5d0eae637ec01f7c/websockets-15.0.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:0701bc3cfcb9164d04a14b149fd74be7347a530ad3bbf15ab2c678a2cd3dd9a2", size = 173332, upload-time = "2025-03-05T20:02:20.187Z" }, - { url = "https://files.pythonhosted.org/packages/a6/02/0073b3952f5bce97eafbb35757f8d0d54812b6174ed8dd952aa08429bcc3/websockets-15.0.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e8b56bdcdb4505c8078cb6c7157d9811a85790f2f2b3632c7d1462ab5783d215", size = 183152, upload-time = "2025-03-05T20:02:22.286Z" }, - { url = "https://files.pythonhosted.org/packages/74/45/c205c8480eafd114b428284840da0b1be9ffd0e4f87338dc95dc6ff961a1/websockets-15.0.1-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:0af68c55afbd5f07986df82831c7bff04846928ea8d1fd7f30052638788bc9b5", size = 182096, upload-time = "2025-03-05T20:02:24.368Z" }, - { url = "https://files.pythonhosted.org/packages/14/8f/aa61f528fba38578ec553c145857a181384c72b98156f858ca5c8e82d9d3/websockets-15.0.1-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:64dee438fed052b52e4f98f76c5790513235efaa1ef7f3f2192c392cd7c91b65", size = 182523, upload-time = "2025-03-05T20:02:25.669Z" }, - { url = "https://files.pythonhosted.org/packages/ec/6d/0267396610add5bc0d0d3e77f546d4cd287200804fe02323797de77dbce9/websockets-15.0.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:d5f6b181bb38171a8ad1d6aa58a67a6aa9d4b38d0f8c5f496b9e42561dfc62fe", size = 182790, upload-time = "2025-03-05T20:02:26.99Z" }, - { url = "https://files.pythonhosted.org/packages/02/05/c68c5adbf679cf610ae2f74a9b871ae84564462955d991178f95a1ddb7dd/websockets-15.0.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:5d54b09eba2bada6011aea5375542a157637b91029687eb4fdb2dab11059c1b4", size = 182165, upload-time = "2025-03-05T20:02:30.291Z" }, - { url = "https://files.pythonhosted.org/packages/29/93/bb672df7b2f5faac89761cb5fa34f5cec45a4026c383a4b5761c6cea5c16/websockets-15.0.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:3be571a8b5afed347da347bfcf27ba12b069d9d7f42cb8c7028b5e98bbb12597", size = 182160, upload-time = "2025-03-05T20:02:31.634Z" }, - { url = "https://files.pythonhosted.org/packages/ff/83/de1f7709376dc3ca9b7eeb4b9a07b4526b14876b6d372a4dc62312bebee0/websockets-15.0.1-cp312-cp312-win32.whl", hash = "sha256:c338ffa0520bdb12fbc527265235639fb76e7bc7faafbb93f6ba80d9c06578a9", size = 176395, upload-time = "2025-03-05T20:02:33.017Z" }, - { url = "https://files.pythonhosted.org/packages/7d/71/abf2ebc3bbfa40f391ce1428c7168fb20582d0ff57019b69ea20fa698043/websockets-15.0.1-cp312-cp312-win_amd64.whl", hash = "sha256:fcd5cf9e305d7b8338754470cf69cf81f420459dbae8a3b40cee57417f4614a7", size = 176841, upload-time = "2025-03-05T20:02:34.498Z" }, - { url = "https://files.pythonhosted.org/packages/cb/9f/51f0cf64471a9d2b4d0fc6c534f323b664e7095640c34562f5182e5a7195/websockets-15.0.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:ee443ef070bb3b6ed74514f5efaa37a252af57c90eb33b956d35c8e9c10a1931", size = 175440, upload-time = "2025-03-05T20:02:36.695Z" }, - { url = "https://files.pythonhosted.org/packages/8a/05/aa116ec9943c718905997412c5989f7ed671bc0188ee2ba89520e8765d7b/websockets-15.0.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:5a939de6b7b4e18ca683218320fc67ea886038265fd1ed30173f5ce3f8e85675", size = 173098, upload-time = "2025-03-05T20:02:37.985Z" }, - { url = "https://files.pythonhosted.org/packages/ff/0b/33cef55ff24f2d92924923c99926dcce78e7bd922d649467f0eda8368923/websockets-15.0.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:746ee8dba912cd6fc889a8147168991d50ed70447bf18bcda7039f7d2e3d9151", size = 173329, upload-time = "2025-03-05T20:02:39.298Z" }, - { url = "https://files.pythonhosted.org/packages/31/1d/063b25dcc01faa8fada1469bdf769de3768b7044eac9d41f734fd7b6ad6d/websockets-15.0.1-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:595b6c3969023ecf9041b2936ac3827e4623bfa3ccf007575f04c5a6aa318c22", size = 183111, upload-time = "2025-03-05T20:02:40.595Z" }, - { url = "https://files.pythonhosted.org/packages/93/53/9a87ee494a51bf63e4ec9241c1ccc4f7c2f45fff85d5bde2ff74fcb68b9e/websockets-15.0.1-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3c714d2fc58b5ca3e285461a4cc0c9a66bd0e24c5da9911e30158286c9b5be7f", size = 182054, upload-time = "2025-03-05T20:02:41.926Z" }, - { url = "https://files.pythonhosted.org/packages/ff/b2/83a6ddf56cdcbad4e3d841fcc55d6ba7d19aeb89c50f24dd7e859ec0805f/websockets-15.0.1-cp313-cp313-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0f3c1e2ab208db911594ae5b4f79addeb3501604a165019dd221c0bdcabe4db8", size = 182496, upload-time = "2025-03-05T20:02:43.304Z" }, - { url = "https://files.pythonhosted.org/packages/98/41/e7038944ed0abf34c45aa4635ba28136f06052e08fc2168520bb8b25149f/websockets-15.0.1-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:229cf1d3ca6c1804400b0a9790dc66528e08a6a1feec0d5040e8b9eb14422375", size = 182829, upload-time = "2025-03-05T20:02:48.812Z" }, - { url = "https://files.pythonhosted.org/packages/e0/17/de15b6158680c7623c6ef0db361da965ab25d813ae54fcfeae2e5b9ef910/websockets-15.0.1-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:756c56e867a90fb00177d530dca4b097dd753cde348448a1012ed6c5131f8b7d", size = 182217, upload-time = "2025-03-05T20:02:50.14Z" }, - { url = "https://files.pythonhosted.org/packages/33/2b/1f168cb6041853eef0362fb9554c3824367c5560cbdaad89ac40f8c2edfc/websockets-15.0.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:558d023b3df0bffe50a04e710bc87742de35060580a293c2a984299ed83bc4e4", size = 182195, upload-time = "2025-03-05T20:02:51.561Z" }, - { url = "https://files.pythonhosted.org/packages/86/eb/20b6cdf273913d0ad05a6a14aed4b9a85591c18a987a3d47f20fa13dcc47/websockets-15.0.1-cp313-cp313-win32.whl", hash = "sha256:ba9e56e8ceeeedb2e080147ba85ffcd5cd0711b89576b83784d8605a7df455fa", size = 176393, upload-time = "2025-03-05T20:02:53.814Z" }, - { url = "https://files.pythonhosted.org/packages/1b/6c/c65773d6cab416a64d191d6ee8a8b1c68a09970ea6909d16965d26bfed1e/websockets-15.0.1-cp313-cp313-win_amd64.whl", hash = "sha256:e09473f095a819042ecb2ab9465aee615bd9c2028e4ef7d933600a8401c79561", size = 176837, upload-time = "2025-03-05T20:02:55.237Z" }, - { url = "https://files.pythonhosted.org/packages/02/9e/d40f779fa16f74d3468357197af8d6ad07e7c5a27ea1ca74ceb38986f77a/websockets-15.0.1-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:0c9e74d766f2818bb95f84c25be4dea09841ac0f734d1966f415e4edfc4ef1c3", size = 173109, upload-time = "2025-03-05T20:03:17.769Z" }, - { url = "https://files.pythonhosted.org/packages/bc/cd/5b887b8585a593073fd92f7c23ecd3985cd2c3175025a91b0d69b0551372/websockets-15.0.1-pp310-pypy310_pp73-macosx_11_0_arm64.whl", hash = "sha256:1009ee0c7739c08a0cd59de430d6de452a55e42d6b522de7aa15e6f67db0b8e1", size = 173343, upload-time = "2025-03-05T20:03:19.094Z" }, - { url = "https://files.pythonhosted.org/packages/fe/ae/d34f7556890341e900a95acf4886833646306269f899d58ad62f588bf410/websockets-15.0.1-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:76d1f20b1c7a2fa82367e04982e708723ba0e7b8d43aa643d3dcd404d74f1475", size = 174599, upload-time = "2025-03-05T20:03:21.1Z" }, - { url = "https://files.pythonhosted.org/packages/71/e6/5fd43993a87db364ec60fc1d608273a1a465c0caba69176dd160e197ce42/websockets-15.0.1-pp310-pypy310_pp73-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f29d80eb9a9263b8d109135351caf568cc3f80b9928bccde535c235de55c22d9", size = 174207, upload-time = "2025-03-05T20:03:23.221Z" }, - { url = "https://files.pythonhosted.org/packages/2b/fb/c492d6daa5ec067c2988ac80c61359ace5c4c674c532985ac5a123436cec/websockets-15.0.1-pp310-pypy310_pp73-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b359ed09954d7c18bbc1680f380c7301f92c60bf924171629c5db97febb12f04", size = 174155, upload-time = "2025-03-05T20:03:25.321Z" }, - { url = "https://files.pythonhosted.org/packages/68/a1/dcb68430b1d00b698ae7a7e0194433bce4f07ded185f0ee5fb21e2a2e91e/websockets-15.0.1-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:cad21560da69f4ce7658ca2cb83138fb4cf695a2ba3e475e0559e05991aa8122", size = 176884, upload-time = "2025-03-05T20:03:27.934Z" }, - { url = "https://files.pythonhosted.org/packages/fa/a8/5b41e0da817d64113292ab1f8247140aac61cbf6cfd085d6a0fa77f4984f/websockets-15.0.1-py3-none-any.whl", hash = "sha256:f7a866fbc1e97b5c617ee4116daaa09b722101d4a3c170c787450ba409f9736f", size = 169743, upload-time = "2025-03-05T20:03:39.41Z" }, +version = "16.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/04/24/4b2031d72e840ce4c1ccb255f693b15c334757fc50023e4db9537080b8c4/websockets-16.0.tar.gz", hash = "sha256:5f6261a5e56e8d5c42a4497b364ea24d94d9563e8fbd44e78ac40879c60179b5", size = 179346, upload-time = "2026-01-10T09:23:47.181Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/20/74/221f58decd852f4b59cc3354cccaf87e8ef695fede361d03dc9a7396573b/websockets-16.0-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:04cdd5d2d1dacbad0a7bf36ccbcd3ccd5a30ee188f2560b7a62a30d14107b31a", size = 177343, upload-time = "2026-01-10T09:22:21.28Z" }, + { url = "https://files.pythonhosted.org/packages/19/0f/22ef6107ee52ab7f0b710d55d36f5a5d3ef19e8a205541a6d7ffa7994e5a/websockets-16.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:8ff32bb86522a9e5e31439a58addbb0166f0204d64066fb955265c4e214160f0", size = 175021, upload-time = "2026-01-10T09:22:22.696Z" }, + { url = "https://files.pythonhosted.org/packages/10/40/904a4cb30d9b61c0e278899bf36342e9b0208eb3c470324a9ecbaac2a30f/websockets-16.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:583b7c42688636f930688d712885cf1531326ee05effd982028212ccc13e5957", size = 175320, upload-time = "2026-01-10T09:22:23.94Z" }, + { url = "https://files.pythonhosted.org/packages/9d/2f/4b3ca7e106bc608744b1cdae041e005e446124bebb037b18799c2d356864/websockets-16.0-cp310-cp310-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:7d837379b647c0c4c2355c2499723f82f1635fd2c26510e1f587d89bc2199e72", size = 183815, upload-time = "2026-01-10T09:22:25.469Z" }, + { url = "https://files.pythonhosted.org/packages/86/26/d40eaa2a46d4302becec8d15b0fc5e45bdde05191e7628405a19cf491ccd/websockets-16.0-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:df57afc692e517a85e65b72e165356ed1df12386ecb879ad5693be08fac65dde", size = 185054, upload-time = "2026-01-10T09:22:27.101Z" }, + { url = "https://files.pythonhosted.org/packages/b0/ba/6500a0efc94f7373ee8fefa8c271acdfd4dca8bd49a90d4be7ccabfc397e/websockets-16.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:2b9f1e0d69bc60a4a87349d50c09a037a2607918746f07de04df9e43252c77a3", size = 184565, upload-time = "2026-01-10T09:22:28.293Z" }, + { url = "https://files.pythonhosted.org/packages/04/b4/96bf2cee7c8d8102389374a2616200574f5f01128d1082f44102140344cc/websockets-16.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:335c23addf3d5e6a8633f9f8eda77efad001671e80b95c491dd0924587ece0b3", size = 183848, upload-time = "2026-01-10T09:22:30.394Z" }, + { url = "https://files.pythonhosted.org/packages/02/8e/81f40fb00fd125357814e8c3025738fc4ffc3da4b6b4a4472a82ba304b41/websockets-16.0-cp310-cp310-win32.whl", hash = "sha256:37b31c1623c6605e4c00d466c9d633f9b812ea430c11c8a278774a1fde1acfa9", size = 178249, upload-time = "2026-01-10T09:22:32.083Z" }, + { url = "https://files.pythonhosted.org/packages/b4/5f/7e40efe8df57db9b91c88a43690ac66f7b7aa73a11aa6a66b927e44f26fa/websockets-16.0-cp310-cp310-win_amd64.whl", hash = "sha256:8e1dab317b6e77424356e11e99a432b7cb2f3ec8c5ab4dabbcee6add48f72b35", size = 178685, upload-time = "2026-01-10T09:22:33.345Z" }, + { url = "https://files.pythonhosted.org/packages/f2/db/de907251b4ff46ae804ad0409809504153b3f30984daf82a1d84a9875830/websockets-16.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:31a52addea25187bde0797a97d6fc3d2f92b6f72a9370792d65a6e84615ac8a8", size = 177340, upload-time = "2026-01-10T09:22:34.539Z" }, + { url = "https://files.pythonhosted.org/packages/f3/fa/abe89019d8d8815c8781e90d697dec52523fb8ebe308bf11664e8de1877e/websockets-16.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:417b28978cdccab24f46400586d128366313e8a96312e4b9362a4af504f3bbad", size = 175022, upload-time = "2026-01-10T09:22:36.332Z" }, + { url = "https://files.pythonhosted.org/packages/58/5d/88ea17ed1ded2079358b40d31d48abe90a73c9e5819dbcde1606e991e2ad/websockets-16.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:af80d74d4edfa3cb9ed973a0a5ba2b2a549371f8a741e0800cb07becdd20f23d", size = 175319, upload-time = "2026-01-10T09:22:37.602Z" }, + { url = "https://files.pythonhosted.org/packages/d2/ae/0ee92b33087a33632f37a635e11e1d99d429d3d323329675a6022312aac2/websockets-16.0-cp311-cp311-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:08d7af67b64d29823fed316505a89b86705f2b7981c07848fb5e3ea3020c1abe", size = 184631, upload-time = "2026-01-10T09:22:38.789Z" }, + { url = "https://files.pythonhosted.org/packages/c8/c5/27178df583b6c5b31b29f526ba2da5e2f864ecc79c99dae630a85d68c304/websockets-16.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:7be95cfb0a4dae143eaed2bcba8ac23f4892d8971311f1b06f3c6b78952ee70b", size = 185870, upload-time = "2026-01-10T09:22:39.893Z" }, + { url = "https://files.pythonhosted.org/packages/87/05/536652aa84ddc1c018dbb7e2c4cbcd0db884580bf8e95aece7593fde526f/websockets-16.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:d6297ce39ce5c2e6feb13c1a996a2ded3b6832155fcfc920265c76f24c7cceb5", size = 185361, upload-time = "2026-01-10T09:22:41.016Z" }, + { url = "https://files.pythonhosted.org/packages/6d/e2/d5332c90da12b1e01f06fb1b85c50cfc489783076547415bf9f0a659ec19/websockets-16.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:1c1b30e4f497b0b354057f3467f56244c603a79c0d1dafce1d16c283c25f6e64", size = 184615, upload-time = "2026-01-10T09:22:42.442Z" }, + { url = "https://files.pythonhosted.org/packages/77/fb/d3f9576691cae9253b51555f841bc6600bf0a983a461c79500ace5a5b364/websockets-16.0-cp311-cp311-win32.whl", hash = "sha256:5f451484aeb5cafee1ccf789b1b66f535409d038c56966d6101740c1614b86c6", size = 178246, upload-time = "2026-01-10T09:22:43.654Z" }, + { url = "https://files.pythonhosted.org/packages/54/67/eaff76b3dbaf18dcddabc3b8c1dba50b483761cccff67793897945b37408/websockets-16.0-cp311-cp311-win_amd64.whl", hash = "sha256:8d7f0659570eefb578dacde98e24fb60af35350193e4f56e11190787bee77dac", size = 178684, upload-time = "2026-01-10T09:22:44.941Z" }, + { url = "https://files.pythonhosted.org/packages/84/7b/bac442e6b96c9d25092695578dda82403c77936104b5682307bd4deb1ad4/websockets-16.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:71c989cbf3254fbd5e84d3bff31e4da39c43f884e64f2551d14bb3c186230f00", size = 177365, upload-time = "2026-01-10T09:22:46.787Z" }, + { url = "https://files.pythonhosted.org/packages/b0/fe/136ccece61bd690d9c1f715baaeefd953bb2360134de73519d5df19d29ca/websockets-16.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:8b6e209ffee39ff1b6d0fa7bfef6de950c60dfb91b8fcead17da4ee539121a79", size = 175038, upload-time = "2026-01-10T09:22:47.999Z" }, + { url = "https://files.pythonhosted.org/packages/40/1e/9771421ac2286eaab95b8575b0cb701ae3663abf8b5e1f64f1fd90d0a673/websockets-16.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:86890e837d61574c92a97496d590968b23c2ef0aeb8a9bc9421d174cd378ae39", size = 175328, upload-time = "2026-01-10T09:22:49.809Z" }, + { url = "https://files.pythonhosted.org/packages/18/29/71729b4671f21e1eaa5d6573031ab810ad2936c8175f03f97f3ff164c802/websockets-16.0-cp312-cp312-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:9b5aca38b67492ef518a8ab76851862488a478602229112c4b0d58d63a7a4d5c", size = 184915, upload-time = "2026-01-10T09:22:51.071Z" }, + { url = "https://files.pythonhosted.org/packages/97/bb/21c36b7dbbafc85d2d480cd65df02a1dc93bf76d97147605a8e27ff9409d/websockets-16.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:e0334872c0a37b606418ac52f6ab9cfd17317ac26365f7f65e203e2d0d0d359f", size = 186152, upload-time = "2026-01-10T09:22:52.224Z" }, + { url = "https://files.pythonhosted.org/packages/4a/34/9bf8df0c0cf88fa7bfe36678dc7b02970c9a7d5e065a3099292db87b1be2/websockets-16.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:a0b31e0b424cc6b5a04b8838bbaec1688834b2383256688cf47eb97412531da1", size = 185583, upload-time = "2026-01-10T09:22:53.443Z" }, + { url = "https://files.pythonhosted.org/packages/47/88/4dd516068e1a3d6ab3c7c183288404cd424a9a02d585efbac226cb61ff2d/websockets-16.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:485c49116d0af10ac698623c513c1cc01c9446c058a4e61e3bf6c19dff7335a2", size = 184880, upload-time = "2026-01-10T09:22:55.033Z" }, + { url = "https://files.pythonhosted.org/packages/91/d6/7d4553ad4bf1c0421e1ebd4b18de5d9098383b5caa1d937b63df8d04b565/websockets-16.0-cp312-cp312-win32.whl", hash = "sha256:eaded469f5e5b7294e2bdca0ab06becb6756ea86894a47806456089298813c89", size = 178261, upload-time = "2026-01-10T09:22:56.251Z" }, + { url = "https://files.pythonhosted.org/packages/c3/f0/f3a17365441ed1c27f850a80b2bc680a0fa9505d733fe152fdf5e98c1c0b/websockets-16.0-cp312-cp312-win_amd64.whl", hash = "sha256:5569417dc80977fc8c2d43a86f78e0a5a22fee17565d78621b6bb264a115d4ea", size = 178693, upload-time = "2026-01-10T09:22:57.478Z" }, + { url = "https://files.pythonhosted.org/packages/cc/9c/baa8456050d1c1b08dd0ec7346026668cbc6f145ab4e314d707bb845bf0d/websockets-16.0-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:878b336ac47938b474c8f982ac2f7266a540adc3fa4ad74ae96fea9823a02cc9", size = 177364, upload-time = "2026-01-10T09:22:59.333Z" }, + { url = "https://files.pythonhosted.org/packages/7e/0c/8811fc53e9bcff68fe7de2bcbe75116a8d959ac699a3200f4847a8925210/websockets-16.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:52a0fec0e6c8d9a784c2c78276a48a2bdf099e4ccc2a4cad53b27718dbfd0230", size = 175039, upload-time = "2026-01-10T09:23:01.171Z" }, + { url = "https://files.pythonhosted.org/packages/aa/82/39a5f910cb99ec0b59e482971238c845af9220d3ab9fa76dd9162cda9d62/websockets-16.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:e6578ed5b6981005df1860a56e3617f14a6c307e6a71b4fff8c48fdc50f3ed2c", size = 175323, upload-time = "2026-01-10T09:23:02.341Z" }, + { url = "https://files.pythonhosted.org/packages/bd/28/0a25ee5342eb5d5f297d992a77e56892ecb65e7854c7898fb7d35e9b33bd/websockets-16.0-cp313-cp313-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:95724e638f0f9c350bb1c2b0a7ad0e83d9cc0c9259f3ea94e40d7b02a2179ae5", size = 184975, upload-time = "2026-01-10T09:23:03.756Z" }, + { url = "https://files.pythonhosted.org/packages/f9/66/27ea52741752f5107c2e41fda05e8395a682a1e11c4e592a809a90c6a506/websockets-16.0-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c0204dc62a89dc9d50d682412c10b3542d748260d743500a85c13cd1ee4bde82", size = 186203, upload-time = "2026-01-10T09:23:05.01Z" }, + { url = "https://files.pythonhosted.org/packages/37/e5/8e32857371406a757816a2b471939d51c463509be73fa538216ea52b792a/websockets-16.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:52ac480f44d32970d66763115edea932f1c5b1312de36df06d6b219f6741eed8", size = 185653, upload-time = "2026-01-10T09:23:06.301Z" }, + { url = "https://files.pythonhosted.org/packages/9b/67/f926bac29882894669368dc73f4da900fcdf47955d0a0185d60103df5737/websockets-16.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:6e5a82b677f8f6f59e8dfc34ec06ca6b5b48bc4fcda346acd093694cc2c24d8f", size = 184920, upload-time = "2026-01-10T09:23:07.492Z" }, + { url = "https://files.pythonhosted.org/packages/3c/a1/3d6ccdcd125b0a42a311bcd15a7f705d688f73b2a22d8cf1c0875d35d34a/websockets-16.0-cp313-cp313-win32.whl", hash = "sha256:abf050a199613f64c886ea10f38b47770a65154dc37181bfaff70c160f45315a", size = 178255, upload-time = "2026-01-10T09:23:09.245Z" }, + { url = "https://files.pythonhosted.org/packages/6b/ae/90366304d7c2ce80f9b826096a9e9048b4bb760e44d3b873bb272cba696b/websockets-16.0-cp313-cp313-win_amd64.whl", hash = "sha256:3425ac5cf448801335d6fdc7ae1eb22072055417a96cc6b31b3861f455fbc156", size = 178689, upload-time = "2026-01-10T09:23:10.483Z" }, + { url = "https://files.pythonhosted.org/packages/f3/1d/e88022630271f5bd349ed82417136281931e558d628dd52c4d8621b4a0b2/websockets-16.0-cp314-cp314-macosx_10_15_universal2.whl", hash = "sha256:8cc451a50f2aee53042ac52d2d053d08bf89bcb31ae799cb4487587661c038a0", size = 177406, upload-time = "2026-01-10T09:23:12.178Z" }, + { url = "https://files.pythonhosted.org/packages/f2/78/e63be1bf0724eeb4616efb1ae1c9044f7c3953b7957799abb5915bffd38e/websockets-16.0-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:daa3b6ff70a9241cf6c7fc9e949d41232d9d7d26fd3522b1ad2b4d62487e9904", size = 175085, upload-time = "2026-01-10T09:23:13.511Z" }, + { url = "https://files.pythonhosted.org/packages/bb/f4/d3c9220d818ee955ae390cf319a7c7a467beceb24f05ee7aaaa2414345ba/websockets-16.0-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:fd3cb4adb94a2a6e2b7c0d8d05cb94e6f1c81a0cf9dc2694fb65c7e8d94c42e4", size = 175328, upload-time = "2026-01-10T09:23:14.727Z" }, + { url = "https://files.pythonhosted.org/packages/63/bc/d3e208028de777087e6fb2b122051a6ff7bbcca0d6df9d9c2bf1dd869ae9/websockets-16.0-cp314-cp314-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:781caf5e8eee67f663126490c2f96f40906594cb86b408a703630f95550a8c3e", size = 185044, upload-time = "2026-01-10T09:23:15.939Z" }, + { url = "https://files.pythonhosted.org/packages/ad/6e/9a0927ac24bd33a0a9af834d89e0abc7cfd8e13bed17a86407a66773cc0e/websockets-16.0-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:caab51a72c51973ca21fa8a18bd8165e1a0183f1ac7066a182ff27107b71e1a4", size = 186279, upload-time = "2026-01-10T09:23:17.148Z" }, + { url = "https://files.pythonhosted.org/packages/b9/ca/bf1c68440d7a868180e11be653c85959502efd3a709323230314fda6e0b3/websockets-16.0-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:19c4dc84098e523fd63711e563077d39e90ec6702aff4b5d9e344a60cb3c0cb1", size = 185711, upload-time = "2026-01-10T09:23:18.372Z" }, + { url = "https://files.pythonhosted.org/packages/c4/f8/fdc34643a989561f217bb477cbc47a3a07212cbda91c0e4389c43c296ebf/websockets-16.0-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:a5e18a238a2b2249c9a9235466b90e96ae4795672598a58772dd806edc7ac6d3", size = 184982, upload-time = "2026-01-10T09:23:19.652Z" }, + { url = "https://files.pythonhosted.org/packages/dd/d1/574fa27e233764dbac9c52730d63fcf2823b16f0856b3329fc6268d6ae4f/websockets-16.0-cp314-cp314-win32.whl", hash = "sha256:a069d734c4a043182729edd3e9f247c3b2a4035415a9172fd0f1b71658a320a8", size = 177915, upload-time = "2026-01-10T09:23:21.458Z" }, + { url = "https://files.pythonhosted.org/packages/8a/f1/ae6b937bf3126b5134ce1f482365fde31a357c784ac51852978768b5eff4/websockets-16.0-cp314-cp314-win_amd64.whl", hash = "sha256:c0ee0e63f23914732c6d7e0cce24915c48f3f1512ec1d079ed01fc629dab269d", size = 178381, upload-time = "2026-01-10T09:23:22.715Z" }, + { url = "https://files.pythonhosted.org/packages/06/9b/f791d1db48403e1f0a27577a6beb37afae94254a8c6f08be4a23e4930bc0/websockets-16.0-cp314-cp314t-macosx_10_15_universal2.whl", hash = "sha256:a35539cacc3febb22b8f4d4a99cc79b104226a756aa7400adc722e83b0d03244", size = 177737, upload-time = "2026-01-10T09:23:24.523Z" }, + { url = "https://files.pythonhosted.org/packages/bd/40/53ad02341fa33b3ce489023f635367a4ac98b73570102ad2cdd770dacc9a/websockets-16.0-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:b784ca5de850f4ce93ec85d3269d24d4c82f22b7212023c974c401d4980ebc5e", size = 175268, upload-time = "2026-01-10T09:23:25.781Z" }, + { url = "https://files.pythonhosted.org/packages/74/9b/6158d4e459b984f949dcbbb0c5d270154c7618e11c01029b9bbd1bb4c4f9/websockets-16.0-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:569d01a4e7fba956c5ae4fc988f0d4e187900f5497ce46339c996dbf24f17641", size = 175486, upload-time = "2026-01-10T09:23:27.033Z" }, + { url = "https://files.pythonhosted.org/packages/e5/2d/7583b30208b639c8090206f95073646c2c9ffd66f44df967981a64f849ad/websockets-16.0-cp314-cp314t-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:50f23cdd8343b984957e4077839841146f67a3d31ab0d00e6b824e74c5b2f6e8", size = 185331, upload-time = "2026-01-10T09:23:28.259Z" }, + { url = "https://files.pythonhosted.org/packages/45/b0/cce3784eb519b7b5ad680d14b9673a31ab8dcb7aad8b64d81709d2430aa8/websockets-16.0-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:152284a83a00c59b759697b7f9e9cddf4e3c7861dd0d964b472b70f78f89e80e", size = 186501, upload-time = "2026-01-10T09:23:29.449Z" }, + { url = "https://files.pythonhosted.org/packages/19/60/b8ebe4c7e89fb5f6cdf080623c9d92789a53636950f7abacfc33fe2b3135/websockets-16.0-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:bc59589ab64b0022385f429b94697348a6a234e8ce22544e3681b2e9331b5944", size = 186062, upload-time = "2026-01-10T09:23:31.368Z" }, + { url = "https://files.pythonhosted.org/packages/88/a8/a080593f89b0138b6cba1b28f8df5673b5506f72879322288b031337c0b8/websockets-16.0-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:32da954ffa2814258030e5a57bc73a3635463238e797c7375dc8091327434206", size = 185356, upload-time = "2026-01-10T09:23:32.627Z" }, + { url = "https://files.pythonhosted.org/packages/c2/b6/b9afed2afadddaf5ebb2afa801abf4b0868f42f8539bfe4b071b5266c9fe/websockets-16.0-cp314-cp314t-win32.whl", hash = "sha256:5a4b4cc550cb665dd8a47f868c8d04c8230f857363ad3c9caf7a0c3bf8c61ca6", size = 178085, upload-time = "2026-01-10T09:23:33.816Z" }, + { url = "https://files.pythonhosted.org/packages/9f/3e/28135a24e384493fa804216b79a6a6759a38cc4ff59118787b9fb693df93/websockets-16.0-cp314-cp314t-win_amd64.whl", hash = "sha256:b14dc141ed6d2dde437cddb216004bcac6a1df0935d79656387bd41632ba0bbd", size = 178531, upload-time = "2026-01-10T09:23:35.016Z" }, + { url = "https://files.pythonhosted.org/packages/72/07/c98a68571dcf256e74f1f816b8cc5eae6eb2d3d5cfa44d37f801619d9166/websockets-16.0-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:349f83cd6c9a415428ee1005cadb5c2c56f4389bc06a9af16103c3bc3dcc8b7d", size = 174947, upload-time = "2026-01-10T09:23:36.166Z" }, + { url = "https://files.pythonhosted.org/packages/7e/52/93e166a81e0305b33fe416338be92ae863563fe7bce446b0f687b9df5aea/websockets-16.0-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:4a1aba3340a8dca8db6eb5a7986157f52eb9e436b74813764241981ca4888f03", size = 175260, upload-time = "2026-01-10T09:23:37.409Z" }, + { url = "https://files.pythonhosted.org/packages/56/0c/2dbf513bafd24889d33de2ff0368190a0e69f37bcfa19009ef819fe4d507/websockets-16.0-pp311-pypy311_pp73-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:f4a32d1bd841d4bcbffdcb3d2ce50c09c3909fbead375ab28d0181af89fd04da", size = 176071, upload-time = "2026-01-10T09:23:39.158Z" }, + { url = "https://files.pythonhosted.org/packages/a5/8f/aea9c71cc92bf9b6cc0f7f70df8f0b420636b6c96ef4feee1e16f80f75dd/websockets-16.0-pp311-pypy311_pp73-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0298d07ee155e2e9fda5be8a9042200dd2e3bb0b8a38482156576f863a9d457c", size = 176968, upload-time = "2026-01-10T09:23:41.031Z" }, + { url = "https://files.pythonhosted.org/packages/9a/3f/f70e03f40ffc9a30d817eef7da1be72ee4956ba8d7255c399a01b135902a/websockets-16.0-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:a653aea902e0324b52f1613332ddf50b00c06fdaf7e92624fbf8c77c78fa5767", size = 178735, upload-time = "2026-01-10T09:23:42.259Z" }, + { url = "https://files.pythonhosted.org/packages/6f/28/258ebab549c2bf3e64d2b0217b973467394a9cea8c42f70418ca2c5d0d2e/websockets-16.0-py3-none-any.whl", hash = "sha256:1637db62fad1dc833276dded54215f2c7fa46912301a24bd94d45d46a011ceec", size = 171598, upload-time = "2026-01-10T09:23:45.395Z" }, ] [[package]] From 90eb589fdc0ce50a186a6fddf20f9b5afc8c7947 Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Mon, 12 Jan 2026 17:44:19 -0800 Subject: [PATCH 10/19] sync uv.lock with dev --- uv.lock | 630 +++++++++++++++++++++++++++----------------------------- 1 file changed, 307 insertions(+), 323 deletions(-) diff --git a/uv.lock b/uv.lock index c0caa2ae66..841b0cccaf 100644 --- a/uv.lock +++ b/uv.lock @@ -186,59 +186,59 @@ wheels = [ [[package]] name = "av" -version = "16.1.0" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/78/cd/3a83ffbc3cc25b39721d174487fb0d51a76582f4a1703f98e46170ce83d4/av-16.1.0.tar.gz", hash = "sha256:a094b4fd87a3721dacf02794d3d2c82b8d712c85b9534437e82a8a978c175ffd", size = 4285203, upload-time = "2026-01-11T07:31:33.772Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/97/51/2217a9249409d2e88e16e3f16f7c0def9fd3e7ffc4238b2ec211f9935bdb/av-16.1.0-cp310-cp310-macosx_11_0_x86_64.whl", hash = "sha256:2395748b0c34fe3a150a1721e4f3d4487b939520991b13e7b36f8926b3b12295", size = 26942590, upload-time = "2026-01-09T20:17:58.588Z" }, - { url = "https://files.pythonhosted.org/packages/bf/cd/a7070f4febc76a327c38808e01e2ff6b94531fe0b321af54ea3915165338/av-16.1.0-cp310-cp310-macosx_14_0_arm64.whl", hash = "sha256:72d7ac832710a158eeb7a93242370aa024a7646516291c562ee7f14a7ea881fd", size = 21507910, upload-time = "2026-01-09T20:18:02.309Z" }, - { url = "https://files.pythonhosted.org/packages/ae/30/ec812418cd9b297f0238fe20eb0747d8a8b68d82c5f73c56fe519a274143/av-16.1.0-cp310-cp310-manylinux_2_28_aarch64.whl", hash = "sha256:6cbac833092e66b6b0ac4d81ab077970b8ca874951e9c3974d41d922aaa653ed", size = 38738309, upload-time = "2026-01-09T20:18:04.701Z" }, - { url = "https://files.pythonhosted.org/packages/3a/b8/6c5795bf1f05f45c5261f8bce6154e0e5e86b158a6676650ddd77c28805e/av-16.1.0-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:eb990672d97c18f99c02f31c8d5750236f770ffe354b5a52c5f4d16c5e65f619", size = 40293006, upload-time = "2026-01-09T20:18:07.238Z" }, - { url = "https://files.pythonhosted.org/packages/a7/44/5e183bcb9333fc3372ee6e683be8b0c9b515a506894b2d32ff465430c074/av-16.1.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:05ad70933ac3b8ef896a820ea64b33b6cca91a5fac5259cb9ba7fa010435be15", size = 40123516, upload-time = "2026-01-09T20:18:09.955Z" }, - { url = "https://files.pythonhosted.org/packages/12/1d/b5346d582a3c3d958b4d26a2cc63ce607233582d956121eb20d2bbe55c2e/av-16.1.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:d831a1062a3c47520bf99de6ec682bd1d64a40dfa958e5457bb613c5270e7ce3", size = 41463289, upload-time = "2026-01-09T20:18:12.459Z" }, - { url = "https://files.pythonhosted.org/packages/fa/31/acc946c0545f72b8d0d74584cb2a0ade9b7dfe2190af3ef9aa52a2e3c0b1/av-16.1.0-cp310-cp310-win_amd64.whl", hash = "sha256:358ab910fef3c5a806c55176f2b27e5663b33c4d0a692dafeb049c6ed71f8aff", size = 31754959, upload-time = "2026-01-09T20:18:14.718Z" }, - { url = "https://files.pythonhosted.org/packages/48/d0/b71b65d1b36520dcb8291a2307d98b7fc12329a45614a303ff92ada4d723/av-16.1.0-cp311-cp311-macosx_11_0_x86_64.whl", hash = "sha256:e88ad64ee9d2b9c4c5d891f16c22ae78e725188b8926eb88187538d9dd0b232f", size = 26927747, upload-time = "2026-01-09T20:18:16.976Z" }, - { url = "https://files.pythonhosted.org/packages/2f/79/720a5a6ccdee06eafa211b945b0a450e3a0b8fc3d12922f0f3c454d870d2/av-16.1.0-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:cb296073fa6935724de72593800ba86ae49ed48af03960a4aee34f8a611f442b", size = 21492232, upload-time = "2026-01-09T20:18:19.266Z" }, - { url = "https://files.pythonhosted.org/packages/8e/4f/a1ba8d922f2f6d1a3d52419463ef26dd6c4d43ee364164a71b424b5ae204/av-16.1.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:720edd4d25aa73723c1532bb0597806d7b9af5ee34fc02358782c358cfe2f879", size = 39291737, upload-time = "2026-01-09T20:18:21.513Z" }, - { url = "https://files.pythonhosted.org/packages/1a/31/fc62b9fe8738d2693e18d99f040b219e26e8df894c10d065f27c6b4f07e3/av-16.1.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:c7f2bc703d0df260a1fdf4de4253c7f5500ca9fc57772ea241b0cb241bcf972e", size = 40846822, upload-time = "2026-01-09T20:18:24.275Z" }, - { url = "https://files.pythonhosted.org/packages/53/10/ab446583dbce730000e8e6beec6ec3c2753e628c7f78f334a35cad0317f4/av-16.1.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:d69c393809babada7d54964d56099e4b30a3e1f8b5736ca5e27bd7be0e0f3c83", size = 40675604, upload-time = "2026-01-09T20:18:26.866Z" }, - { url = "https://files.pythonhosted.org/packages/31/d7/1003be685277005f6d63fd9e64904ee222fe1f7a0ea70af313468bb597db/av-16.1.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:441892be28582356d53f282873c5a951592daaf71642c7f20165e3ddcb0b4c63", size = 42015955, upload-time = "2026-01-09T20:18:29.461Z" }, - { url = "https://files.pythonhosted.org/packages/2f/4a/fa2a38ee9306bf4579f556f94ecbc757520652eb91294d2a99c7cf7623b9/av-16.1.0-cp311-cp311-win_amd64.whl", hash = "sha256:273a3e32de64819e4a1cd96341824299fe06f70c46f2288b5dc4173944f0fd62", size = 31750339, upload-time = "2026-01-09T20:18:32.249Z" }, - { url = "https://files.pythonhosted.org/packages/9c/84/2535f55edcd426cebec02eb37b811b1b0c163f26b8d3f53b059e2ec32665/av-16.1.0-cp312-cp312-macosx_11_0_x86_64.whl", hash = "sha256:640f57b93f927fba8689f6966c956737ee95388a91bd0b8c8b5e0481f73513d6", size = 26945785, upload-time = "2026-01-09T20:18:34.486Z" }, - { url = "https://files.pythonhosted.org/packages/b6/17/ffb940c9e490bf42e86db4db1ff426ee1559cd355a69609ec1efe4d3a9eb/av-16.1.0-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:ae3fb658eec00852ebd7412fdc141f17f3ddce8afee2d2e1cf366263ad2a3b35", size = 21481147, upload-time = "2026-01-09T20:18:36.716Z" }, - { url = "https://files.pythonhosted.org/packages/15/c1/e0d58003d2d83c3921887d5c8c9b8f5f7de9b58dc2194356a2656a45cfdc/av-16.1.0-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:27ee558d9c02a142eebcbe55578a6d817fedfde42ff5676275504e16d07a7f86", size = 39517197, upload-time = "2026-01-11T09:57:31.937Z" }, - { url = "https://files.pythonhosted.org/packages/32/77/787797b43475d1b90626af76f80bfb0c12cfec5e11eafcfc4151b8c80218/av-16.1.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:7ae547f6d5fa31763f73900d43901e8c5fa6367bb9a9840978d57b5a7ae14ed2", size = 41174337, upload-time = "2026-01-11T09:57:35.792Z" }, - { url = "https://files.pythonhosted.org/packages/8e/ac/d90df7f1e3b97fc5554cf45076df5045f1e0a6adf13899e10121229b826c/av-16.1.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:8cf065f9d438e1921dc31fc7aa045790b58aee71736897866420d80b5450f62a", size = 40817720, upload-time = "2026-01-11T09:57:39.039Z" }, - { url = "https://files.pythonhosted.org/packages/80/6f/13c3a35f9dbcebafd03fe0c4cbd075d71ac8968ec849a3cfce406c35a9d2/av-16.1.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:a345877a9d3cc0f08e2bc4ec163ee83176864b92587afb9d08dff50f37a9a829", size = 42267396, upload-time = "2026-01-11T09:57:42.115Z" }, - { url = "https://files.pythonhosted.org/packages/c8/b9/275df9607f7fb44317ccb1d4be74827185c0d410f52b6e2cd770fe209118/av-16.1.0-cp312-cp312-win_amd64.whl", hash = "sha256:f49243b1d27c91cd8c66fdba90a674e344eb8eb917264f36117bf2b6879118fd", size = 31752045, upload-time = "2026-01-11T09:57:45.106Z" }, - { url = "https://files.pythonhosted.org/packages/75/2a/63797a4dde34283dd8054219fcb29294ba1c25d68ba8c8c8a6ae53c62c45/av-16.1.0-cp313-cp313-macosx_11_0_x86_64.whl", hash = "sha256:ce2a1b3d8bf619f6c47a9f28cfa7518ff75ddd516c234a4ee351037b05e6a587", size = 26916715, upload-time = "2026-01-11T09:57:47.682Z" }, - { url = "https://files.pythonhosted.org/packages/d2/c4/0b49cf730d0ae8cda925402f18ae814aef351f5772d14da72dd87ff66448/av-16.1.0-cp313-cp313-macosx_14_0_arm64.whl", hash = "sha256:408dbe6a2573ca58a855eb8cd854112b33ea598651902c36709f5f84c991ed8e", size = 21452167, upload-time = "2026-01-11T09:57:50.606Z" }, - { url = "https://files.pythonhosted.org/packages/51/23/408806503e8d5d840975aad5699b153aaa21eb6de41ade75248a79b7a37f/av-16.1.0-cp313-cp313-manylinux_2_28_aarch64.whl", hash = "sha256:57f657f86652a160a8a01887aaab82282f9e629abf94c780bbdbb01595d6f0f7", size = 39215659, upload-time = "2026-01-11T09:57:53.757Z" }, - { url = "https://files.pythonhosted.org/packages/c4/19/a8528d5bba592b3903f44c28dab9cc653c95fcf7393f382d2751a1d1523e/av-16.1.0-cp313-cp313-manylinux_2_28_x86_64.whl", hash = "sha256:adbad2b355c2ee4552cac59762809d791bda90586d134a33c6f13727fb86cb3a", size = 40874970, upload-time = "2026-01-11T09:57:56.802Z" }, - { url = "https://files.pythonhosted.org/packages/e8/24/2dbcdf0e929ad56b7df078e514e7bd4ca0d45cba798aff3c8caac097d2f7/av-16.1.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:f42e1a68ec2aebd21f7eb6895be69efa6aa27eec1670536876399725bbda4b99", size = 40530345, upload-time = "2026-01-11T09:58:00.421Z" }, - { url = "https://files.pythonhosted.org/packages/54/27/ae91b41207f34e99602d1c72ab6ffd9c51d7c67e3fbcd4e3a6c0e54f882c/av-16.1.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:58fe47aeaef0f100c40ec8a5de9abbd37f118d3ca03829a1009cf288e9aef67c", size = 41972163, upload-time = "2026-01-11T09:58:03.756Z" }, - { url = "https://files.pythonhosted.org/packages/fc/7a/22158fb923b2a9a00dfab0e96ef2e8a1763a94dd89e666a5858412383d46/av-16.1.0-cp313-cp313-win_amd64.whl", hash = "sha256:565093ebc93b2f4b76782589564869dadfa83af5b852edebedd8fee746457d06", size = 31729230, upload-time = "2026-01-11T09:58:07.254Z" }, - { url = "https://files.pythonhosted.org/packages/7f/f1/878f8687d801d6c4565d57ebec08449c46f75126ebca8e0fed6986599627/av-16.1.0-cp313-cp313t-macosx_11_0_x86_64.whl", hash = "sha256:574081a24edb98343fd9f473e21ae155bf61443d4ec9d7708987fa597d6b04b2", size = 27008769, upload-time = "2026-01-11T09:58:10.266Z" }, - { url = "https://files.pythonhosted.org/packages/30/f1/bd4ce8c8b5cbf1d43e27048e436cbc9de628d48ede088a1d0a993768eb86/av-16.1.0-cp313-cp313t-macosx_14_0_arm64.whl", hash = "sha256:9ab00ea29c25ebf2ea1d1e928d7babb3532d562481c5d96c0829212b70756ad0", size = 21590588, upload-time = "2026-01-11T09:58:12.629Z" }, - { url = "https://files.pythonhosted.org/packages/1d/dd/c81f6f9209201ff0b5d5bed6da6c6e641eef52d8fbc930d738c3f4f6f75d/av-16.1.0-cp313-cp313t-manylinux_2_28_aarch64.whl", hash = "sha256:a84a91188c1071f238a9523fd42dbe567fb2e2607b22b779851b2ce0eac1b560", size = 40638029, upload-time = "2026-01-11T09:58:15.399Z" }, - { url = "https://files.pythonhosted.org/packages/15/4d/07edff82b78d0459a6e807e01cd280d3180ce832efc1543de80d77676722/av-16.1.0-cp313-cp313t-manylinux_2_28_x86_64.whl", hash = "sha256:c2cd0de4dd022a7225ff224fde8e7971496d700be41c50adaaa26c07bb50bf97", size = 41970776, upload-time = "2026-01-11T09:58:19.075Z" }, - { url = "https://files.pythonhosted.org/packages/da/9d/1f48b354b82fa135d388477cd1b11b81bdd4384bd6a42a60808e2ec2d66b/av-16.1.0-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:0816143530624a5a93bc5494f8c6eeaf77549b9366709c2ac8566c1e9bff6df5", size = 41764751, upload-time = "2026-01-11T09:58:22.788Z" }, - { url = "https://files.pythonhosted.org/packages/2f/c7/a509801e98db35ec552dd79da7bdbcff7104044bfeb4c7d196c1ce121593/av-16.1.0-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:e3a28053af29644696d0c007e897d19b1197585834660a54773e12a40b16974c", size = 43034355, upload-time = "2026-01-11T09:58:26.125Z" }, - { url = "https://files.pythonhosted.org/packages/36/8b/e5f530d9e8f640da5f5c5f681a424c65f9dd171c871cd255d8a861785a6e/av-16.1.0-cp313-cp313t-win_amd64.whl", hash = "sha256:2e3e67144a202b95ed299d165232533989390a9ea3119d37eccec697dc6dbb0c", size = 31947047, upload-time = "2026-01-11T09:58:31.867Z" }, - { url = "https://files.pythonhosted.org/packages/df/18/8812221108c27d19f7e5f486a82c827923061edf55f906824ee0fcaadf50/av-16.1.0-cp314-cp314-macosx_11_0_x86_64.whl", hash = "sha256:39a634d8e5a87e78ea80772774bfd20c0721f0d633837ff185f36c9d14ffede4", size = 26916179, upload-time = "2026-01-11T09:58:36.506Z" }, - { url = "https://files.pythonhosted.org/packages/38/ef/49d128a9ddce42a2766fe2b6595bd9c49e067ad8937a560f7838a541464e/av-16.1.0-cp314-cp314-macosx_14_0_arm64.whl", hash = "sha256:0ba32fb9e9300948a7fa9f8a3fc686e6f7f77599a665c71eb2118fdfd2c743f9", size = 21460168, upload-time = "2026-01-11T09:58:39.231Z" }, - { url = "https://files.pythonhosted.org/packages/e6/a9/b310d390844656fa74eeb8c2750e98030877c75b97551a23a77d3f982741/av-16.1.0-cp314-cp314-manylinux_2_28_aarch64.whl", hash = "sha256:ca04d17815182d34ce3edc53cbda78a4f36e956c0fd73e3bab249872a831c4d7", size = 39210194, upload-time = "2026-01-11T09:58:42.138Z" }, - { url = "https://files.pythonhosted.org/packages/0c/7b/e65aae179929d0f173af6e474ad1489b5b5ad4c968a62c42758d619e54cf/av-16.1.0-cp314-cp314-manylinux_2_28_x86_64.whl", hash = "sha256:ee0e8de2e124a9ef53c955fe2add6ee7c56cc8fd83318265549e44057db77142", size = 40811675, upload-time = "2026-01-11T09:58:45.871Z" }, - { url = "https://files.pythonhosted.org/packages/54/3f/5d7edefd26b6a5187d6fac0f5065ee286109934f3dea607ef05e53f05b31/av-16.1.0-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:22bf77a2f658827043a1e184b479c3bf25c4c43ab32353677df2d119f080e28f", size = 40543942, upload-time = "2026-01-11T09:58:49.759Z" }, - { url = "https://files.pythonhosted.org/packages/1b/24/f8b17897b67be0900a211142f5646a99d896168f54d57c81f3e018853796/av-16.1.0-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:2dd419d262e6a71cab206d80bbf28e0a10d0f227b671cdf5e854c028faa2d043", size = 41924336, upload-time = "2026-01-11T09:58:53.344Z" }, - { url = "https://files.pythonhosted.org/packages/1c/cf/d32bc6bbbcf60b65f6510c54690ed3ae1c4ca5d9fafbce835b6056858686/av-16.1.0-cp314-cp314-win_amd64.whl", hash = "sha256:53585986fd431cd436f290fba662cfb44d9494fbc2949a183de00acc5b33fa88", size = 31735077, upload-time = "2026-01-11T09:58:56.684Z" }, - { url = "https://files.pythonhosted.org/packages/53/f4/9b63dc70af8636399bd933e9df4f3025a0294609510239782c1b746fc796/av-16.1.0-cp314-cp314t-macosx_11_0_x86_64.whl", hash = "sha256:76f5ed8495cf41e1209a5775d3699dc63fdc1740b94a095e2485f13586593205", size = 27014423, upload-time = "2026-01-11T09:58:59.703Z" }, - { url = "https://files.pythonhosted.org/packages/d1/da/787a07a0d6ed35a0888d7e5cfb8c2ffa202f38b7ad2c657299fac08eb046/av-16.1.0-cp314-cp314t-macosx_14_0_arm64.whl", hash = "sha256:8d55397190f12a1a3ae7538be58c356cceb2bf50df1b33523817587748ce89e5", size = 21595536, upload-time = "2026-01-11T09:59:02.508Z" }, - { url = "https://files.pythonhosted.org/packages/d8/f4/9a7d8651a611be6e7e3ab7b30bb43779899c8cac5f7293b9fb634c44a3f3/av-16.1.0-cp314-cp314t-manylinux_2_28_aarch64.whl", hash = "sha256:9d51d9037437218261b4bbf9df78a95e216f83d7774fbfe8d289230b5b2e28e2", size = 40642490, upload-time = "2026-01-11T09:59:05.842Z" }, - { url = "https://files.pythonhosted.org/packages/6b/e4/eb79bc538a94b4ff93cd4237d00939cba797579f3272490dd0144c165a21/av-16.1.0-cp314-cp314t-manylinux_2_28_x86_64.whl", hash = "sha256:0ce07a89c15644407f49d942111ca046e323bbab0a9078ff43ee57c9b4a50dad", size = 41976905, upload-time = "2026-01-11T09:59:09.169Z" }, - { url = "https://files.pythonhosted.org/packages/5e/f5/f6db0dd86b70167a4d55ee0d9d9640983c570d25504f2bde42599f38241e/av-16.1.0-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:cac0c074892ea97113b53556ff41c99562db7b9f09f098adac1f08318c2acad5", size = 41770481, upload-time = "2026-01-11T09:59:12.74Z" }, - { url = "https://files.pythonhosted.org/packages/9e/8b/33651d658e45e16ab7671ea5fcf3d20980ea7983234f4d8d0c63c65581a5/av-16.1.0-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:7dec3dcbc35a187ce450f65a2e0dda820d5a9e6553eea8344a1459af11c98649", size = 43036824, upload-time = "2026-01-11T09:59:16.507Z" }, - { url = "https://files.pythonhosted.org/packages/83/41/7f13361db54d7e02f11552575c0384dadaf0918138f4eaa82ea03a9f9580/av-16.1.0-cp314-cp314t-win_amd64.whl", hash = "sha256:6f90dc082ff2068ddbe77618400b44d698d25d9c4edac57459e250c16b33d700", size = 31948164, upload-time = "2026-01-11T09:59:19.501Z" }, +version = "16.0.1" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/15/c3/fd72a0315bc6c943ced1105aaac6e0ec1be57c70d8a616bd05acaa21ffee/av-16.0.1.tar.gz", hash = "sha256:dd2ce779fa0b5f5889a6d9e00fbbbc39f58e247e52d31044272648fe16ff1dbf", size = 3904030, upload-time = "2025-10-13T12:28:51.082Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/e8/3c/eefa29b7d0f5afdf7af9197bbecad8ec2ad06bcb5ac7e909c05a624b00a6/av-16.0.1-cp310-cp310-macosx_11_0_x86_64.whl", hash = "sha256:8b141aaa29a3afc96a1d467d106790782c1914628b57309eaadb8c10c299c9c0", size = 27206679, upload-time = "2025-10-13T12:24:41.145Z" }, + { url = "https://files.pythonhosted.org/packages/ac/89/a474feb07d5b94aa5af3771b0fe328056e2e0a840039b329f4fa2a1fd13a/av-16.0.1-cp310-cp310-macosx_14_0_arm64.whl", hash = "sha256:4b8a08a59a5be0082af063d3f4b216e3950340121c6ea95b505a3f5f5cc8f21d", size = 21774556, upload-time = "2025-10-13T12:24:44.332Z" }, + { url = "https://files.pythonhosted.org/packages/be/e5/4361010dcac398bc224823e4b2a47803845e159af9f95164662c523770dc/av-16.0.1-cp310-cp310-manylinux_2_28_aarch64.whl", hash = "sha256:792e7fc3c08eae005ff36486983966476e553cbb55aaeb0ec99adc4909377320", size = 38176763, upload-time = "2025-10-13T12:24:46.98Z" }, + { url = "https://files.pythonhosted.org/packages/d4/db/b27bdd20c9dc80de5b8792dae16dd6f4edf16408c0c7b28070c6228a8057/av-16.0.1-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:4e8ef5df76d8d0ee56139789f80bb90ad1a82a7e6df6e080e2e95c06fa22aea7", size = 39696277, upload-time = "2025-10-13T12:24:50.951Z" }, + { url = "https://files.pythonhosted.org/packages/4e/c8/dd48e6a3ac1e922c141475a0dc30e2b6dfdef9751b3274829889a9281cce/av-16.0.1-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:4f7a6985784a7464f078e419c71f5528c3e550ee5d605e7149b4a37a111eb136", size = 39576660, upload-time = "2025-10-13T12:24:55.773Z" }, + { url = "https://files.pythonhosted.org/packages/b9/f0/223d047e2e60672a2fb5e51e28913de8d52195199f3e949cbfda1e6cd64b/av-16.0.1-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:3f45c8d7b803b6faa2a25a26de5964a0a897de68298d9c9672c7af9d65d8b48a", size = 40752775, upload-time = "2025-10-13T12:25:00.827Z" }, + { url = "https://files.pythonhosted.org/packages/18/73/73acad21c9203bc63d806e8baf42fe705eb5d36dafd1996b71ab5861a933/av-16.0.1-cp310-cp310-win_amd64.whl", hash = "sha256:58e6faf1d9328d8cc6be14c5aadacb7d2965ed6d6ae1af32696993096543ff00", size = 32302328, upload-time = "2025-10-13T12:25:06.042Z" }, + { url = "https://files.pythonhosted.org/packages/49/d3/f2a483c5273fccd556dfa1fce14fab3b5d6d213b46e28e54e254465a2255/av-16.0.1-cp311-cp311-macosx_11_0_x86_64.whl", hash = "sha256:e310d1fb42879df9bad2152a8db6d2ff8bf332c8c36349a09d62cc122f5070fb", size = 27191982, upload-time = "2025-10-13T12:25:10.622Z" }, + { url = "https://files.pythonhosted.org/packages/e0/39/dff28bd252131b3befd09d8587992fe18c09d5125eaefc83a6434d5f56ff/av-16.0.1-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:2f4b357e5615457a84e6b6290916b22864b76b43d5079e1a73bc27581a5b9bac", size = 21760305, upload-time = "2025-10-13T12:25:14.882Z" }, + { url = "https://files.pythonhosted.org/packages/4a/4d/2312d50a09c84a9b4269f7fea5de84f05dd2b7c7113dd961d31fad6c64c4/av-16.0.1-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:286665c77034c3a98080169b8b5586d5568a15da81fbcdaf8099252f2d232d7c", size = 38691616, upload-time = "2025-10-13T12:25:20.063Z" }, + { url = "https://files.pythonhosted.org/packages/15/9a/3d2d30b56252f998e53fced13720e2ce809c4db477110f944034e0fa4c9f/av-16.0.1-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:f88de8e5b8ea29e41af4d8d61df108323d050ccfbc90f15b13ec1f99ce0e841e", size = 40216464, upload-time = "2025-10-13T12:25:24.848Z" }, + { url = "https://files.pythonhosted.org/packages/98/cb/3860054794a47715b4be0006105158c7119a57be58d9e8882b72e4d4e1dd/av-16.0.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:0cdb71ebe4d1b241cf700f8f0c44a7d2a6602b921e16547dd68c0842113736e1", size = 40094077, upload-time = "2025-10-13T12:25:30.238Z" }, + { url = "https://files.pythonhosted.org/packages/41/58/79830fb8af0a89c015250f7864bbd427dff09c70575c97847055f8a302f7/av-16.0.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:28c27a65d40e8cf82b6db2543f8feeb8b56d36c1938f50773494cd3b073c7223", size = 41279948, upload-time = "2025-10-13T12:25:35.24Z" }, + { url = "https://files.pythonhosted.org/packages/83/79/6e1463b04382f379f857113b851cf5f9d580a2f7bd794211cd75352f4e04/av-16.0.1-cp311-cp311-win_amd64.whl", hash = "sha256:ffea39ac7574f234f5168f9b9602e8d4ecdd81853238ec4d661001f03a6d3f64", size = 32297586, upload-time = "2025-10-13T12:25:39.826Z" }, + { url = "https://files.pythonhosted.org/packages/44/78/12a11d7a44fdd8b26a65e2efa1d8a5826733c8887a989a78306ec4785956/av-16.0.1-cp312-cp312-macosx_11_0_x86_64.whl", hash = "sha256:e41a8fef85dfb2c717349f9ff74f92f9560122a9f1a94b1c6c9a8a9c9462ba71", size = 27206375, upload-time = "2025-10-13T12:25:44.423Z" }, + { url = "https://files.pythonhosted.org/packages/27/19/3a4d3882852a0ee136121979ce46f6d2867b974eb217a2c9a070939f55ad/av-16.0.1-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:6352a64b25c9f985d4f279c2902db9a92424e6f2c972161e67119616f0796cb9", size = 21752603, upload-time = "2025-10-13T12:25:49.122Z" }, + { url = "https://files.pythonhosted.org/packages/cb/6e/f7abefba6e008e2f69bebb9a17ba38ce1df240c79b36a5b5fcacf8c8fcfd/av-16.0.1-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:5201f7b4b5ed2128118cb90c2a6d64feedb0586ca7c783176896c78ffb4bbd5c", size = 38931978, upload-time = "2025-10-13T12:25:55.021Z" }, + { url = "https://files.pythonhosted.org/packages/b2/7a/1305243ab47f724fdd99ddef7309a594e669af7f0e655e11bdd2c325dfae/av-16.0.1-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:daecc2072b82b6a942acbdaa9a2e00c05234c61fef976b22713983c020b07992", size = 40549383, upload-time = "2025-10-13T12:26:00.897Z" }, + { url = "https://files.pythonhosted.org/packages/32/b2/357cc063185043eb757b4a48782bff780826103bcad1eb40c3ddfc050b7e/av-16.0.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:6573da96e8bebc3536860a7def108d7dbe1875c86517072431ced702447e6aea", size = 40241993, upload-time = "2025-10-13T12:26:06.993Z" }, + { url = "https://files.pythonhosted.org/packages/20/bb/ced42a4588ba168bf0ef1e9d016982e3ba09fde6992f1dda586fd20dcf71/av-16.0.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:4bc064e48a8de6c087b97dd27cf4ef8c13073f0793108fbce3ecd721201b2502", size = 41532235, upload-time = "2025-10-13T12:26:12.488Z" }, + { url = "https://files.pythonhosted.org/packages/15/37/c7811eca0f318d5fd3212f7e8c3d8335f75a54907c97a89213dc580b8056/av-16.0.1-cp312-cp312-win_amd64.whl", hash = "sha256:0c669b6b6668c8ae74451c15ec6d6d8a36e4c3803dc5d9910f607a174dd18f17", size = 32296912, upload-time = "2025-10-13T12:26:19.187Z" }, + { url = "https://files.pythonhosted.org/packages/86/59/972f199ccc4f8c9e51f59e0f8962a09407396b3f6d11355e2c697ba555f9/av-16.0.1-cp313-cp313-macosx_11_0_x86_64.whl", hash = "sha256:4c61c6c120f5c5d95c711caf54e2c4a9fb2f1e613ac0a9c273d895f6b2602e44", size = 27170433, upload-time = "2025-10-13T12:26:24.673Z" }, + { url = "https://files.pythonhosted.org/packages/53/9d/0514cbc185fb20353ab25da54197fbd169a233e39efcbb26533c36a9dbb9/av-16.0.1-cp313-cp313-macosx_14_0_arm64.whl", hash = "sha256:7ecc2e41320c69095f44aff93470a0d32c30892b2dbad0a08040441c81efa379", size = 21717654, upload-time = "2025-10-13T12:26:29.12Z" }, + { url = "https://files.pythonhosted.org/packages/32/8c/881409dd124b4e07d909d2b70568acb21126fc747656390840a2238651c9/av-16.0.1-cp313-cp313-manylinux_2_28_aarch64.whl", hash = "sha256:036f0554d6faef3f4a94acaeb0cedd388e3ab96eb0eb5a14ec27c17369c466c9", size = 38651601, upload-time = "2025-10-13T12:26:33.919Z" }, + { url = "https://files.pythonhosted.org/packages/35/fd/867ba4cc3ab504442dc89b0c117e6a994fc62782eb634c8f31304586f93e/av-16.0.1-cp313-cp313-manylinux_2_28_x86_64.whl", hash = "sha256:876415470a62e4a3550cc38db2fc0094c25e64eea34d7293b7454125d5958190", size = 40278604, upload-time = "2025-10-13T12:26:39.2Z" }, + { url = "https://files.pythonhosted.org/packages/b3/87/63cde866c0af09a1fa9727b4f40b34d71b0535785f5665c27894306f1fbc/av-16.0.1-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:56902a06bd0828d13f13352874c370670882048267191ff5829534b611ba3956", size = 39984854, upload-time = "2025-10-13T12:26:44.581Z" }, + { url = "https://files.pythonhosted.org/packages/71/3b/8f40a708bff0e6b0f957836e2ef1f4d4429041cf8d99a415a77ead8ac8a3/av-16.0.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:fe988c2bf0fc2d952858f791f18377ea4ae4e19ba3504793799cd6c2a2562edf", size = 41270352, upload-time = "2025-10-13T12:26:50.817Z" }, + { url = "https://files.pythonhosted.org/packages/1e/b5/c114292cb58a7269405ae13b7ba48c7d7bfeebbb2e4e66c8073c065a4430/av-16.0.1-cp313-cp313-win_amd64.whl", hash = "sha256:708a66c248848029bf518f0482b81c5803846f1b597ef8013b19c014470b620f", size = 32273242, upload-time = "2025-10-13T12:26:55.788Z" }, + { url = "https://files.pythonhosted.org/packages/ff/e9/a5b714bc078fdcca8b46c8a0b38484ae5c24cd81d9c1703d3e8ae2b57259/av-16.0.1-cp313-cp313t-macosx_11_0_x86_64.whl", hash = "sha256:79a77ee452537030c21a0b41139bedaf16629636bf764b634e93b99c9d5f4558", size = 27248984, upload-time = "2025-10-13T12:27:00.564Z" }, + { url = "https://files.pythonhosted.org/packages/06/ef/ff777aaf1f88e3f6ce94aca4c5806a0c360e68d48f9d9f0214e42650f740/av-16.0.1-cp313-cp313t-macosx_14_0_arm64.whl", hash = "sha256:080823a6ff712f81e7089ae9756fb1512ca1742a138556a852ce50f58e457213", size = 21828098, upload-time = "2025-10-13T12:27:05.433Z" }, + { url = "https://files.pythonhosted.org/packages/34/d7/a484358d24a42bedde97f61f5d6ee568a7dd866d9df6e33731378db92d9e/av-16.0.1-cp313-cp313t-manylinux_2_28_aarch64.whl", hash = "sha256:04e00124afa8b46a850ed48951ddda61de874407fb8307d6a875bba659d5727e", size = 40051697, upload-time = "2025-10-13T12:27:10.525Z" }, + { url = "https://files.pythonhosted.org/packages/73/87/6772d6080837da5d5c810a98a95bde6977e1f5a6e2e759e8c9292af9ec69/av-16.0.1-cp313-cp313t-manylinux_2_28_x86_64.whl", hash = "sha256:bc098c1c6dc4e7080629a7e9560e67bd4b5654951e17e5ddfd2b1515cfcd37db", size = 41352596, upload-time = "2025-10-13T12:27:16.217Z" }, + { url = "https://files.pythonhosted.org/packages/bd/58/fe448c60cf7f85640a0ed8936f16bac874846aa35e1baa521028949c1ea3/av-16.0.1-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:e6ffd3559a72c46a76aa622630751a821499ba5a780b0047ecc75105d43a6b61", size = 41183156, upload-time = "2025-10-13T12:27:21.574Z" }, + { url = "https://files.pythonhosted.org/packages/85/c6/a039a0979d0c278e1bed6758d5a6186416c3ccb8081970df893fdf9a0d99/av-16.0.1-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:7a3f1a36b550adadd7513f4f5ee956f9e06b01a88e59f3150ef5fec6879d6f79", size = 42302331, upload-time = "2025-10-13T12:27:26.953Z" }, + { url = "https://files.pythonhosted.org/packages/18/7b/2ca4a9e3609ff155436dac384e360f530919cb1e328491f7df294be0f0dc/av-16.0.1-cp313-cp313t-win_amd64.whl", hash = "sha256:c6de794abe52b8c0be55d8bb09ade05905efa74b1a5ab4860b4b9c2bfb6578bf", size = 32462194, upload-time = "2025-10-13T12:27:32.942Z" }, + { url = "https://files.pythonhosted.org/packages/14/9a/6d17e379906cf53a7a44dfac9cf7e4b2e7df2082ba2dbf07126055effcc1/av-16.0.1-cp314-cp314-macosx_11_0_x86_64.whl", hash = "sha256:4b55ba69a943ae592ad7900da67129422954789de9dc384685d6b529925f542e", size = 27167101, upload-time = "2025-10-13T12:27:38.886Z" }, + { url = "https://files.pythonhosted.org/packages/6c/34/891816cd82d5646cb5a51d201d20be0a578232536d083b7d939734258067/av-16.0.1-cp314-cp314-macosx_14_0_arm64.whl", hash = "sha256:d4a0c47b6c9bbadad8909b82847f5fe64a608ad392f0b01704e427349bcd9a47", size = 21722708, upload-time = "2025-10-13T12:27:43.29Z" }, + { url = "https://files.pythonhosted.org/packages/1d/20/c24ad34038423ab8c9728cef3301e0861727c188442dcfd70a4a10834c63/av-16.0.1-cp314-cp314-manylinux_2_28_aarch64.whl", hash = "sha256:8bba52f3035708456f6b1994d10b0371b45cfd8f917b5e84ff81aef4ec2f08bf", size = 38638842, upload-time = "2025-10-13T12:27:49.776Z" }, + { url = "https://files.pythonhosted.org/packages/d7/32/034412309572ba3ad713079d07a3ffc13739263321aece54a3055d7a4f1f/av-16.0.1-cp314-cp314-manylinux_2_28_x86_64.whl", hash = "sha256:08e34c7e7b5e55e29931180bbe21095e1874ac120992bf6b8615d39574487617", size = 40197789, upload-time = "2025-10-13T12:27:55.688Z" }, + { url = "https://files.pythonhosted.org/packages/fb/9c/40496298c32f9094e7df28641c5c58aa6fb07554dc232a9ac98a9894376f/av-16.0.1-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:0d6250ab9db80c641b299987027c987f14935ea837ea4c02c5f5182f6b69d9e5", size = 39980829, upload-time = "2025-10-13T12:28:01.507Z" }, + { url = "https://files.pythonhosted.org/packages/4a/7e/5c38268ac1d424f309b13b2de4597ad28daea6039ee5af061e62918b12a8/av-16.0.1-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:7b621f28d8bcbb07cdcd7b18943ddc040739ad304545715ae733873b6e1b739d", size = 41205928, upload-time = "2025-10-13T12:28:08.431Z" }, + { url = "https://files.pythonhosted.org/packages/e3/07/3176e02692d8753a6c4606021c60e4031341afb56292178eee633b6760a4/av-16.0.1-cp314-cp314-win_amd64.whl", hash = "sha256:92101f49082392580c9dba4ba2fe5b931b3bb0fb75a1a848bfb9a11ded68be91", size = 32272836, upload-time = "2025-10-13T12:28:13.405Z" }, + { url = "https://files.pythonhosted.org/packages/8a/47/10e03b88de097385d1550cbb6d8de96159131705c13adb92bd9b7e677425/av-16.0.1-cp314-cp314t-macosx_11_0_x86_64.whl", hash = "sha256:07c464bf2bc362a154eccc82e235ef64fd3aaf8d76fc8ed63d0ae520943c6d3f", size = 27248864, upload-time = "2025-10-13T12:28:17.467Z" }, + { url = "https://files.pythonhosted.org/packages/b1/60/7447f206bec3e55e81371f1989098baa2fe9adb7b46c149e6937b7e7c1ca/av-16.0.1-cp314-cp314t-macosx_14_0_arm64.whl", hash = "sha256:750da0673864b669c95882c7b25768cd93ece0e47010d74ebcc29dbb14d611f8", size = 21828185, upload-time = "2025-10-13T12:28:21.461Z" }, + { url = "https://files.pythonhosted.org/packages/68/48/ee2680e7a01bc4911bbe902b814346911fa2528697a44f3043ee68e0f07e/av-16.0.1-cp314-cp314t-manylinux_2_28_aarch64.whl", hash = "sha256:0b7c0d060863b2e341d07cd26851cb9057b7979814148b028fb7ee5d5eb8772d", size = 40040572, upload-time = "2025-10-13T12:28:26.585Z" }, + { url = "https://files.pythonhosted.org/packages/da/68/2c43d28871721ae07cde432d6e36ae2f7035197cbadb43764cc5bf3d4b33/av-16.0.1-cp314-cp314t-manylinux_2_28_x86_64.whl", hash = "sha256:e67c2eca6023ca7d76b0709c5f392b23a5defba499f4c262411f8155b1482cbd", size = 41344288, upload-time = "2025-10-13T12:28:32.512Z" }, + { url = "https://files.pythonhosted.org/packages/ec/7f/1d801bff43ae1af4758c45eee2eaae64f303bbb460e79f352f08587fd179/av-16.0.1-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:e3243d54d84986e8fbdc1946db634b0c41fe69b6de35a99fa8b763e18503d040", size = 41175142, upload-time = "2025-10-13T12:28:38.356Z" }, + { url = "https://files.pythonhosted.org/packages/e4/06/bb363138687066bbf8997c1433dbd9c81762bae120955ea431fb72d69d26/av-16.0.1-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:a1bcf73efab5379601e6510abd7afe5f397d0f6defe69b1610c2f37a4a17996b", size = 42293932, upload-time = "2025-10-13T12:28:43.442Z" }, + { url = "https://files.pythonhosted.org/packages/92/15/5e713098a085f970ccf88550194d277d244464d7b3a7365ad92acb4b6dc1/av-16.0.1-cp314-cp314t-win_amd64.whl", hash = "sha256:6368d4ff153d75469d2a3217bc403630dc870a72fe0a014d9135de550d731a86", size = 32460624, upload-time = "2025-10-13T12:28:48.767Z" }, ] [[package]] @@ -424,7 +424,7 @@ dependencies = [ { name = "orbax-checkpoint" }, { name = "pillow" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "tensorboardx" }, { name = "trimesh" }, { name = "typing-extensions" }, @@ -1397,7 +1397,7 @@ dependencies = [ { name = "reactivex" }, { name = "rerun-sdk" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "sortedcontainers" }, { name = "structlog" }, { name = "terminaltexteffects" }, @@ -2074,11 +2074,11 @@ wheels = [ [[package]] name = "filelock" -version = "3.20.3" +version = "3.20.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/1d/65/ce7f1b70157833bf3cb851b556a37d4547ceafc158aa9b34b36782f23696/filelock-3.20.3.tar.gz", hash = "sha256:18c57ee915c7ec61cff0ecf7f0f869936c7c30191bb0cf406f1341778d0834e1", size = 19485, upload-time = "2026-01-09T17:55:05.421Z" } +sdist = { url = "https://files.pythonhosted.org/packages/c1/e0/a75dbe4bca1e7d41307323dad5ea2efdd95408f74ab2de8bd7dba9b51a1a/filelock-3.20.2.tar.gz", hash = "sha256:a2241ff4ddde2a7cebddf78e39832509cb045d18ec1a09d7248d6bfc6bfbbe64", size = 19510, upload-time = "2026-01-02T15:33:32.582Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/b5/36/7fb70f04bf00bc646cd5bb45aa9eddb15e19437a28b8fb2b4a5249fac770/filelock-3.20.3-py3-none-any.whl", hash = "sha256:4b0dda527ee31078689fc205ec4f1c1bf7d56cf88b6dc9426c4f230e46c2dce1", size = 16701, upload-time = "2026-01-09T17:55:04.334Z" }, + { url = "https://files.pythonhosted.org/packages/9a/30/ab407e2ec752aa541704ed8f93c11e2a5d92c168b8a755d818b74a3c5c2d/filelock-3.20.2-py3-none-any.whl", hash = "sha256:fbba7237d6ea277175a32c54bb71ef814a8546d8601269e1bfc388de333974e8", size = 16697, upload-time = "2026-01-02T15:33:31.133Z" }, ] [[package]] @@ -2090,7 +2090,7 @@ dependencies = [ { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/f6/1d/ac8914360460fafa1990890259b7fa5ef7ba4cd59014e782e4ab3ab144d8/filterpy-1.4.5.zip", hash = "sha256:4f2a4d39e4ea601b9ab42b2db08b5918a9538c168cff1c6895ae26646f3d73b1", size = 177985, upload-time = "2018-10-10T22:38:24.63Z" } @@ -2291,11 +2291,11 @@ wheels = [ [[package]] name = "fsspec" -version = "2026.1.0" +version = "2025.12.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/d5/7d/5df2650c57d47c57232af5ef4b4fdbff182070421e405e0d62c6cdbfaa87/fsspec-2026.1.0.tar.gz", hash = "sha256:e987cb0496a0d81bba3a9d1cee62922fb395e7d4c3b575e57f547953334fe07b", size = 310496, upload-time = "2026-01-09T15:21:35.562Z" } +sdist = { url = "https://files.pythonhosted.org/packages/b6/27/954057b0d1f53f086f681755207dda6de6c660ce133c829158e8e8fe7895/fsspec-2025.12.0.tar.gz", hash = "sha256:c505de011584597b1060ff778bb664c1bc022e87921b0e4f10cc9c44f9635973", size = 309748, upload-time = "2025-12-03T15:23:42.687Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/01/c9/97cc5aae1648dcb851958a3ddf73ccd7dbe5650d95203ecb4d7720b4cdbf/fsspec-2026.1.0-py3-none-any.whl", hash = "sha256:cb76aa913c2285a3b49bdd5fc55b1d7c708d7208126b60f2eb8194fe1b4cbdcc", size = 201838, upload-time = "2026-01-09T15:21:34.041Z" }, + { url = "https://files.pythonhosted.org/packages/51/c7/b64cae5dba3a1b138d7123ec36bb5ccd39d39939f18454407e5468f4763f/fsspec-2025.12.0-py3-none-any.whl", hash = "sha256:8bf1fe301b7d8acfa6e8571e3b1c3d158f909666642431cc78a1b7b4dbc5ec5b", size = 201422, upload-time = "2025-12-03T15:23:41.434Z" }, ] [[package]] @@ -2691,11 +2691,11 @@ wheels = [ [[package]] name = "identify" -version = "2.6.16" +version = "2.6.15" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/5b/8d/e8b97e6bd3fb6fb271346f7981362f1e04d6a7463abd0de79e1fda17c067/identify-2.6.16.tar.gz", hash = "sha256:846857203b5511bbe94d5a352a48ef2359532bc8f6727b5544077a0dcfb24980", size = 99360, upload-time = "2026-01-12T18:58:58.201Z" } +sdist = { url = "https://files.pythonhosted.org/packages/ff/e7/685de97986c916a6d93b3876139e00eef26ad5bbbd61925d670ae8013449/identify-2.6.15.tar.gz", hash = "sha256:e4f4864b96c6557ef2a1e1c951771838f4edc9df3a72ec7118b338801b11c7bf", size = 99311, upload-time = "2025-10-02T17:43:40.631Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/b8/58/40fbbcefeda82364720eba5cf2270f98496bdfa19ea75b4cccae79c698e6/identify-2.6.16-py2.py3-none-any.whl", hash = "sha256:391ee4d77741d994189522896270b787aed8670389bfd60f326d677d64a6dfb0", size = 99202, upload-time = "2026-01-12T18:58:56.627Z" }, + { url = "https://files.pythonhosted.org/packages/0f/1c/e5fd8f973d4f375adb21565739498e2e9a1e54c858a97b9a8ccfdc81da9b/identify-2.6.15-py2.py3-none-any.whl", hash = "sha256:1181ef7608e00704db228516541eb83a88a9f94433a8c80bb9b5bd54b1d81757", size = 99183, upload-time = "2025-10-02T17:43:39.137Z" }, ] [[package]] @@ -2915,7 +2915,7 @@ dependencies = [ { name = "ml-dtypes", marker = "python_full_version >= '3.11'" }, { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "opt-einsum", marker = "python_full_version >= '3.11'" }, - { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/e6/25/5efb46e5492076622d9150ed394da97ef9aad393aa52f7dd7e980f836e1f/jax-0.8.2.tar.gz", hash = "sha256:1a685ded06a8223a7b52e45e668e406049dbbead02873f2b5a4d881ba7b421ae", size = 2505776, upload-time = "2025-12-18T18:41:59.274Z" } wheels = [ @@ -2979,7 +2979,7 @@ resolution-markers = [ dependencies = [ { name = "ml-dtypes", marker = "python_full_version >= '3.11'" }, { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, - { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/5f/87/0a44b1a5c558e6d8e4fd796d4f9efe5c8cac2b3013ab7349968c65931fa4/jaxlib-0.8.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:490bf0cb029c73c65c9431124b86cdc95082dbc1fb76fc549d24d75da33e5454", size = 55929353, upload-time = "2025-12-18T18:40:35.844Z" }, @@ -3018,7 +3018,7 @@ dependencies = [ { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/3a/da/ff7d7fbd13b8ed5e8458e80308d075fc649062b9f8676d3fc56f2dc99a82/jaxopt-0.8.5.tar.gz", hash = "sha256:2790bd68ef132b216c083a8bc7a2704eceb35a92c0fc0a1e652e79dfb1e9e9ab", size = 121709, upload-time = "2025-04-14T17:59:01.618Z" } wheels = [ @@ -3409,7 +3409,7 @@ wheels = [ [[package]] name = "langchain-core" -version = "1.2.7" +version = "1.2.6" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "jsonpatch" }, @@ -3421,9 +3421,9 @@ dependencies = [ { name = "typing-extensions" }, { name = "uuid-utils" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/a2/0e/664d8d81b3493e09cbab72448d2f9d693d1fa5aa2bcc488602203a9b6da0/langchain_core-1.2.7.tar.gz", hash = "sha256:e1460639f96c352b4a41c375f25aeb8d16ffc1769499fb1c20503aad59305ced", size = 837039, upload-time = "2026-01-09T17:44:25.505Z" } +sdist = { url = "https://files.pythonhosted.org/packages/b9/ce/ba5ed5ea6df22965b2893c2ed28ebb456204962723d408904c4acfa5e942/langchain_core-1.2.6.tar.gz", hash = "sha256:b4e7841dd7f8690375aa07c54739178dc2c635147d475e0c2955bf82a1afa498", size = 833343, upload-time = "2026-01-02T21:35:44.749Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/6e/6f/34a9fba14d191a67f7e2ee3dbce3e9b86d2fa7310e2c7f2c713583481bd2/langchain_core-1.2.7-py3-none-any.whl", hash = "sha256:452f4fef7a3d883357b22600788d37e3d8854ef29da345b7ac7099f33c31828b", size = 490232, upload-time = "2026-01-09T17:44:24.236Z" }, + { url = "https://files.pythonhosted.org/packages/6f/40/0655892c245d8fbe6bca6d673ab5927e5c3ab7be143de40b52289a0663bc/langchain_core-1.2.6-py3-none-any.whl", hash = "sha256:aa6ed954b4b1f4504937fe75fdf674317027e9a91ba7a97558b0de3dc8004e34", size = 489096, upload-time = "2026-01-02T21:35:43.391Z" }, ] [[package]] @@ -3481,7 +3481,7 @@ wheels = [ [[package]] name = "langgraph" -version = "1.0.6" +version = "1.0.5" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "langchain-core" }, @@ -3491,48 +3491,48 @@ dependencies = [ { name = "pydantic" }, { name = "xxhash" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/c2/9c/dac99ab1732e9fb2d3b673482ac28f02bee222c0319a3b8f8f73d90727e6/langgraph-1.0.6.tar.gz", hash = "sha256:dd8e754c76d34a07485308d7117221acf63990e7de8f46ddf5fe256b0a22e6c5", size = 495092, upload-time = "2026-01-12T20:33:30.778Z" } +sdist = { url = "https://files.pythonhosted.org/packages/7d/47/28f4d4d33d88f69de26f7a54065961ac0c662cec2479b36a2db081ef5cb6/langgraph-1.0.5.tar.gz", hash = "sha256:7f6ae59622386b60fe9fa0ad4c53f42016b668455ed604329e7dc7904adbf3f8", size = 493969, upload-time = "2025-12-12T23:05:48.224Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/10/45/9960747781416bed4e531ed0c6b2f2c739bc7b5397d8e92155463735a40e/langgraph-1.0.6-py3-none-any.whl", hash = "sha256:bcfce190974519c72e29f6e5b17f0023914fd6f936bfab8894083215b271eb89", size = 157356, upload-time = "2026-01-12T20:33:29.191Z" }, + { url = "https://files.pythonhosted.org/packages/23/1b/e318ee76e42d28f515d87356ac5bd7a7acc8bad3b8f54ee377bef62e1cbf/langgraph-1.0.5-py3-none-any.whl", hash = "sha256:b4cfd173dca3c389735b47228ad8b295e6f7b3df779aba3a1e0c23871f81281e", size = 157056, upload-time = "2025-12-12T23:05:46.499Z" }, ] [[package]] name = "langgraph-checkpoint" -version = "4.0.0" +version = "3.0.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "langchain-core" }, { name = "ormsgpack" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/98/76/55a18c59dedf39688d72c4b06af73a5e3ea0d1a01bc867b88fbf0659f203/langgraph_checkpoint-4.0.0.tar.gz", hash = "sha256:814d1bd050fac029476558d8e68d87bce9009a0262d04a2c14b918255954a624", size = 137320, upload-time = "2026-01-12T20:30:26.38Z" } +sdist = { url = "https://files.pythonhosted.org/packages/0f/07/2b1c042fa87d40cf2db5ca27dc4e8dd86f9a0436a10aa4361a8982718ae7/langgraph_checkpoint-3.0.1.tar.gz", hash = "sha256:59222f875f85186a22c494aedc65c4e985a3df27e696e5016ba0b98a5ed2cee0", size = 137785, upload-time = "2025-11-04T21:55:47.774Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/4a/de/ddd53b7032e623f3c7bcdab2b44e8bf635e468f62e10e5ff1946f62c9356/langgraph_checkpoint-4.0.0-py3-none-any.whl", hash = "sha256:3fa9b2635a7c5ac28b338f631abf6a030c3b508b7b9ce17c22611513b589c784", size = 46329, upload-time = "2026-01-12T20:30:25.2Z" }, + { url = "https://files.pythonhosted.org/packages/48/e3/616e3a7ff737d98c1bbb5700dd62278914e2a9ded09a79a1fa93cf24ce12/langgraph_checkpoint-3.0.1-py3-none-any.whl", hash = "sha256:9b04a8d0edc0474ce4eaf30c5d731cee38f11ddff50a6177eead95b5c4e4220b", size = 46249, upload-time = "2025-11-04T21:55:46.472Z" }, ] [[package]] name = "langgraph-prebuilt" -version = "1.0.6" +version = "1.0.5" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "langchain-core" }, { name = "langgraph-checkpoint" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/3c/f5/8c75dace0d729561dce2966e630c5e312193df7e5df41a7e10cd7378c3a7/langgraph_prebuilt-1.0.6.tar.gz", hash = "sha256:c5f6cf0f5a0ac47643d2e26ae6faa38cb28885ecde67911190df9e30c4f72361", size = 162623, upload-time = "2026-01-12T20:31:28.425Z" } +sdist = { url = "https://files.pythonhosted.org/packages/46/f9/54f8891b32159e4542236817aea2ee83de0de18bce28e9bdba08c7f93001/langgraph_prebuilt-1.0.5.tar.gz", hash = "sha256:85802675ad778cc7240fd02d47db1e0b59c0c86d8369447d77ce47623845db2d", size = 144453, upload-time = "2025-11-20T16:47:39.23Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/26/6c/4045822b0630cfc0f8624c4499ceaf90644142143c063a8dc385a7424fc3/langgraph_prebuilt-1.0.6-py3-none-any.whl", hash = "sha256:9fdc35048ff4ac985a55bd2a019a86d45b8184551504aff6780d096c678b39ae", size = 35322, upload-time = "2026-01-12T20:31:27.161Z" }, + { url = "https://files.pythonhosted.org/packages/87/5e/aeba4a5b39fe6e874e0dd003a82da71c7153e671312671a8dacc5cb7c1af/langgraph_prebuilt-1.0.5-py3-none-any.whl", hash = "sha256:22369563e1848862ace53fbc11b027c28dd04a9ac39314633bb95f2a7e258496", size = 35072, upload-time = "2025-11-20T16:47:38.187Z" }, ] [[package]] name = "langgraph-sdk" -version = "0.3.3" +version = "0.3.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "httpx" }, { name = "orjson" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/c3/0f/ed0634c222eed48a31ba48eab6881f94ad690d65e44fe7ca838240a260c1/langgraph_sdk-0.3.3.tar.gz", hash = "sha256:c34c3dce3b6848755eb61f0c94369d1ba04aceeb1b76015db1ea7362c544fb26", size = 130589, upload-time = "2026-01-13T00:30:43.894Z" } +sdist = { url = "https://files.pythonhosted.org/packages/a9/d3/b6be0b0aba2a53a8920a2b0b4328a83121ec03eea9952e576d06a4182f6f/langgraph_sdk-0.3.1.tar.gz", hash = "sha256:f6dadfd2444eeff3e01405a9005c95fb3a028d4bd954ebec80ea6150084f92bb", size = 130312, upload-time = "2025-12-18T22:11:47.42Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/6e/be/4ad511bacfdd854afb12974f407cb30010dceb982dc20c55491867b34526/langgraph_sdk-0.3.3-py3-none-any.whl", hash = "sha256:a52ebaf09d91143e55378bb2d0b033ed98f57f48c9ad35c8f81493b88705fc7b", size = 67021, upload-time = "2026-01-13T00:30:42.264Z" }, + { url = "https://files.pythonhosted.org/packages/ab/fe/0c1c9c01a154eba62b20b02fabe811fd94a2b810061ae9e4d8462b8cf85a/langgraph_sdk-0.3.1-py3-none-any.whl", hash = "sha256:0b856923bfd20bf3441ce9d03bef488aa333fb610e972618799a9d584436acad", size = 66517, upload-time = "2025-12-18T22:11:46.625Z" }, ] [[package]] @@ -4597,7 +4597,7 @@ dependencies = [ { name = "jaxlib", version = "0.8.2", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "mujoco" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "trimesh" }, ] sdist = { url = "https://files.pythonhosted.org/packages/cb/57/2cebcde17bdad9c575c71a301ea1524eb9dba76a974e24f07abf714050be/mujoco_mjx-3.4.0.tar.gz", hash = "sha256:10fa51a92c22affd27c9205c5fb965c14c256729ab58fd2021dc9e4df9bedec6", size = 6872370, upload-time = "2025-12-05T23:14:13.734Z" } @@ -5212,7 +5212,7 @@ wheels = [ [[package]] name = "onnx" -version = "1.20.1" +version = "1.20.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "ml-dtypes" }, @@ -5221,30 +5221,30 @@ dependencies = [ { name = "protobuf" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/3b/8a/335c03a8683a88a32f9a6bb98899ea6df241a41df64b37b9696772414794/onnx-1.20.1.tar.gz", hash = "sha256:ded16de1df563d51fbc1ad885f2a426f814039d8b5f4feb77febe09c0295ad67", size = 12048980, upload-time = "2026-01-10T01:40:03.043Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/79/cc/4ba3c80cfaffdb541dc5a23eaccb045a627361e94ecaeba30496270f15b3/onnx-1.20.1-cp310-cp310-macosx_12_0_universal2.whl", hash = "sha256:3fe243e83ad737637af6512708454e720d4b0864def2b28e6b0ee587b80a50be", size = 17904206, upload-time = "2026-01-10T01:38:58.574Z" }, - { url = "https://files.pythonhosted.org/packages/f3/fc/3a1c4ae2cd5cfab2d0ebc1842769b04b417fe13946144a7c8ce470dd9c85/onnx-1.20.1-cp310-cp310-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:e24e96b48f27e4d6b44cb0b195b367a2665da2d819621eec51903d575fc49d38", size = 17414849, upload-time = "2026-01-10T01:39:01.494Z" }, - { url = "https://files.pythonhosted.org/packages/a4/ab/5017945291b981f2681fb620f2d5b6070e02170c648770711ef1eac79d56/onnx-1.20.1-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:0903e6088ed5e8f59ebd381ab2a6e9b2a60b4c898f79aa2fe76bb79cf38a5031", size = 17513600, upload-time = "2026-01-10T01:39:04.348Z" }, - { url = "https://files.pythonhosted.org/packages/2e/b0/063e79dc365972af876d786bacc6acd8909691af2b9296615ff74ad182f3/onnx-1.20.1-cp310-cp310-win32.whl", hash = "sha256:17483e59082b2ca6cadd2b48fd8dce937e5b2c985ed5583fefc38af928be1826", size = 16239159, upload-time = "2026-01-10T01:39:07.254Z" }, - { url = "https://files.pythonhosted.org/packages/2a/73/a992271eb3683e676239d71b5a78ad3cf4d06d2223c387e701bf305da199/onnx-1.20.1-cp310-cp310-win_amd64.whl", hash = "sha256:e2b0cf797faedfd3b83491dc168ab5f1542511448c65ceb482f20f04420cbf3a", size = 16391718, upload-time = "2026-01-10T01:39:09.96Z" }, - { url = "https://files.pythonhosted.org/packages/0c/38/1a0e74d586c08833404100f5c052f92732fb5be417c0b2d7cb0838443bfe/onnx-1.20.1-cp311-cp311-macosx_12_0_universal2.whl", hash = "sha256:53426e1b458641e7a537e9f176330012ff59d90206cac1c1a9d03cdd73ed3095", size = 17904965, upload-time = "2026-01-10T01:39:13.532Z" }, - { url = "https://files.pythonhosted.org/packages/96/25/64b076e9684d17335f80b15b3bf502f7a8e1a89f08a6b208d4f2861b3011/onnx-1.20.1-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:ca7281f8c576adf396c338cf43fff26faee8d4d2e2577b8e73738f37ceccf945", size = 17415179, upload-time = "2026-01-10T01:39:16.516Z" }, - { url = "https://files.pythonhosted.org/packages/ac/d5/6743b409421ced20ad5af1b3a7b4c4e568689ffaca86db431692fca409a6/onnx-1.20.1-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:2297f428c51c7fc6d8fad0cf34384284dfeff3f86799f8e83ef905451348ade0", size = 17513672, upload-time = "2026-01-10T01:39:19.35Z" }, - { url = "https://files.pythonhosted.org/packages/9a/6b/dae82e6fdb2043302f29adca37522312ea2be55b75907b59be06fbdffe87/onnx-1.20.1-cp311-cp311-win32.whl", hash = "sha256:63d9cbcab8c96841eadeb7c930e07bfab4dde8081eb76fb68e0dfb222706b81e", size = 16239336, upload-time = "2026-01-10T01:39:22.506Z" }, - { url = "https://files.pythonhosted.org/packages/8e/17/a0d7863390c1f2067d7c02dcc1477034965c32aaa1407bfcf775305ffee4/onnx-1.20.1-cp311-cp311-win_amd64.whl", hash = "sha256:d78cde72d7ca8356a2d99c5dc0dbf67264254828cae2c5780184486c0cd7b3bf", size = 16392120, upload-time = "2026-01-10T01:39:25.106Z" }, - { url = "https://files.pythonhosted.org/packages/aa/72/9b879a46eb7a3322223791f36bf9c25d95da9ed93779eabb75a560f22e5b/onnx-1.20.1-cp311-cp311-win_arm64.whl", hash = "sha256:0104bb2d4394c179bcea3df7599a45a2932b80f4633840896fcf0d7d8daecea2", size = 16346923, upload-time = "2026-01-10T01:39:27.782Z" }, - { url = "https://files.pythonhosted.org/packages/7c/4c/4b17e82f91ab9aa07ff595771e935ca73547b035030dc5f5a76e63fbfea9/onnx-1.20.1-cp312-abi3-macosx_12_0_universal2.whl", hash = "sha256:1d923bb4f0ce1b24c6859222a7e6b2f123e7bfe7623683662805f2e7b9e95af2", size = 17903547, upload-time = "2026-01-10T01:39:31.015Z" }, - { url = "https://files.pythonhosted.org/packages/64/5e/1bfa100a9cb3f2d3d5f2f05f52f7e60323b0e20bb0abace1ae64dbc88f25/onnx-1.20.1-cp312-abi3-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:ddc0b7d8b5a94627dc86c533d5e415af94cbfd103019a582669dad1f56d30281", size = 17412021, upload-time = "2026-01-10T01:39:33.885Z" }, - { url = "https://files.pythonhosted.org/packages/fb/71/d3fec0dcf9a7a99e7368112d9c765154e81da70fcba1e3121131a45c245b/onnx-1.20.1-cp312-abi3-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9336b6b8e6efcf5c490a845f6afd7e041c89a56199aeda384ed7d58fb953b080", size = 17510450, upload-time = "2026-01-10T01:39:36.589Z" }, - { url = "https://files.pythonhosted.org/packages/74/a7/edce1403e05a46e59b502fae8e3350ceeac5841f8e8f1561e98562ed9b09/onnx-1.20.1-cp312-abi3-win32.whl", hash = "sha256:564c35a94811979808ab5800d9eb4f3f32c12daedba7e33ed0845f7c61ef2431", size = 16238216, upload-time = "2026-01-10T01:39:39.46Z" }, - { url = "https://files.pythonhosted.org/packages/8b/c7/8690c81200ae652ac550c1df52f89d7795e6cc941f3cb38c9ef821419e80/onnx-1.20.1-cp312-abi3-win_amd64.whl", hash = "sha256:9fe7f9a633979d50984b94bda8ceb7807403f59a341d09d19342dc544d0ca1d5", size = 16389207, upload-time = "2026-01-10T01:39:41.955Z" }, - { url = "https://files.pythonhosted.org/packages/01/a0/4fb0e6d36eaf079af366b2c1f68bafe92df6db963e2295da84388af64abc/onnx-1.20.1-cp312-abi3-win_arm64.whl", hash = "sha256:21d747348b1c8207406fa2f3e12b82f53e0d5bb3958bcd0288bd27d3cb6ebb00", size = 16344155, upload-time = "2026-01-10T01:39:45.536Z" }, - { url = "https://files.pythonhosted.org/packages/ea/bb/715fad292b255664f0e603f1b2ef7bf2b386281775f37406beb99fa05957/onnx-1.20.1-cp313-cp313t-macosx_12_0_universal2.whl", hash = "sha256:29197b768f5acdd1568ddeb0a376407a2817844f6ac1ef8c8dd2d974c9ab27c3", size = 17912296, upload-time = "2026-01-10T01:39:48.21Z" }, - { url = "https://files.pythonhosted.org/packages/2d/c3/541af12c3d45e159a94ee701100ba9e94b7bd8b7a8ac5ca6838569f894f8/onnx-1.20.1-cp313-cp313t-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:1f0371aa67f51917a09cc829ada0f9a79a58f833449e03d748f7f7f53787c43c", size = 17416925, upload-time = "2026-01-10T01:39:50.82Z" }, - { url = "https://files.pythonhosted.org/packages/2c/3b/d5660a7d2ddf14f531ca66d409239f543bb290277c3f14f4b4b78e32efa3/onnx-1.20.1-cp313-cp313t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:be1e5522200b203b34327b2cf132ddec20ab063469476e1f5b02bb7bd259a489", size = 17515602, upload-time = "2026-01-10T01:39:54.132Z" }, - { url = "https://files.pythonhosted.org/packages/9c/b4/47225ab2a92562eff87ba9a1a028e3535d659a7157d7cde659003998b8e3/onnx-1.20.1-cp313-cp313t-win_amd64.whl", hash = "sha256:15c815313bbc4b2fdc7e4daeb6e26b6012012adc4d850f4e3b09ed327a7ea92a", size = 16395729, upload-time = "2026-01-10T01:39:57.577Z" }, - { url = "https://files.pythonhosted.org/packages/aa/7d/1bbe626ff6b192c844d3ad34356840cc60fca02e2dea0db95e01645758b1/onnx-1.20.1-cp313-cp313t-win_arm64.whl", hash = "sha256:eb335d7bcf9abac82a0d6a0fda0363531ae0b22cfd0fc6304bff32ee29905def", size = 16348968, upload-time = "2026-01-10T01:40:00.491Z" }, +sdist = { url = "https://files.pythonhosted.org/packages/bd/bf/824b13b7ea14c2d374b48a296cfa412442e5559326fbab5441a4fcb68924/onnx-1.20.0.tar.gz", hash = "sha256:1a93ec69996b4556062d552ed1aa0671978cfd3c17a40bf4c89a1ae169c6a4ad", size = 12049527, upload-time = "2025-12-01T18:14:34.679Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/23/18/8fd768f715a990d3b5786c9bffa6f158934cc1935f2774dd15b26c62f99f/onnx-1.20.0-cp310-cp310-macosx_12_0_universal2.whl", hash = "sha256:7e706470f8b731af6d0347c4f01b8e0e1810855d0c71c467066a5bd7fa21704b", size = 18341375, upload-time = "2025-12-01T18:13:29.481Z" }, + { url = "https://files.pythonhosted.org/packages/cf/47/9fdb6e8bde5f77f8bdcf7e584ad88ffa7a189338b92658351518c192bde0/onnx-1.20.0-cp310-cp310-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:3e941d0f3edd57e1d63e2562c74aec2803ead5b965e76ccc3d2b2bd4ae0ea054", size = 17899075, upload-time = "2025-12-01T18:13:32.375Z" }, + { url = "https://files.pythonhosted.org/packages/b2/17/7bb16372f95a8a8251c202018952a747ac7f796a9e6d5720ed7b36680834/onnx-1.20.0-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6930ed7795912c4298ec8642b33c99c51c026a57edf17788b8451fe22d11e674", size = 18118826, upload-time = "2025-12-01T18:13:35.077Z" }, + { url = "https://files.pythonhosted.org/packages/19/d8/19e3f599601195b1d8ff0bf9e9469065ebeefd9b5e5ec090344f031c38cb/onnx-1.20.0-cp310-cp310-win32.whl", hash = "sha256:f8424c95491de38ecc280f7d467b298cb0b7cdeb1cd892eb9b4b9541c00a600e", size = 16364286, upload-time = "2025-12-01T18:13:38.304Z" }, + { url = "https://files.pythonhosted.org/packages/5d/f9/11d2db50a6c56092bd2e22515fe6998309c7b2389ed67f8ffd27285c33b5/onnx-1.20.0-cp310-cp310-win_amd64.whl", hash = "sha256:1ecca1f963d69e002c03000f15844f8cac3b6d7b6639a934e73571ee02d59c35", size = 16487791, upload-time = "2025-12-01T18:13:41.062Z" }, + { url = "https://files.pythonhosted.org/packages/9e/9a/125ad5ed919d1782b26b0b4404e51adc44afd029be30d5a81b446dccd9c5/onnx-1.20.0-cp311-cp311-macosx_12_0_universal2.whl", hash = "sha256:00dc8ae2c7b283f79623961f450b5515bd2c4b47a7027e7a1374ba49cef27768", size = 18341929, upload-time = "2025-12-01T18:13:43.79Z" }, + { url = "https://files.pythonhosted.org/packages/4d/3c/85280dd05396493f3e1b4feb7a3426715e344b36083229437f31d9788a01/onnx-1.20.0-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f62978ecfb8f320faba6704abd20253a5a79aacc4e5d39a9c061dd63d3b7574f", size = 17899362, upload-time = "2025-12-01T18:13:46.496Z" }, + { url = "https://files.pythonhosted.org/packages/26/db/e11cf9aaa6ccbcd27ea94d321020fef3207cba388bff96111e6431f97d1a/onnx-1.20.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:71177f8fd5c0dd90697bc281f5035f73707bdac83257a5c54d74403a1100ace9", size = 18119129, upload-time = "2025-12-01T18:13:49.662Z" }, + { url = "https://files.pythonhosted.org/packages/ef/0b/1b99e7ba5ccfa8ecb3509ec579c8520098d09b903ccd520026d60faa7c75/onnx-1.20.0-cp311-cp311-win32.whl", hash = "sha256:1d3d0308e2c194f4b782f51e78461b567fac8ce6871c0cf5452ede261683cc8f", size = 16364604, upload-time = "2025-12-01T18:13:52.691Z" }, + { url = "https://files.pythonhosted.org/packages/51/ab/7399817821d0d18ff67292ac183383e41f4f4ddff2047902f1b7b51d2d40/onnx-1.20.0-cp311-cp311-win_amd64.whl", hash = "sha256:3a6de7dda77926c323b0e5a830dc9c2866ce350c1901229e193be1003a076c25", size = 16488019, upload-time = "2025-12-01T18:13:55.776Z" }, + { url = "https://files.pythonhosted.org/packages/fd/e0/23059c11d9c0fb1951acec504a5cc86e1dd03d2eef3a98cf1941839f5322/onnx-1.20.0-cp311-cp311-win_arm64.whl", hash = "sha256:afc4cf83ce5d547ebfbb276dae8eb0ec836254a8698d462b4ba5f51e717fd1ae", size = 16446841, upload-time = "2025-12-01T18:13:58.091Z" }, + { url = "https://files.pythonhosted.org/packages/5e/19/2caa972a31014a8cb4525f715f2a75d93caef9d4b9da2809cc05d0489e43/onnx-1.20.0-cp312-abi3-macosx_12_0_universal2.whl", hash = "sha256:31efe37d7d1d659091f34ddd6a31780334acf7c624176832db9a0a8ececa8fb5", size = 18340913, upload-time = "2025-12-01T18:14:00.477Z" }, + { url = "https://files.pythonhosted.org/packages/78/bb/b98732309f2f6beb4cdcf7b955d7bbfd75a191185370ee21233373db381e/onnx-1.20.0-cp312-abi3-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:d75da05e743eb9a11ff155a775cae5745e71f1cd0ca26402881b8f20e8d6e449", size = 17896118, upload-time = "2025-12-01T18:14:03.239Z" }, + { url = "https://files.pythonhosted.org/packages/84/a7/38aa564871d062c11538d65c575af9c7e057be880c09ecbd899dd1abfa83/onnx-1.20.0-cp312-abi3-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:02e0d72ab09a983fce46686b155a5049898558d9f3bc6e8515120d6c40666318", size = 18115415, upload-time = "2025-12-01T18:14:06.261Z" }, + { url = "https://files.pythonhosted.org/packages/3b/17/a600b62cf4ad72976c66f83ce9e324205af434706ad5ec0e35129e125aef/onnx-1.20.0-cp312-abi3-win32.whl", hash = "sha256:392ca68b34b97e172d33b507e1e7bfdf2eea96603e6e7ff109895b82ff009dc7", size = 16363019, upload-time = "2025-12-01T18:14:09.16Z" }, + { url = "https://files.pythonhosted.org/packages/9c/3b/5146ba0a89f73c026bb468c49612bab8d005aa28155ebf06cf5f2eb8d36c/onnx-1.20.0-cp312-abi3-win_amd64.whl", hash = "sha256:259b05758d41645f5545c09f887187662b350d40db8d707c33c94a4f398e1733", size = 16485934, upload-time = "2025-12-01T18:14:13.046Z" }, + { url = "https://files.pythonhosted.org/packages/f3/bc/d251b97395e721b3034e9578d4d4d9fb33aac4197ae16ce8c7ed79a26dce/onnx-1.20.0-cp312-abi3-win_arm64.whl", hash = "sha256:2d25a9e1fde44bc69988e50e2211f62d6afcd01b0fd6dfd23429fd978a35d32f", size = 16444946, upload-time = "2025-12-01T18:14:15.801Z" }, + { url = "https://files.pythonhosted.org/packages/8d/11/4d47409e257013951a17d08c31988e7c2e8638c91d4d5ce18cc57c6ea9d9/onnx-1.20.0-cp313-cp313t-macosx_12_0_universal2.whl", hash = "sha256:7646e700c0a53770a86d5a9a582999a625a3173c4323635960aec3cba8441c6a", size = 18348524, upload-time = "2025-12-01T18:14:18.102Z" }, + { url = "https://files.pythonhosted.org/packages/67/60/774d29a0f00f84a4ec624fe35e0c59e1dbd7f424adaab751977a45b60e05/onnx-1.20.0-cp313-cp313t-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:d0bdfd22fe92b87bf98424335ec1191ed79b08cd0f57fe396fab558b83b2c868", size = 17900987, upload-time = "2025-12-01T18:14:20.835Z" }, + { url = "https://files.pythonhosted.org/packages/9c/7c/6bd82b81b85b2680e3de8cf7b6cc49a7380674b121265bb6e1e2ff3bb0aa/onnx-1.20.0-cp313-cp313t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9d1a4e02148b2a7a4b82796d0ecdb6e49ba7abd34bb5a9de22af86aad556fb76", size = 18121332, upload-time = "2025-12-01T18:14:24.558Z" }, + { url = "https://files.pythonhosted.org/packages/d1/42/d2cd00c84def4e17b471e24d82a1d2e3c5be202e2c163420b0353ddf34df/onnx-1.20.0-cp313-cp313t-win_amd64.whl", hash = "sha256:2241c85fdaa25a66565fcd1d327c7bcd8f55165420ebaee1e9563c3b9bf961c9", size = 16492660, upload-time = "2025-12-01T18:14:27.456Z" }, + { url = "https://files.pythonhosted.org/packages/42/cd/1106de50a17f2a2dfbb4c8bb3cf2f99be2c7ac2e19abbbf9e07ab47b1b35/onnx-1.20.0-cp313-cp313t-win_arm64.whl", hash = "sha256:ee46cdc5abd851a007a4be81ee53e0e303cf9a0e46d74231d5d361333a1c9411", size = 16448588, upload-time = "2025-12-01T18:14:32.277Z" }, ] [[package]] @@ -5365,7 +5365,7 @@ wheels = [ [[package]] name = "openai" -version = "2.15.0" +version = "2.14.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "anyio" }, @@ -5377,9 +5377,9 @@ dependencies = [ { name = "tqdm" }, { name = "typing-extensions" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/94/f4/4690ecb5d70023ce6bfcfeabfe717020f654bde59a775058ec6ac4692463/openai-2.15.0.tar.gz", hash = "sha256:42eb8cbb407d84770633f31bf727d4ffb4138711c670565a41663d9439174fba", size = 627383, upload-time = "2026-01-09T22:10:08.603Z" } +sdist = { url = "https://files.pythonhosted.org/packages/d8/b1/12fe1c196bea326261718eb037307c1c1fe1dedc2d2d4de777df822e6238/openai-2.14.0.tar.gz", hash = "sha256:419357bedde9402d23bf8f2ee372fca1985a73348debba94bddff06f19459952", size = 626938, upload-time = "2025-12-19T03:28:45.742Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/b5/df/c306f7375d42bafb379934c2df4c2fa3964656c8c782bac75ee10c102818/openai-2.15.0-py3-none-any.whl", hash = "sha256:6ae23b932cd7230f7244e52954daa6602716d6b9bf235401a107af731baea6c3", size = 1067879, upload-time = "2026-01-09T22:10:06.446Z" }, + { url = "https://files.pythonhosted.org/packages/27/4b/7c1a00c2c3fbd004253937f7520f692a9650767aa73894d7a34f0d65d3f4/openai-2.14.0-py3-none-any.whl", hash = "sha256:7ea40aca4ffc4c4a776e77679021b47eec1160e341f42ae086ba949c9dcc9183", size = 1067558, upload-time = "2025-12-19T03:28:43.727Z" }, ] [[package]] @@ -5999,30 +5999,28 @@ wheels = [ [[package]] name = "polars" -version = "1.37.1" +version = "1.36.1" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "polars-runtime-32" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/84/ae/dfebf31b9988c20998140b54d5b521f64ce08879f2c13d9b4d44d7c87e32/polars-1.37.1.tar.gz", hash = "sha256:0309e2a4633e712513401964b4d95452f124ceabf7aec6db50affb9ced4a274e", size = 715572, upload-time = "2026-01-12T23:27:03.267Z" } +sdist = { url = "https://files.pythonhosted.org/packages/9f/dc/56f2a90c79a2cb13f9e956eab6385effe54216ae7a2068b3a6406bae4345/polars-1.36.1.tar.gz", hash = "sha256:12c7616a2305559144711ab73eaa18814f7aa898c522e7645014b68f1432d54c", size = 711993, upload-time = "2025-12-10T01:14:53.033Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/08/75/ec73e38812bca7c2240aff481b9ddff20d1ad2f10dee4b3353f5eeaacdab/polars-1.37.1-py3-none-any.whl", hash = "sha256:377fed8939a2f1223c1563cfabdc7b4a3d6ff846efa1f2ddeb8644fafd9b1aff", size = 805749, upload-time = "2026-01-12T23:25:48.595Z" }, + { url = "https://files.pythonhosted.org/packages/f6/c6/36a1b874036b49893ecae0ac44a2f63d1a76e6212631a5b2f50a86e0e8af/polars-1.36.1-py3-none-any.whl", hash = "sha256:853c1bbb237add6a5f6d133c15094a9b727d66dd6a4eb91dbb07cdb056b2b8ef", size = 802429, upload-time = "2025-12-10T01:13:53.838Z" }, ] [[package]] name = "polars-runtime-32" -version = "1.37.1" +version = "1.36.1" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/40/0b/addabe5e8d28a5a4c9887a08907be7ddc3fce892dc38f37d14b055438a57/polars_runtime_32-1.37.1.tar.gz", hash = "sha256:68779d4a691da20a5eb767d74165a8f80a2bdfbde4b54acf59af43f7fa028d8f", size = 2818945, upload-time = "2026-01-12T23:27:04.653Z" } +sdist = { url = "https://files.pythonhosted.org/packages/31/df/597c0ef5eb8d761a16d72327846599b57c5d40d7f9e74306fc154aba8c37/polars_runtime_32-1.36.1.tar.gz", hash = "sha256:201c2cfd80ceb5d5cd7b63085b5fd08d6ae6554f922bcb941035e39638528a09", size = 2788751, upload-time = "2025-12-10T01:14:54.172Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/2a/a2/e828ea9f845796de02d923edb790e408ca0b560cd68dbd74bb99a1b3c461/polars_runtime_32-1.37.1-cp310-abi3-macosx_10_12_x86_64.whl", hash = "sha256:0b8d4d73ea9977d3731927740e59d814647c5198bdbe359bcf6a8bfce2e79771", size = 43499912, upload-time = "2026-01-12T23:25:51.182Z" }, - { url = "https://files.pythonhosted.org/packages/7e/46/81b71b7aa9e3703ee6e4ef1f69a87e40f58ea7c99212bf49a95071e99c8c/polars_runtime_32-1.37.1-cp310-abi3-macosx_11_0_arm64.whl", hash = "sha256:c682bf83f5f352e5e02f5c16c652c48ca40442f07b236f30662b22217320ce76", size = 39695707, upload-time = "2026-01-12T23:25:54.289Z" }, - { url = "https://files.pythonhosted.org/packages/81/2e/20009d1fde7ee919e24040f5c87cb9d0e4f8e3f109b74ba06bc10c02459c/polars_runtime_32-1.37.1-cp310-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:fc82b5bbe70ca1a4b764eed1419f6336752d6ba9fc1245388d7f8b12438afa2c", size = 41467034, upload-time = "2026-01-12T23:25:56.925Z" }, - { url = "https://files.pythonhosted.org/packages/eb/21/9b55bea940524324625b1e8fd96233290303eb1bf2c23b54573487bbbc25/polars_runtime_32-1.37.1-cp310-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a8362d11ac5193b994c7e9048ffe22ccfb976699cfbf6e128ce0302e06728894", size = 45142711, upload-time = "2026-01-12T23:26:00.817Z" }, - { url = "https://files.pythonhosted.org/packages/8c/25/c5f64461aeccdac6834a89f826d051ccd3b4ce204075e562c87a06ed2619/polars_runtime_32-1.37.1-cp310-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:04f5d5a2f013dca7391b7d8e7672fa6d37573a87f1d45d3dd5f0d9b5565a4b0f", size = 41638564, upload-time = "2026-01-12T23:26:04.186Z" }, - { url = "https://files.pythonhosted.org/packages/35/af/509d3cf6c45e764ccf856beaae26fc34352f16f10f94a7839b1042920a73/polars_runtime_32-1.37.1-cp310-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:fbfde7c0ca8209eeaed546e4a32cca1319189aa61c5f0f9a2b4494262bd0c689", size = 44721136, upload-time = "2026-01-12T23:26:07.088Z" }, - { url = "https://files.pythonhosted.org/packages/af/d1/5c0a83a625f72beef59394bebc57d12637997632a4f9d3ab2ffc2cc62bbf/polars_runtime_32-1.37.1-cp310-abi3-win_amd64.whl", hash = "sha256:da3d3642ae944e18dd17109d2a3036cb94ce50e5495c5023c77b1599d4c861bc", size = 44948288, upload-time = "2026-01-12T23:26:10.214Z" }, - { url = "https://files.pythonhosted.org/packages/10/f3/061bb702465904b6502f7c9081daee34b09ccbaa4f8c94cf43a2a3b6dd6f/polars_runtime_32-1.37.1-cp310-abi3-win_arm64.whl", hash = "sha256:55f2c4847a8d2e267612f564de7b753a4bde3902eaabe7b436a0a4abf75949a0", size = 41001914, upload-time = "2026-01-12T23:26:12.997Z" }, + { url = "https://files.pythonhosted.org/packages/e1/ea/871129a2d296966c0925b078a9a93c6c5e7facb1c5eebfcd3d5811aeddc1/polars_runtime_32-1.36.1-cp39-abi3-macosx_10_12_x86_64.whl", hash = "sha256:327b621ca82594f277751f7e23d4b939ebd1be18d54b4cdf7a2f8406cecc18b2", size = 43494311, upload-time = "2025-12-10T01:13:56.096Z" }, + { url = "https://files.pythonhosted.org/packages/d8/76/0038210ad1e526ce5bb2933b13760d6b986b3045eccc1338e661bd656f77/polars_runtime_32-1.36.1-cp39-abi3-macosx_11_0_arm64.whl", hash = "sha256:ab0d1f23084afee2b97de8c37aa3e02ec3569749ae39571bd89e7a8b11ae9e83", size = 39300602, upload-time = "2025-12-10T01:13:59.366Z" }, + { url = "https://files.pythonhosted.org/packages/54/1e/2707bee75a780a953a77a2c59829ee90ef55708f02fc4add761c579bf76e/polars_runtime_32-1.36.1-cp39-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:899b9ad2e47ceb31eb157f27a09dbc2047efbf4969a923a6b1ba7f0412c3e64c", size = 44511780, upload-time = "2025-12-10T01:14:02.285Z" }, + { url = "https://files.pythonhosted.org/packages/11/b2/3fede95feee441be64b4bcb32444679a8fbb7a453a10251583053f6efe52/polars_runtime_32-1.36.1-cp39-abi3-manylinux_2_24_aarch64.whl", hash = "sha256:d9d077bb9df711bc635a86540df48242bb91975b353e53ef261c6fae6cb0948f", size = 40688448, upload-time = "2025-12-10T01:14:05.131Z" }, + { url = "https://files.pythonhosted.org/packages/05/0f/e629713a72999939b7b4bfdbf030a32794db588b04fdf3dc977dd8ea6c53/polars_runtime_32-1.36.1-cp39-abi3-win_amd64.whl", hash = "sha256:cc17101f28c9a169ff8b5b8d4977a3683cd403621841623825525f440b564cf0", size = 44464898, upload-time = "2025-12-10T01:14:08.296Z" }, + { url = "https://files.pythonhosted.org/packages/d1/d8/a12e6aa14f63784cead437083319ec7cece0d5bb9a5bfe7678cc6578b52a/polars_runtime_32-1.36.1-cp39-abi3-win_arm64.whl", hash = "sha256:809e73857be71250141225ddd5d2b30c97e6340aeaa0d445f930e01bef6888dc", size = 39798896, upload-time = "2025-12-10T01:14:11.568Z" }, ] [[package]] @@ -6071,17 +6069,17 @@ wheels = [ [[package]] name = "protobuf" -version = "6.33.4" +version = "6.33.2" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/53/b8/cda15d9d46d03d4aa3a67cb6bffe05173440ccf86a9541afaf7ac59a1b6b/protobuf-6.33.4.tar.gz", hash = "sha256:dc2e61bca3b10470c1912d166fe0af67bfc20eb55971dcef8dfa48ce14f0ed91", size = 444346, upload-time = "2026-01-12T18:33:40.109Z" } +sdist = { url = "https://files.pythonhosted.org/packages/34/44/e49ecff446afeec9d1a66d6bbf9adc21e3c7cea7803a920ca3773379d4f6/protobuf-6.33.2.tar.gz", hash = "sha256:56dc370c91fbb8ac85bc13582c9e373569668a290aa2e66a590c2a0d35ddb9e4", size = 444296, upload-time = "2025-12-06T00:17:53.311Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/e0/be/24ef9f3095bacdf95b458543334d0c4908ccdaee5130420bf064492c325f/protobuf-6.33.4-cp310-abi3-win32.whl", hash = "sha256:918966612c8232fc6c24c78e1cd89784307f5814ad7506c308ee3cf86662850d", size = 425612, upload-time = "2026-01-12T18:33:29.656Z" }, - { url = "https://files.pythonhosted.org/packages/31/ad/e5693e1974a28869e7cd244302911955c1cebc0161eb32dfa2b25b6e96f0/protobuf-6.33.4-cp310-abi3-win_amd64.whl", hash = "sha256:8f11ffae31ec67fc2554c2ef891dcb561dae9a2a3ed941f9e134c2db06657dbc", size = 436962, upload-time = "2026-01-12T18:33:31.345Z" }, - { url = "https://files.pythonhosted.org/packages/66/15/6ee23553b6bfd82670207ead921f4d8ef14c107e5e11443b04caeb5ab5ec/protobuf-6.33.4-cp39-abi3-macosx_10_9_universal2.whl", hash = "sha256:2fe67f6c014c84f655ee06f6f66213f9254b3a8b6bda6cda0ccd4232c73c06f0", size = 427612, upload-time = "2026-01-12T18:33:32.646Z" }, - { url = "https://files.pythonhosted.org/packages/2b/48/d301907ce6d0db75f959ca74f44b475a9caa8fcba102d098d3c3dd0f2d3f/protobuf-6.33.4-cp39-abi3-manylinux2014_aarch64.whl", hash = "sha256:757c978f82e74d75cba88eddec479df9b99a42b31193313b75e492c06a51764e", size = 324484, upload-time = "2026-01-12T18:33:33.789Z" }, - { url = "https://files.pythonhosted.org/packages/92/1c/e53078d3f7fe710572ab2dcffd993e1e3b438ae71cfc031b71bae44fcb2d/protobuf-6.33.4-cp39-abi3-manylinux2014_s390x.whl", hash = "sha256:c7c64f259c618f0bef7bee042075e390debbf9682334be2b67408ec7c1c09ee6", size = 339256, upload-time = "2026-01-12T18:33:35.231Z" }, - { url = "https://files.pythonhosted.org/packages/e8/8e/971c0edd084914f7ee7c23aa70ba89e8903918adca179319ee94403701d5/protobuf-6.33.4-cp39-abi3-manylinux2014_x86_64.whl", hash = "sha256:3df850c2f8db9934de4cf8f9152f8dc2558f49f298f37f90c517e8e5c84c30e9", size = 323311, upload-time = "2026-01-12T18:33:36.305Z" }, - { url = "https://files.pythonhosted.org/packages/75/b1/1dc83c2c661b4c62d56cc081706ee33a4fc2835bd90f965baa2663ef7676/protobuf-6.33.4-py3-none-any.whl", hash = "sha256:1fe3730068fcf2e595816a6c34fe66eeedd37d51d0400b72fabc848811fdc1bc", size = 170532, upload-time = "2026-01-12T18:33:39.199Z" }, + { url = "https://files.pythonhosted.org/packages/bc/91/1e3a34881a88697a7354ffd177e8746e97a722e5e8db101544b47e84afb1/protobuf-6.33.2-cp310-abi3-win32.whl", hash = "sha256:87eb388bd2d0f78febd8f4c8779c79247b26a5befad525008e49a6955787ff3d", size = 425603, upload-time = "2025-12-06T00:17:41.114Z" }, + { url = "https://files.pythonhosted.org/packages/64/20/4d50191997e917ae13ad0a235c8b42d8c1ab9c3e6fd455ca16d416944355/protobuf-6.33.2-cp310-abi3-win_amd64.whl", hash = "sha256:fc2a0e8b05b180e5fc0dd1559fe8ebdae21a27e81ac77728fb6c42b12c7419b4", size = 436930, upload-time = "2025-12-06T00:17:43.278Z" }, + { url = "https://files.pythonhosted.org/packages/b2/ca/7e485da88ba45c920fb3f50ae78de29ab925d9e54ef0de678306abfbb497/protobuf-6.33.2-cp39-abi3-macosx_10_9_universal2.whl", hash = "sha256:d9b19771ca75935b3a4422957bc518b0cecb978b31d1dd12037b088f6bcc0e43", size = 427621, upload-time = "2025-12-06T00:17:44.445Z" }, + { url = "https://files.pythonhosted.org/packages/7d/4f/f743761e41d3b2b2566748eb76bbff2b43e14d5fcab694f494a16458b05f/protobuf-6.33.2-cp39-abi3-manylinux2014_aarch64.whl", hash = "sha256:b5d3b5625192214066d99b2b605f5783483575656784de223f00a8d00754fc0e", size = 324460, upload-time = "2025-12-06T00:17:45.678Z" }, + { url = "https://files.pythonhosted.org/packages/b1/fa/26468d00a92824020f6f2090d827078c09c9c587e34cbfd2d0c7911221f8/protobuf-6.33.2-cp39-abi3-manylinux2014_s390x.whl", hash = "sha256:8cd7640aee0b7828b6d03ae518b5b4806fdfc1afe8de82f79c3454f8aef29872", size = 339168, upload-time = "2025-12-06T00:17:46.813Z" }, + { url = "https://files.pythonhosted.org/packages/56/13/333b8f421738f149d4fe5e49553bc2a2ab75235486259f689b4b91f96cec/protobuf-6.33.2-cp39-abi3-manylinux2014_x86_64.whl", hash = "sha256:1f8017c48c07ec5859106533b682260ba3d7c5567b1ca1f24297ce03384d1b4f", size = 323270, upload-time = "2025-12-06T00:17:48.253Z" }, + { url = "https://files.pythonhosted.org/packages/0e/15/4f02896cc3df04fc465010a4c6a0cd89810f54617a32a70ef531ed75d61c/protobuf-6.33.2-py3-none-any.whl", hash = "sha256:7636aad9bb01768870266de5dc009de2d1b936771b38a793f73cbbf279c91c5c", size = 170501, upload-time = "2025-12-06T00:17:52.211Z" }, ] [[package]] @@ -6848,7 +6846,7 @@ dependencies = [ { name = "pyglet" }, { name = "pyopengl" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "six" }, { name = "trimesh" }, ] @@ -7719,7 +7717,7 @@ resolution-markers = [ dependencies = [ { name = "joblib", marker = "python_full_version >= '3.11'" }, { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, - { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "threadpoolctl", marker = "python_full_version >= '3.11'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/0e/d4/40988bf3b8e34feec1d0e6a051446b1f66225f8529b9309becaeef62b6c4/scikit_learn-1.8.0.tar.gz", hash = "sha256:9bccbb3b40e3de10351f8f5068e105d0f4083b1a65fa07b6634fbc401a6287fd", size = 7335585, upload-time = "2025-12-10T07:08:53.618Z" } @@ -7826,7 +7824,7 @@ wheels = [ [[package]] name = "scipy" -version = "1.17.0" +version = "1.16.3" source = { registry = "https://pypi.org/simple" } resolution-markers = [ "python_full_version >= '3.13' and sys_platform == 'darwin'", @@ -7845,68 +7843,68 @@ resolution-markers = [ dependencies = [ { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/56/3e/9cca699f3486ce6bc12ff46dc2031f1ec8eb9ccc9a320fdaf925f1417426/scipy-1.17.0.tar.gz", hash = "sha256:2591060c8e648d8b96439e111ac41fd8342fdeff1876be2e19dea3fe8930454e", size = 30396830, upload-time = "2026-01-10T21:34:23.009Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/1e/4b/c89c131aa87cad2b77a54eb0fb94d633a842420fa7e919dc2f922037c3d8/scipy-1.17.0-cp311-cp311-macosx_10_14_x86_64.whl", hash = "sha256:2abd71643797bd8a106dff97894ff7869eeeb0af0f7a5ce02e4227c6a2e9d6fd", size = 31381316, upload-time = "2026-01-10T21:24:33.42Z" }, - { url = "https://files.pythonhosted.org/packages/5e/5f/a6b38f79a07d74989224d5f11b55267714707582908a5f1ae854cf9a9b84/scipy-1.17.0-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:ef28d815f4d2686503e5f4f00edc387ae58dfd7a2f42e348bb53359538f01558", size = 27966760, upload-time = "2026-01-10T21:24:38.911Z" }, - { url = "https://files.pythonhosted.org/packages/c1/20/095ad24e031ee8ed3c5975954d816b8e7e2abd731e04f8be573de8740885/scipy-1.17.0-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:272a9f16d6bb4667e8b50d25d71eddcc2158a214df1b566319298de0939d2ab7", size = 20138701, upload-time = "2026-01-10T21:24:43.249Z" }, - { url = "https://files.pythonhosted.org/packages/89/11/4aad2b3858d0337756f3323f8960755704e530b27eb2a94386c970c32cbe/scipy-1.17.0-cp311-cp311-macosx_14_0_x86_64.whl", hash = "sha256:7204fddcbec2fe6598f1c5fdf027e9f259106d05202a959a9f1aecf036adc9f6", size = 22480574, upload-time = "2026-01-10T21:24:47.266Z" }, - { url = "https://files.pythonhosted.org/packages/85/bd/f5af70c28c6da2227e510875cadf64879855193a687fb19951f0f44cfd6b/scipy-1.17.0-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:fc02c37a5639ee67d8fb646ffded6d793c06c5622d36b35cfa8fe5ececb8f042", size = 32862414, upload-time = "2026-01-10T21:24:52.566Z" }, - { url = "https://files.pythonhosted.org/packages/ef/df/df1457c4df3826e908879fe3d76bc5b6e60aae45f4ee42539512438cfd5d/scipy-1.17.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:dac97a27520d66c12a34fd90a4fe65f43766c18c0d6e1c0a80f114d2260080e4", size = 35112380, upload-time = "2026-01-10T21:24:58.433Z" }, - { url = "https://files.pythonhosted.org/packages/5f/bb/88e2c16bd1dd4de19d80d7c5e238387182993c2fb13b4b8111e3927ad422/scipy-1.17.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:ebb7446a39b3ae0fe8f416a9a3fdc6fba3f11c634f680f16a239c5187bc487c0", size = 34922676, upload-time = "2026-01-10T21:25:04.287Z" }, - { url = "https://files.pythonhosted.org/packages/02/ba/5120242cc735f71fc002cff0303d536af4405eb265f7c60742851e7ccfe9/scipy-1.17.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:474da16199f6af66601a01546144922ce402cb17362e07d82f5a6cf8f963e449", size = 37507599, upload-time = "2026-01-10T21:25:09.851Z" }, - { url = "https://files.pythonhosted.org/packages/52/c8/08629657ac6c0da198487ce8cd3de78e02cfde42b7f34117d56a3fe249dc/scipy-1.17.0-cp311-cp311-win_amd64.whl", hash = "sha256:255c0da161bd7b32a6c898e7891509e8a9289f0b1c6c7d96142ee0d2b114c2ea", size = 36380284, upload-time = "2026-01-10T21:25:15.632Z" }, - { url = "https://files.pythonhosted.org/packages/6c/4a/465f96d42c6f33ad324a40049dfd63269891db9324aa66c4a1c108c6f994/scipy-1.17.0-cp311-cp311-win_arm64.whl", hash = "sha256:85b0ac3ad17fa3be50abd7e69d583d98792d7edc08367e01445a1e2076005379", size = 24370427, upload-time = "2026-01-10T21:25:20.514Z" }, - { url = "https://files.pythonhosted.org/packages/0b/11/7241a63e73ba5a516f1930ac8d5b44cbbfabd35ac73a2d08ca206df007c4/scipy-1.17.0-cp312-cp312-macosx_10_14_x86_64.whl", hash = "sha256:0d5018a57c24cb1dd828bcf51d7b10e65986d549f52ef5adb6b4d1ded3e32a57", size = 31364580, upload-time = "2026-01-10T21:25:25.717Z" }, - { url = "https://files.pythonhosted.org/packages/ed/1d/5057f812d4f6adc91a20a2d6f2ebcdb517fdbc87ae3acc5633c9b97c8ba5/scipy-1.17.0-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:88c22af9e5d5a4f9e027e26772cc7b5922fab8bcc839edb3ae33de404feebd9e", size = 27969012, upload-time = "2026-01-10T21:25:30.921Z" }, - { url = "https://files.pythonhosted.org/packages/e3/21/f6ec556c1e3b6ec4e088da667d9987bb77cc3ab3026511f427dc8451187d/scipy-1.17.0-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:f3cd947f20fe17013d401b64e857c6b2da83cae567adbb75b9dcba865abc66d8", size = 20140691, upload-time = "2026-01-10T21:25:34.802Z" }, - { url = "https://files.pythonhosted.org/packages/7a/fe/5e5ad04784964ba964a96f16c8d4676aa1b51357199014dce58ab7ec5670/scipy-1.17.0-cp312-cp312-macosx_14_0_x86_64.whl", hash = "sha256:e8c0b331c2c1f531eb51f1b4fc9ba709521a712cce58f1aa627bc007421a5306", size = 22463015, upload-time = "2026-01-10T21:25:39.277Z" }, - { url = "https://files.pythonhosted.org/packages/4a/69/7c347e857224fcaf32a34a05183b9d8a7aca25f8f2d10b8a698b8388561a/scipy-1.17.0-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:5194c445d0a1c7a6c1a4a4681b6b7c71baad98ff66d96b949097e7513c9d6742", size = 32724197, upload-time = "2026-01-10T21:25:44.084Z" }, - { url = "https://files.pythonhosted.org/packages/d1/fe/66d73b76d378ba8cc2fe605920c0c75092e3a65ae746e1e767d9d020a75a/scipy-1.17.0-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9eeb9b5f5997f75507814ed9d298ab23f62cf79f5a3ef90031b1ee2506abdb5b", size = 35009148, upload-time = "2026-01-10T21:25:50.591Z" }, - { url = "https://files.pythonhosted.org/packages/af/07/07dec27d9dc41c18d8c43c69e9e413431d20c53a0339c388bcf72f353c4b/scipy-1.17.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:40052543f7bbe921df4408f46003d6f01c6af109b9e2c8a66dd1cf6cf57f7d5d", size = 34798766, upload-time = "2026-01-10T21:25:59.41Z" }, - { url = "https://files.pythonhosted.org/packages/81/61/0470810c8a093cdacd4ba7504b8a218fd49ca070d79eca23a615f5d9a0b0/scipy-1.17.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:0cf46c8013fec9d3694dc572f0b54100c28405d55d3e2cb15e2895b25057996e", size = 37405953, upload-time = "2026-01-10T21:26:07.75Z" }, - { url = "https://files.pythonhosted.org/packages/92/ce/672ed546f96d5d41ae78c4b9b02006cedd0b3d6f2bf5bb76ea455c320c28/scipy-1.17.0-cp312-cp312-win_amd64.whl", hash = "sha256:0937a0b0d8d593a198cededd4c439a0ea216a3f36653901ea1f3e4be949056f8", size = 36328121, upload-time = "2026-01-10T21:26:16.509Z" }, - { url = "https://files.pythonhosted.org/packages/9d/21/38165845392cae67b61843a52c6455d47d0cc2a40dd495c89f4362944654/scipy-1.17.0-cp312-cp312-win_arm64.whl", hash = "sha256:f603d8a5518c7426414d1d8f82e253e454471de682ce5e39c29adb0df1efb86b", size = 24314368, upload-time = "2026-01-10T21:26:23.087Z" }, - { url = "https://files.pythonhosted.org/packages/0c/51/3468fdfd49387ddefee1636f5cf6d03ce603b75205bf439bbf0e62069bfd/scipy-1.17.0-cp313-cp313-macosx_10_14_x86_64.whl", hash = "sha256:65ec32f3d32dfc48c72df4291345dae4f048749bc8d5203ee0a3f347f96c5ce6", size = 31344101, upload-time = "2026-01-10T21:26:30.25Z" }, - { url = "https://files.pythonhosted.org/packages/b2/9a/9406aec58268d437636069419e6977af953d1e246df941d42d3720b7277b/scipy-1.17.0-cp313-cp313-macosx_12_0_arm64.whl", hash = "sha256:1f9586a58039d7229ce77b52f8472c972448cded5736eaf102d5658bbac4c269", size = 27950385, upload-time = "2026-01-10T21:26:36.801Z" }, - { url = "https://files.pythonhosted.org/packages/4f/98/e7342709e17afdfd1b26b56ae499ef4939b45a23a00e471dfb5375eea205/scipy-1.17.0-cp313-cp313-macosx_14_0_arm64.whl", hash = "sha256:9fad7d3578c877d606b1150135c2639e9de9cecd3705caa37b66862977cc3e72", size = 20122115, upload-time = "2026-01-10T21:26:42.107Z" }, - { url = "https://files.pythonhosted.org/packages/fd/0e/9eeeb5357a64fd157cbe0302c213517c541cc16b8486d82de251f3c68ede/scipy-1.17.0-cp313-cp313-macosx_14_0_x86_64.whl", hash = "sha256:423ca1f6584fc03936972b5f7c06961670dbba9f234e71676a7c7ccf938a0d61", size = 22442402, upload-time = "2026-01-10T21:26:48.029Z" }, - { url = "https://files.pythonhosted.org/packages/c9/10/be13397a0e434f98e0c79552b2b584ae5bb1c8b2be95db421533bbca5369/scipy-1.17.0-cp313-cp313-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:fe508b5690e9eaaa9467fc047f833af58f1152ae51a0d0aed67aa5801f4dd7d6", size = 32696338, upload-time = "2026-01-10T21:26:55.521Z" }, - { url = "https://files.pythonhosted.org/packages/63/1e/12fbf2a3bb240161651c94bb5cdd0eae5d4e8cc6eaeceb74ab07b12a753d/scipy-1.17.0-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6680f2dfd4f6182e7d6db161344537da644d1cf85cf293f015c60a17ecf08752", size = 34977201, upload-time = "2026-01-10T21:27:03.501Z" }, - { url = "https://files.pythonhosted.org/packages/19/5b/1a63923e23ccd20bd32156d7dd708af5bbde410daa993aa2500c847ab2d2/scipy-1.17.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:eec3842ec9ac9de5917899b277428886042a93db0b227ebbe3a333b64ec7643d", size = 34777384, upload-time = "2026-01-10T21:27:11.423Z" }, - { url = "https://files.pythonhosted.org/packages/39/22/b5da95d74edcf81e540e467202a988c50fef41bd2011f46e05f72ba07df6/scipy-1.17.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:d7425fcafbc09a03731e1bc05581f5fad988e48c6a861f441b7ab729a49a55ea", size = 37379586, upload-time = "2026-01-10T21:27:20.171Z" }, - { url = "https://files.pythonhosted.org/packages/b9/b6/8ac583d6da79e7b9e520579f03007cb006f063642afd6b2eeb16b890bf93/scipy-1.17.0-cp313-cp313-win_amd64.whl", hash = "sha256:87b411e42b425b84777718cc41516b8a7e0795abfa8e8e1d573bf0ef014f0812", size = 36287211, upload-time = "2026-01-10T21:28:43.122Z" }, - { url = "https://files.pythonhosted.org/packages/55/fb/7db19e0b3e52f882b420417644ec81dd57eeef1bd1705b6f689d8ff93541/scipy-1.17.0-cp313-cp313-win_arm64.whl", hash = "sha256:357ca001c6e37601066092e7c89cca2f1ce74e2a520ca78d063a6d2201101df2", size = 24312646, upload-time = "2026-01-10T21:28:49.893Z" }, - { url = "https://files.pythonhosted.org/packages/20/b6/7feaa252c21cc7aff335c6c55e1b90ab3e3306da3f048109b8b639b94648/scipy-1.17.0-cp313-cp313t-macosx_10_14_x86_64.whl", hash = "sha256:ec0827aa4d36cb79ff1b81de898e948a51ac0b9b1c43e4a372c0508c38c0f9a3", size = 31693194, upload-time = "2026-01-10T21:27:27.454Z" }, - { url = "https://files.pythonhosted.org/packages/76/bb/bbb392005abce039fb7e672cb78ac7d158700e826b0515cab6b5b60c26fb/scipy-1.17.0-cp313-cp313t-macosx_12_0_arm64.whl", hash = "sha256:819fc26862b4b3c73a60d486dbb919202f3d6d98c87cf20c223511429f2d1a97", size = 28365415, upload-time = "2026-01-10T21:27:34.26Z" }, - { url = "https://files.pythonhosted.org/packages/37/da/9d33196ecc99fba16a409c691ed464a3a283ac454a34a13a3a57c0d66f3a/scipy-1.17.0-cp313-cp313t-macosx_14_0_arm64.whl", hash = "sha256:363ad4ae2853d88ebcde3ae6ec46ccca903ea9835ee8ba543f12f575e7b07e4e", size = 20537232, upload-time = "2026-01-10T21:27:40.306Z" }, - { url = "https://files.pythonhosted.org/packages/56/9d/f4b184f6ddb28e9a5caea36a6f98e8ecd2a524f9127354087ce780885d83/scipy-1.17.0-cp313-cp313t-macosx_14_0_x86_64.whl", hash = "sha256:979c3a0ff8e5ba254d45d59ebd38cde48fce4f10b5125c680c7a4bfe177aab07", size = 22791051, upload-time = "2026-01-10T21:27:46.539Z" }, - { url = "https://files.pythonhosted.org/packages/9b/9d/025cccdd738a72140efc582b1641d0dd4caf2e86c3fb127568dc80444e6e/scipy-1.17.0-cp313-cp313t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:130d12926ae34399d157de777472bf82e9061c60cc081372b3118edacafe1d00", size = 32815098, upload-time = "2026-01-10T21:27:54.389Z" }, - { url = "https://files.pythonhosted.org/packages/48/5f/09b879619f8bca15ce392bfc1894bd9c54377e01d1b3f2f3b595a1b4d945/scipy-1.17.0-cp313-cp313t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6e886000eb4919eae3a44f035e63f0fd8b651234117e8f6f29bad1cd26e7bc45", size = 35031342, upload-time = "2026-01-10T21:28:03.012Z" }, - { url = "https://files.pythonhosted.org/packages/f2/9a/f0f0a9f0aa079d2f106555b984ff0fbb11a837df280f04f71f056ea9c6e4/scipy-1.17.0-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:13c4096ac6bc31d706018f06a49abe0485f96499deb82066b94d19b02f664209", size = 34893199, upload-time = "2026-01-10T21:28:10.832Z" }, - { url = "https://files.pythonhosted.org/packages/90/b8/4f0f5cf0c5ea4d7548424e6533e6b17d164f34a6e2fb2e43ffebb6697b06/scipy-1.17.0-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:cacbaddd91fcffde703934897c5cd2c7cb0371fac195d383f4e1f1c5d3f3bd04", size = 37438061, upload-time = "2026-01-10T21:28:19.684Z" }, - { url = "https://files.pythonhosted.org/packages/f9/cc/2bd59140ed3b2fa2882fb15da0a9cb1b5a6443d67cfd0d98d4cec83a57ec/scipy-1.17.0-cp313-cp313t-win_amd64.whl", hash = "sha256:edce1a1cf66298cccdc48a1bdf8fb10a3bf58e8b58d6c3883dd1530e103f87c0", size = 36328593, upload-time = "2026-01-10T21:28:28.007Z" }, - { url = "https://files.pythonhosted.org/packages/13/1b/c87cc44a0d2c7aaf0f003aef2904c3d097b422a96c7e7c07f5efd9073c1b/scipy-1.17.0-cp313-cp313t-win_arm64.whl", hash = "sha256:30509da9dbec1c2ed8f168b8d8aa853bc6723fede1dbc23c7d43a56f5ab72a67", size = 24625083, upload-time = "2026-01-10T21:28:35.188Z" }, - { url = "https://files.pythonhosted.org/packages/1a/2d/51006cd369b8e7879e1c630999a19d1fbf6f8b5ed3e33374f29dc87e53b3/scipy-1.17.0-cp314-cp314-macosx_10_14_x86_64.whl", hash = "sha256:c17514d11b78be8f7e6331b983a65a7f5ca1fd037b95e27b280921fe5606286a", size = 31346803, upload-time = "2026-01-10T21:28:57.24Z" }, - { url = "https://files.pythonhosted.org/packages/d6/2e/2349458c3ce445f53a6c93d4386b1c4c5c0c540917304c01222ff95ff317/scipy-1.17.0-cp314-cp314-macosx_12_0_arm64.whl", hash = "sha256:4e00562e519c09da34c31685f6acc3aa384d4d50604db0f245c14e1b4488bfa2", size = 27967182, upload-time = "2026-01-10T21:29:04.107Z" }, - { url = "https://files.pythonhosted.org/packages/5e/7c/df525fbfa77b878d1cfe625249529514dc02f4fd5f45f0f6295676a76528/scipy-1.17.0-cp314-cp314-macosx_14_0_arm64.whl", hash = "sha256:f7df7941d71314e60a481e02d5ebcb3f0185b8d799c70d03d8258f6c80f3d467", size = 20139125, upload-time = "2026-01-10T21:29:10.179Z" }, - { url = "https://files.pythonhosted.org/packages/33/11/fcf9d43a7ed1234d31765ec643b0515a85a30b58eddccc5d5a4d12b5f194/scipy-1.17.0-cp314-cp314-macosx_14_0_x86_64.whl", hash = "sha256:aabf057c632798832f071a8dde013c2e26284043934f53b00489f1773b33527e", size = 22443554, upload-time = "2026-01-10T21:29:15.888Z" }, - { url = "https://files.pythonhosted.org/packages/80/5c/ea5d239cda2dd3d31399424967a24d556cf409fbea7b5b21412b0fd0a44f/scipy-1.17.0-cp314-cp314-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:a38c3337e00be6fd8a95b4ed66b5d988bac4ec888fd922c2ea9fe5fb1603dd67", size = 32757834, upload-time = "2026-01-10T21:29:23.406Z" }, - { url = "https://files.pythonhosted.org/packages/b8/7e/8c917cc573310e5dc91cbeead76f1b600d3fb17cf0969db02c9cf92e3cfa/scipy-1.17.0-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:00fb5f8ec8398ad90215008d8b6009c9db9fa924fd4c7d6be307c6f945f9cd73", size = 34995775, upload-time = "2026-01-10T21:29:31.915Z" }, - { url = "https://files.pythonhosted.org/packages/c5/43/176c0c3c07b3f7df324e7cdd933d3e2c4898ca202b090bd5ba122f9fe270/scipy-1.17.0-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:f2a4942b0f5f7c23c7cd641a0ca1955e2ae83dedcff537e3a0259096635e186b", size = 34841240, upload-time = "2026-01-10T21:29:39.995Z" }, - { url = "https://files.pythonhosted.org/packages/44/8c/d1f5f4b491160592e7f084d997de53a8e896a3ac01cd07e59f43ca222744/scipy-1.17.0-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:dbf133ced83889583156566d2bdf7a07ff89228fe0c0cb727f777de92092ec6b", size = 37394463, upload-time = "2026-01-10T21:29:48.723Z" }, - { url = "https://files.pythonhosted.org/packages/9f/ec/42a6657f8d2d087e750e9a5dde0b481fd135657f09eaf1cf5688bb23c338/scipy-1.17.0-cp314-cp314-win_amd64.whl", hash = "sha256:3625c631a7acd7cfd929e4e31d2582cf00f42fcf06011f59281271746d77e061", size = 37053015, upload-time = "2026-01-10T21:30:51.418Z" }, - { url = "https://files.pythonhosted.org/packages/27/58/6b89a6afd132787d89a362d443a7bddd511b8f41336a1ae47f9e4f000dc4/scipy-1.17.0-cp314-cp314-win_arm64.whl", hash = "sha256:9244608d27eafe02b20558523ba57f15c689357c85bdcfe920b1828750aa26eb", size = 24951312, upload-time = "2026-01-10T21:30:56.771Z" }, - { url = "https://files.pythonhosted.org/packages/e9/01/f58916b9d9ae0112b86d7c3b10b9e685625ce6e8248df139d0fcb17f7397/scipy-1.17.0-cp314-cp314t-macosx_10_14_x86_64.whl", hash = "sha256:2b531f57e09c946f56ad0b4a3b2abee778789097871fc541e267d2eca081cff1", size = 31706502, upload-time = "2026-01-10T21:29:56.326Z" }, - { url = "https://files.pythonhosted.org/packages/59/8e/2912a87f94a7d1f8b38aabc0faf74b82d3b6c9e22be991c49979f0eceed8/scipy-1.17.0-cp314-cp314t-macosx_12_0_arm64.whl", hash = "sha256:13e861634a2c480bd237deb69333ac79ea1941b94568d4b0efa5db5e263d4fd1", size = 28380854, upload-time = "2026-01-10T21:30:01.554Z" }, - { url = "https://files.pythonhosted.org/packages/bd/1c/874137a52dddab7d5d595c1887089a2125d27d0601fce8c0026a24a92a0b/scipy-1.17.0-cp314-cp314t-macosx_14_0_arm64.whl", hash = "sha256:eb2651271135154aa24f6481cbae5cc8af1f0dd46e6533fb7b56aa9727b6a232", size = 20552752, upload-time = "2026-01-10T21:30:05.93Z" }, - { url = "https://files.pythonhosted.org/packages/3f/f0/7518d171cb735f6400f4576cf70f756d5b419a07fe1867da34e2c2c9c11b/scipy-1.17.0-cp314-cp314t-macosx_14_0_x86_64.whl", hash = "sha256:c5e8647f60679790c2f5c76be17e2e9247dc6b98ad0d3b065861e082c56e078d", size = 22803972, upload-time = "2026-01-10T21:30:10.651Z" }, - { url = "https://files.pythonhosted.org/packages/7c/74/3498563a2c619e8a3ebb4d75457486c249b19b5b04a30600dfd9af06bea5/scipy-1.17.0-cp314-cp314t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:5fb10d17e649e1446410895639f3385fd2bf4c3c7dfc9bea937bddcbc3d7b9ba", size = 32829770, upload-time = "2026-01-10T21:30:16.359Z" }, - { url = "https://files.pythonhosted.org/packages/48/d1/7b50cedd8c6c9d6f706b4b36fa8544d829c712a75e370f763b318e9638c1/scipy-1.17.0-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:8547e7c57f932e7354a2319fab613981cde910631979f74c9b542bb167a8b9db", size = 35051093, upload-time = "2026-01-10T21:30:22.987Z" }, - { url = "https://files.pythonhosted.org/packages/e2/82/a2d684dfddb87ba1b3ea325df7c3293496ee9accb3a19abe9429bce94755/scipy-1.17.0-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:33af70d040e8af9d5e7a38b5ed3b772adddd281e3062ff23fec49e49681c38cf", size = 34909905, upload-time = "2026-01-10T21:30:28.704Z" }, - { url = "https://files.pythonhosted.org/packages/ef/5e/e565bd73991d42023eb82bb99e51c5b3d9e2c588ca9d4b3e2cc1d3ca62a6/scipy-1.17.0-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:f9eb55bb97d00f8b7ab95cb64f873eb0bf54d9446264d9f3609130381233483f", size = 37457743, upload-time = "2026-01-10T21:30:34.819Z" }, - { url = "https://files.pythonhosted.org/packages/58/a8/a66a75c3d8f1fb2b83f66007d6455a06a6f6cf5618c3dc35bc9b69dd096e/scipy-1.17.0-cp314-cp314t-win_amd64.whl", hash = "sha256:1ff269abf702f6c7e67a4b7aad981d42871a11b9dd83c58d2d2ea624efbd1088", size = 37098574, upload-time = "2026-01-10T21:30:40.782Z" }, - { url = "https://files.pythonhosted.org/packages/56/a5/df8f46ef7da168f1bc52cd86e09a9de5c6f19cc1da04454d51b7d4f43408/scipy-1.17.0-cp314-cp314t-win_arm64.whl", hash = "sha256:031121914e295d9791319a1875444d55079885bbae5bdc9c5e0f2ee5f09d34ff", size = 25246266, upload-time = "2026-01-10T21:30:45.923Z" }, +sdist = { url = "https://files.pythonhosted.org/packages/0a/ca/d8ace4f98322d01abcd52d381134344bf7b431eba7ed8b42bdea5a3c2ac9/scipy-1.16.3.tar.gz", hash = "sha256:01e87659402762f43bd2fee13370553a17ada367d42e7487800bf2916535aecb", size = 30597883, upload-time = "2025-10-28T17:38:54.068Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/9b/5f/6f37d7439de1455ce9c5a556b8d1db0979f03a796c030bafdf08d35b7bf9/scipy-1.16.3-cp311-cp311-macosx_10_14_x86_64.whl", hash = "sha256:40be6cf99e68b6c4321e9f8782e7d5ff8265af28ef2cd56e9c9b2638fa08ad97", size = 36630881, upload-time = "2025-10-28T17:31:47.104Z" }, + { url = "https://files.pythonhosted.org/packages/7c/89/d70e9f628749b7e4db2aa4cd89735502ff3f08f7b9b27d2e799485987cd9/scipy-1.16.3-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:8be1ca9170fcb6223cc7c27f4305d680ded114a1567c0bd2bfcbf947d1b17511", size = 28941012, upload-time = "2025-10-28T17:31:53.411Z" }, + { url = "https://files.pythonhosted.org/packages/a8/a8/0e7a9a6872a923505dbdf6bb93451edcac120363131c19013044a1e7cb0c/scipy-1.16.3-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:bea0a62734d20d67608660f69dcda23e7f90fb4ca20974ab80b6ed40df87a005", size = 20931935, upload-time = "2025-10-28T17:31:57.361Z" }, + { url = "https://files.pythonhosted.org/packages/bd/c7/020fb72bd79ad798e4dbe53938543ecb96b3a9ac3fe274b7189e23e27353/scipy-1.16.3-cp311-cp311-macosx_14_0_x86_64.whl", hash = "sha256:2a207a6ce9c24f1951241f4693ede2d393f59c07abc159b2cb2be980820e01fb", size = 23534466, upload-time = "2025-10-28T17:32:01.875Z" }, + { url = "https://files.pythonhosted.org/packages/be/a0/668c4609ce6dbf2f948e167836ccaf897f95fb63fa231c87da7558a374cd/scipy-1.16.3-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:532fb5ad6a87e9e9cd9c959b106b73145a03f04c7d57ea3e6f6bb60b86ab0876", size = 33593618, upload-time = "2025-10-28T17:32:06.902Z" }, + { url = "https://files.pythonhosted.org/packages/ca/6e/8942461cf2636cdae083e3eb72622a7fbbfa5cf559c7d13ab250a5dbdc01/scipy-1.16.3-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:0151a0749efeaaab78711c78422d413c583b8cdd2011a3c1d6c794938ee9fdb2", size = 35899798, upload-time = "2025-10-28T17:32:12.665Z" }, + { url = "https://files.pythonhosted.org/packages/79/e8/d0f33590364cdbd67f28ce79368b373889faa4ee959588beddf6daef9abe/scipy-1.16.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:b7180967113560cca57418a7bc719e30366b47959dd845a93206fbed693c867e", size = 36226154, upload-time = "2025-10-28T17:32:17.961Z" }, + { url = "https://files.pythonhosted.org/packages/39/c1/1903de608c0c924a1749c590064e65810f8046e437aba6be365abc4f7557/scipy-1.16.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:deb3841c925eeddb6afc1e4e4a45e418d19ec7b87c5df177695224078e8ec733", size = 38878540, upload-time = "2025-10-28T17:32:23.907Z" }, + { url = "https://files.pythonhosted.org/packages/f1/d0/22ec7036ba0b0a35bccb7f25ab407382ed34af0b111475eb301c16f8a2e5/scipy-1.16.3-cp311-cp311-win_amd64.whl", hash = "sha256:53c3844d527213631e886621df5695d35e4f6a75f620dca412bcd292f6b87d78", size = 38722107, upload-time = "2025-10-28T17:32:29.921Z" }, + { url = "https://files.pythonhosted.org/packages/7b/60/8a00e5a524bb3bf8898db1650d350f50e6cffb9d7a491c561dc9826c7515/scipy-1.16.3-cp311-cp311-win_arm64.whl", hash = "sha256:9452781bd879b14b6f055b26643703551320aa8d79ae064a71df55c00286a184", size = 25506272, upload-time = "2025-10-28T17:32:34.577Z" }, + { url = "https://files.pythonhosted.org/packages/40/41/5bf55c3f386b1643812f3a5674edf74b26184378ef0f3e7c7a09a7e2ca7f/scipy-1.16.3-cp312-cp312-macosx_10_14_x86_64.whl", hash = "sha256:81fc5827606858cf71446a5e98715ba0e11f0dbc83d71c7409d05486592a45d6", size = 36659043, upload-time = "2025-10-28T17:32:40.285Z" }, + { url = "https://files.pythonhosted.org/packages/1e/0f/65582071948cfc45d43e9870bf7ca5f0e0684e165d7c9ef4e50d783073eb/scipy-1.16.3-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:c97176013d404c7346bf57874eaac5187d969293bf40497140b0a2b2b7482e07", size = 28898986, upload-time = "2025-10-28T17:32:45.325Z" }, + { url = "https://files.pythonhosted.org/packages/96/5e/36bf3f0ac298187d1ceadde9051177d6a4fe4d507e8f59067dc9dd39e650/scipy-1.16.3-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:2b71d93c8a9936046866acebc915e2af2e292b883ed6e2cbe5c34beb094b82d9", size = 20889814, upload-time = "2025-10-28T17:32:49.277Z" }, + { url = "https://files.pythonhosted.org/packages/80/35/178d9d0c35394d5d5211bbff7ac4f2986c5488b59506fef9e1de13ea28d3/scipy-1.16.3-cp312-cp312-macosx_14_0_x86_64.whl", hash = "sha256:3d4a07a8e785d80289dfe66b7c27d8634a773020742ec7187b85ccc4b0e7b686", size = 23565795, upload-time = "2025-10-28T17:32:53.337Z" }, + { url = "https://files.pythonhosted.org/packages/fa/46/d1146ff536d034d02f83c8afc3c4bab2eddb634624d6529a8512f3afc9da/scipy-1.16.3-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:0553371015692a898e1aa858fed67a3576c34edefa6b7ebdb4e9dde49ce5c203", size = 33349476, upload-time = "2025-10-28T17:32:58.353Z" }, + { url = "https://files.pythonhosted.org/packages/79/2e/415119c9ab3e62249e18c2b082c07aff907a273741b3f8160414b0e9193c/scipy-1.16.3-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:72d1717fd3b5e6ec747327ce9bda32d5463f472c9dce9f54499e81fbd50245a1", size = 35676692, upload-time = "2025-10-28T17:33:03.88Z" }, + { url = "https://files.pythonhosted.org/packages/27/82/df26e44da78bf8d2aeaf7566082260cfa15955a5a6e96e6a29935b64132f/scipy-1.16.3-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:1fb2472e72e24d1530debe6ae078db70fb1605350c88a3d14bc401d6306dbffe", size = 36019345, upload-time = "2025-10-28T17:33:09.773Z" }, + { url = "https://files.pythonhosted.org/packages/82/31/006cbb4b648ba379a95c87262c2855cd0d09453e500937f78b30f02fa1cd/scipy-1.16.3-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:c5192722cffe15f9329a3948c4b1db789fbb1f05c97899187dcf009b283aea70", size = 38678975, upload-time = "2025-10-28T17:33:15.809Z" }, + { url = "https://files.pythonhosted.org/packages/c2/7f/acbd28c97e990b421af7d6d6cd416358c9c293fc958b8529e0bd5d2a2a19/scipy-1.16.3-cp312-cp312-win_amd64.whl", hash = "sha256:56edc65510d1331dae01ef9b658d428e33ed48b4f77b1d51caf479a0253f96dc", size = 38555926, upload-time = "2025-10-28T17:33:21.388Z" }, + { url = "https://files.pythonhosted.org/packages/ce/69/c5c7807fd007dad4f48e0a5f2153038dc96e8725d3345b9ee31b2b7bed46/scipy-1.16.3-cp312-cp312-win_arm64.whl", hash = "sha256:a8a26c78ef223d3e30920ef759e25625a0ecdd0d60e5a8818b7513c3e5384cf2", size = 25463014, upload-time = "2025-10-28T17:33:25.975Z" }, + { url = "https://files.pythonhosted.org/packages/72/f1/57e8327ab1508272029e27eeef34f2302ffc156b69e7e233e906c2a5c379/scipy-1.16.3-cp313-cp313-macosx_10_14_x86_64.whl", hash = "sha256:d2ec56337675e61b312179a1ad124f5f570c00f920cc75e1000025451b88241c", size = 36617856, upload-time = "2025-10-28T17:33:31.375Z" }, + { url = "https://files.pythonhosted.org/packages/44/13/7e63cfba8a7452eb756306aa2fd9b37a29a323b672b964b4fdeded9a3f21/scipy-1.16.3-cp313-cp313-macosx_12_0_arm64.whl", hash = "sha256:16b8bc35a4cc24db80a0ec836a9286d0e31b2503cb2fd7ff7fb0e0374a97081d", size = 28874306, upload-time = "2025-10-28T17:33:36.516Z" }, + { url = "https://files.pythonhosted.org/packages/15/65/3a9400efd0228a176e6ec3454b1fa998fbbb5a8defa1672c3f65706987db/scipy-1.16.3-cp313-cp313-macosx_14_0_arm64.whl", hash = "sha256:5803c5fadd29de0cf27fa08ccbfe7a9e5d741bf63e4ab1085437266f12460ff9", size = 20865371, upload-time = "2025-10-28T17:33:42.094Z" }, + { url = "https://files.pythonhosted.org/packages/33/d7/eda09adf009a9fb81827194d4dd02d2e4bc752cef16737cc4ef065234031/scipy-1.16.3-cp313-cp313-macosx_14_0_x86_64.whl", hash = "sha256:b81c27fc41954319a943d43b20e07c40bdcd3ff7cf013f4fb86286faefe546c4", size = 23524877, upload-time = "2025-10-28T17:33:48.483Z" }, + { url = "https://files.pythonhosted.org/packages/7d/6b/3f911e1ebc364cb81320223a3422aab7d26c9c7973109a9cd0f27c64c6c0/scipy-1.16.3-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:0c3b4dd3d9b08dbce0f3440032c52e9e2ab9f96ade2d3943313dfe51a7056959", size = 33342103, upload-time = "2025-10-28T17:33:56.495Z" }, + { url = "https://files.pythonhosted.org/packages/21/f6/4bfb5695d8941e5c570a04d9fcd0d36bce7511b7d78e6e75c8f9791f82d0/scipy-1.16.3-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:7dc1360c06535ea6116a2220f760ae572db9f661aba2d88074fe30ec2aa1ff88", size = 35697297, upload-time = "2025-10-28T17:34:04.722Z" }, + { url = "https://files.pythonhosted.org/packages/04/e1/6496dadbc80d8d896ff72511ecfe2316b50313bfc3ebf07a3f580f08bd8c/scipy-1.16.3-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:663b8d66a8748051c3ee9c96465fb417509315b99c71550fda2591d7dd634234", size = 36021756, upload-time = "2025-10-28T17:34:13.482Z" }, + { url = "https://files.pythonhosted.org/packages/fe/bd/a8c7799e0136b987bda3e1b23d155bcb31aec68a4a472554df5f0937eef7/scipy-1.16.3-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:eab43fae33a0c39006a88096cd7b4f4ef545ea0447d250d5ac18202d40b6611d", size = 38696566, upload-time = "2025-10-28T17:34:22.384Z" }, + { url = "https://files.pythonhosted.org/packages/cd/01/1204382461fcbfeb05b6161b594f4007e78b6eba9b375382f79153172b4d/scipy-1.16.3-cp313-cp313-win_amd64.whl", hash = "sha256:062246acacbe9f8210de8e751b16fc37458213f124bef161a5a02c7a39284304", size = 38529877, upload-time = "2025-10-28T17:35:51.076Z" }, + { url = "https://files.pythonhosted.org/packages/7f/14/9d9fbcaa1260a94f4bb5b64ba9213ceb5d03cd88841fe9fd1ffd47a45b73/scipy-1.16.3-cp313-cp313-win_arm64.whl", hash = "sha256:50a3dbf286dbc7d84f176f9a1574c705f277cb6565069f88f60db9eafdbe3ee2", size = 25455366, upload-time = "2025-10-28T17:35:59.014Z" }, + { url = "https://files.pythonhosted.org/packages/e2/a3/9ec205bd49f42d45d77f1730dbad9ccf146244c1647605cf834b3a8c4f36/scipy-1.16.3-cp313-cp313t-macosx_10_14_x86_64.whl", hash = "sha256:fb4b29f4cf8cc5a8d628bc8d8e26d12d7278cd1f219f22698a378c3d67db5e4b", size = 37027931, upload-time = "2025-10-28T17:34:31.451Z" }, + { url = "https://files.pythonhosted.org/packages/25/06/ca9fd1f3a4589cbd825b1447e5db3a8ebb969c1eaf22c8579bd286f51b6d/scipy-1.16.3-cp313-cp313t-macosx_12_0_arm64.whl", hash = "sha256:8d09d72dc92742988b0e7750bddb8060b0c7079606c0d24a8cc8e9c9c11f9079", size = 29400081, upload-time = "2025-10-28T17:34:39.087Z" }, + { url = "https://files.pythonhosted.org/packages/6a/56/933e68210d92657d93fb0e381683bc0e53a965048d7358ff5fbf9e6a1b17/scipy-1.16.3-cp313-cp313t-macosx_14_0_arm64.whl", hash = "sha256:03192a35e661470197556de24e7cb1330d84b35b94ead65c46ad6f16f6b28f2a", size = 21391244, upload-time = "2025-10-28T17:34:45.234Z" }, + { url = "https://files.pythonhosted.org/packages/a8/7e/779845db03dc1418e215726329674b40576879b91814568757ff0014ad65/scipy-1.16.3-cp313-cp313t-macosx_14_0_x86_64.whl", hash = "sha256:57d01cb6f85e34f0946b33caa66e892aae072b64b034183f3d87c4025802a119", size = 23929753, upload-time = "2025-10-28T17:34:51.793Z" }, + { url = "https://files.pythonhosted.org/packages/4c/4b/f756cf8161d5365dcdef9e5f460ab226c068211030a175d2fc7f3f41ca64/scipy-1.16.3-cp313-cp313t-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:96491a6a54e995f00a28a3c3badfff58fd093bf26cd5fb34a2188c8c756a3a2c", size = 33496912, upload-time = "2025-10-28T17:34:59.8Z" }, + { url = "https://files.pythonhosted.org/packages/09/b5/222b1e49a58668f23839ca1542a6322bb095ab8d6590d4f71723869a6c2c/scipy-1.16.3-cp313-cp313t-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:cd13e354df9938598af2be05822c323e97132d5e6306b83a3b4ee6724c6e522e", size = 35802371, upload-time = "2025-10-28T17:35:08.173Z" }, + { url = "https://files.pythonhosted.org/packages/c1/8d/5964ef68bb31829bde27611f8c9deeac13764589fe74a75390242b64ca44/scipy-1.16.3-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:63d3cdacb8a824a295191a723ee5e4ea7768ca5ca5f2838532d9f2e2b3ce2135", size = 36190477, upload-time = "2025-10-28T17:35:16.7Z" }, + { url = "https://files.pythonhosted.org/packages/ab/f2/b31d75cb9b5fa4dd39a0a931ee9b33e7f6f36f23be5ef560bf72e0f92f32/scipy-1.16.3-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:e7efa2681ea410b10dde31a52b18b0154d66f2485328830e45fdf183af5aefc6", size = 38796678, upload-time = "2025-10-28T17:35:26.354Z" }, + { url = "https://files.pythonhosted.org/packages/b4/1e/b3723d8ff64ab548c38d87055483714fefe6ee20e0189b62352b5e015bb1/scipy-1.16.3-cp313-cp313t-win_amd64.whl", hash = "sha256:2d1ae2cf0c350e7705168ff2429962a89ad90c2d49d1dd300686d8b2a5af22fc", size = 38640178, upload-time = "2025-10-28T17:35:35.304Z" }, + { url = "https://files.pythonhosted.org/packages/8e/f3/d854ff38789aca9b0cc23008d607ced9de4f7ab14fa1ca4329f86b3758ca/scipy-1.16.3-cp313-cp313t-win_arm64.whl", hash = "sha256:0c623a54f7b79dd88ef56da19bc2873afec9673a48f3b85b18e4d402bdd29a5a", size = 25803246, upload-time = "2025-10-28T17:35:42.155Z" }, + { url = "https://files.pythonhosted.org/packages/99/f6/99b10fd70f2d864c1e29a28bbcaa0c6340f9d8518396542d9ea3b4aaae15/scipy-1.16.3-cp314-cp314-macosx_10_14_x86_64.whl", hash = "sha256:875555ce62743e1d54f06cdf22c1e0bc47b91130ac40fe5d783b6dfa114beeb6", size = 36606469, upload-time = "2025-10-28T17:36:08.741Z" }, + { url = "https://files.pythonhosted.org/packages/4d/74/043b54f2319f48ea940dd025779fa28ee360e6b95acb7cd188fad4391c6b/scipy-1.16.3-cp314-cp314-macosx_12_0_arm64.whl", hash = "sha256:bb61878c18a470021fb515a843dc7a76961a8daceaaaa8bad1332f1bf4b54657", size = 28872043, upload-time = "2025-10-28T17:36:16.599Z" }, + { url = "https://files.pythonhosted.org/packages/4d/e1/24b7e50cc1c4ee6ffbcb1f27fe9f4c8b40e7911675f6d2d20955f41c6348/scipy-1.16.3-cp314-cp314-macosx_14_0_arm64.whl", hash = "sha256:f2622206f5559784fa5c4b53a950c3c7c1cf3e84ca1b9c4b6c03f062f289ca26", size = 20862952, upload-time = "2025-10-28T17:36:22.966Z" }, + { url = "https://files.pythonhosted.org/packages/dd/3a/3e8c01a4d742b730df368e063787c6808597ccb38636ed821d10b39ca51b/scipy-1.16.3-cp314-cp314-macosx_14_0_x86_64.whl", hash = "sha256:7f68154688c515cdb541a31ef8eb66d8cd1050605be9dcd74199cbd22ac739bc", size = 23508512, upload-time = "2025-10-28T17:36:29.731Z" }, + { url = "https://files.pythonhosted.org/packages/1f/60/c45a12b98ad591536bfe5330cb3cfe1850d7570259303563b1721564d458/scipy-1.16.3-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:8b3c820ddb80029fe9f43d61b81d8b488d3ef8ca010d15122b152db77dc94c22", size = 33413639, upload-time = "2025-10-28T17:36:37.982Z" }, + { url = "https://files.pythonhosted.org/packages/71/bc/35957d88645476307e4839712642896689df442f3e53b0fa016ecf8a3357/scipy-1.16.3-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:d3837938ae715fc0fe3c39c0202de3a8853aff22ca66781ddc2ade7554b7e2cc", size = 35704729, upload-time = "2025-10-28T17:36:46.547Z" }, + { url = "https://files.pythonhosted.org/packages/3b/15/89105e659041b1ca11c386e9995aefacd513a78493656e57789f9d9eab61/scipy-1.16.3-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:aadd23f98f9cb069b3bd64ddc900c4d277778242e961751f77a8cb5c4b946fb0", size = 36086251, upload-time = "2025-10-28T17:36:55.161Z" }, + { url = "https://files.pythonhosted.org/packages/1a/87/c0ea673ac9c6cc50b3da2196d860273bc7389aa69b64efa8493bdd25b093/scipy-1.16.3-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:b7c5f1bda1354d6a19bc6af73a649f8285ca63ac6b52e64e658a5a11d4d69800", size = 38716681, upload-time = "2025-10-28T17:37:04.1Z" }, + { url = "https://files.pythonhosted.org/packages/91/06/837893227b043fb9b0d13e4bd7586982d8136cb249ffb3492930dab905b8/scipy-1.16.3-cp314-cp314-win_amd64.whl", hash = "sha256:e5d42a9472e7579e473879a1990327830493a7047506d58d73fc429b84c1d49d", size = 39358423, upload-time = "2025-10-28T17:38:20.005Z" }, + { url = "https://files.pythonhosted.org/packages/95/03/28bce0355e4d34a7c034727505a02d19548549e190bedd13a721e35380b7/scipy-1.16.3-cp314-cp314-win_arm64.whl", hash = "sha256:6020470b9d00245926f2d5bb93b119ca0340f0d564eb6fbaad843eaebf9d690f", size = 26135027, upload-time = "2025-10-28T17:38:24.966Z" }, + { url = "https://files.pythonhosted.org/packages/b2/6f/69f1e2b682efe9de8fe9f91040f0cd32f13cfccba690512ba4c582b0bc29/scipy-1.16.3-cp314-cp314t-macosx_10_14_x86_64.whl", hash = "sha256:e1d27cbcb4602680a49d787d90664fa4974063ac9d4134813332a8c53dbe667c", size = 37028379, upload-time = "2025-10-28T17:37:14.061Z" }, + { url = "https://files.pythonhosted.org/packages/7c/2d/e826f31624a5ebbab1cd93d30fd74349914753076ed0593e1d56a98c4fb4/scipy-1.16.3-cp314-cp314t-macosx_12_0_arm64.whl", hash = "sha256:9b9c9c07b6d56a35777a1b4cc8966118fb16cfd8daf6743867d17d36cfad2d40", size = 29400052, upload-time = "2025-10-28T17:37:21.709Z" }, + { url = "https://files.pythonhosted.org/packages/69/27/d24feb80155f41fd1f156bf144e7e049b4e2b9dd06261a242905e3bc7a03/scipy-1.16.3-cp314-cp314t-macosx_14_0_arm64.whl", hash = "sha256:3a4c460301fb2cffb7f88528f30b3127742cff583603aa7dc964a52c463b385d", size = 21391183, upload-time = "2025-10-28T17:37:29.559Z" }, + { url = "https://files.pythonhosted.org/packages/f8/d3/1b229e433074c5738a24277eca520a2319aac7465eea7310ea6ae0e98ae2/scipy-1.16.3-cp314-cp314t-macosx_14_0_x86_64.whl", hash = "sha256:f667a4542cc8917af1db06366d3f78a5c8e83badd56409f94d1eac8d8d9133fa", size = 23930174, upload-time = "2025-10-28T17:37:36.306Z" }, + { url = "https://files.pythonhosted.org/packages/16/9d/d9e148b0ec680c0f042581a2be79a28a7ab66c0c4946697f9e7553ead337/scipy-1.16.3-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:f379b54b77a597aa7ee5e697df0d66903e41b9c85a6dd7946159e356319158e8", size = 33497852, upload-time = "2025-10-28T17:37:42.228Z" }, + { url = "https://files.pythonhosted.org/packages/2f/22/4e5f7561e4f98b7bea63cf3fd7934bff1e3182e9f1626b089a679914d5c8/scipy-1.16.3-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:4aff59800a3b7f786b70bfd6ab551001cb553244988d7d6b8299cb1ea653b353", size = 35798595, upload-time = "2025-10-28T17:37:48.102Z" }, + { url = "https://files.pythonhosted.org/packages/83/42/6644d714c179429fc7196857866f219fef25238319b650bb32dde7bf7a48/scipy-1.16.3-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:da7763f55885045036fabcebd80144b757d3db06ab0861415d1c3b7c69042146", size = 36186269, upload-time = "2025-10-28T17:37:53.72Z" }, + { url = "https://files.pythonhosted.org/packages/ac/70/64b4d7ca92f9cf2e6fc6aaa2eecf80bb9b6b985043a9583f32f8177ea122/scipy-1.16.3-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:ffa6eea95283b2b8079b821dc11f50a17d0571c92b43e2b5b12764dc5f9b285d", size = 38802779, upload-time = "2025-10-28T17:37:59.393Z" }, + { url = "https://files.pythonhosted.org/packages/61/82/8d0e39f62764cce5ffd5284131e109f07cf8955aef9ab8ed4e3aa5e30539/scipy-1.16.3-cp314-cp314t-win_amd64.whl", hash = "sha256:d9f48cafc7ce94cf9b15c6bffdc443a81a27bf7075cf2dcd5c8b40f85d10c4e7", size = 39471128, upload-time = "2025-10-28T17:38:05.259Z" }, + { url = "https://files.pythonhosted.org/packages/64/47/a494741db7280eae6dc033510c319e34d42dd41b7ac0c7ead39354d1a2b5/scipy-1.16.3-cp314-cp314t-win_arm64.whl", hash = "sha256:21d9d6b197227a12dcbf9633320a4e34c6b0e51c57268df255a0942983bac562", size = 26464127, upload-time = "2025-10-28T17:38:11.34Z" }, ] [[package]] @@ -7918,7 +7916,7 @@ dependencies = [ { name = "scikit-learn", version = "1.7.2", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, { name = "scikit-learn", version = "1.8.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "torch" }, { name = "tqdm" }, { name = "transformers" }, @@ -8473,56 +8471,51 @@ wheels = [ [[package]] name = "tomli" -version = "2.4.0" +version = "2.3.0" source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/82/30/31573e9457673ab10aa432461bee537ce6cef177667deca369efb79df071/tomli-2.4.0.tar.gz", hash = "sha256:aa89c3f6c277dd275d8e243ad24f3b5e701491a860d5121f2cdd399fbb31fc9c", size = 17477, upload-time = "2026-01-11T11:22:38.165Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/3c/d9/3dc2289e1f3b32eb19b9785b6a006b28ee99acb37d1d47f78d4c10e28bf8/tomli-2.4.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:b5ef256a3fd497d4973c11bf142e9ed78b150d36f5773f1ca6088c230ffc5867", size = 153663, upload-time = "2026-01-11T11:21:45.27Z" }, - { url = "https://files.pythonhosted.org/packages/51/32/ef9f6845e6b9ca392cd3f64f9ec185cc6f09f0a2df3db08cbe8809d1d435/tomli-2.4.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:5572e41282d5268eb09a697c89a7bee84fae66511f87533a6f88bd2f7b652da9", size = 148469, upload-time = "2026-01-11T11:21:46.873Z" }, - { url = "https://files.pythonhosted.org/packages/d6/c2/506e44cce89a8b1b1e047d64bd495c22c9f71f21e05f380f1a950dd9c217/tomli-2.4.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:551e321c6ba03b55676970b47cb1b73f14a0a4dce6a3e1a9458fd6d921d72e95", size = 236039, upload-time = "2026-01-11T11:21:48.503Z" }, - { url = "https://files.pythonhosted.org/packages/b3/40/e1b65986dbc861b7e986e8ec394598187fa8aee85b1650b01dd925ca0be8/tomli-2.4.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:5e3f639a7a8f10069d0e15408c0b96a2a828cfdec6fca05296ebcdcc28ca7c76", size = 243007, upload-time = "2026-01-11T11:21:49.456Z" }, - { url = "https://files.pythonhosted.org/packages/9c/6f/6e39ce66b58a5b7ae572a0f4352ff40c71e8573633deda43f6a379d56b3e/tomli-2.4.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:1b168f2731796b045128c45982d3a4874057626da0e2ef1fdd722848b741361d", size = 240875, upload-time = "2026-01-11T11:21:50.755Z" }, - { url = "https://files.pythonhosted.org/packages/aa/ad/cb089cb190487caa80204d503c7fd0f4d443f90b95cf4ef5cf5aa0f439b0/tomli-2.4.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:133e93646ec4300d651839d382d63edff11d8978be23da4cc106f5a18b7d0576", size = 246271, upload-time = "2026-01-11T11:21:51.81Z" }, - { url = "https://files.pythonhosted.org/packages/0b/63/69125220e47fd7a3a27fd0de0c6398c89432fec41bc739823bcc66506af6/tomli-2.4.0-cp311-cp311-win32.whl", hash = "sha256:b6c78bdf37764092d369722d9946cb65b8767bfa4110f902a1b2542d8d173c8a", size = 96770, upload-time = "2026-01-11T11:21:52.647Z" }, - { url = "https://files.pythonhosted.org/packages/1e/0d/a22bb6c83f83386b0008425a6cd1fa1c14b5f3dd4bad05e98cf3dbbf4a64/tomli-2.4.0-cp311-cp311-win_amd64.whl", hash = "sha256:d3d1654e11d724760cdb37a3d7691f0be9db5fbdaef59c9f532aabf87006dbaa", size = 107626, upload-time = "2026-01-11T11:21:53.459Z" }, - { url = "https://files.pythonhosted.org/packages/2f/6d/77be674a3485e75cacbf2ddba2b146911477bd887dda9d8c9dfb2f15e871/tomli-2.4.0-cp311-cp311-win_arm64.whl", hash = "sha256:cae9c19ed12d4e8f3ebf46d1a75090e4c0dc16271c5bce1c833ac168f08fb614", size = 94842, upload-time = "2026-01-11T11:21:54.831Z" }, - { url = "https://files.pythonhosted.org/packages/3c/43/7389a1869f2f26dba52404e1ef13b4784b6b37dac93bac53457e3ff24ca3/tomli-2.4.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:920b1de295e72887bafa3ad9f7a792f811847d57ea6b1215154030cf131f16b1", size = 154894, upload-time = "2026-01-11T11:21:56.07Z" }, - { url = "https://files.pythonhosted.org/packages/e9/05/2f9bf110b5294132b2edf13fe6ca6ae456204f3d749f623307cbb7a946f2/tomli-2.4.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:7d6d9a4aee98fac3eab4952ad1d73aee87359452d1c086b5ceb43ed02ddb16b8", size = 149053, upload-time = "2026-01-11T11:21:57.467Z" }, - { url = "https://files.pythonhosted.org/packages/e8/41/1eda3ca1abc6f6154a8db4d714a4d35c4ad90adc0bcf700657291593fbf3/tomli-2.4.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:36b9d05b51e65b254ea6c2585b59d2c4cb91c8a3d91d0ed0f17591a29aaea54a", size = 243481, upload-time = "2026-01-11T11:21:58.661Z" }, - { url = "https://files.pythonhosted.org/packages/d2/6d/02ff5ab6c8868b41e7d4b987ce2b5f6a51d3335a70aa144edd999e055a01/tomli-2.4.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:1c8a885b370751837c029ef9bc014f27d80840e48bac415f3412e6593bbc18c1", size = 251720, upload-time = "2026-01-11T11:22:00.178Z" }, - { url = "https://files.pythonhosted.org/packages/7b/57/0405c59a909c45d5b6f146107c6d997825aa87568b042042f7a9c0afed34/tomli-2.4.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:8768715ffc41f0008abe25d808c20c3d990f42b6e2e58305d5da280ae7d1fa3b", size = 247014, upload-time = "2026-01-11T11:22:01.238Z" }, - { url = "https://files.pythonhosted.org/packages/2c/0e/2e37568edd944b4165735687cbaf2fe3648129e440c26d02223672ee0630/tomli-2.4.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:7b438885858efd5be02a9a133caf5812b8776ee0c969fea02c45e8e3f296ba51", size = 251820, upload-time = "2026-01-11T11:22:02.727Z" }, - { url = "https://files.pythonhosted.org/packages/5a/1c/ee3b707fdac82aeeb92d1a113f803cf6d0f37bdca0849cb489553e1f417a/tomli-2.4.0-cp312-cp312-win32.whl", hash = "sha256:0408e3de5ec77cc7f81960c362543cbbd91ef883e3138e81b729fc3eea5b9729", size = 97712, upload-time = "2026-01-11T11:22:03.777Z" }, - { url = "https://files.pythonhosted.org/packages/69/13/c07a9177d0b3bab7913299b9278845fc6eaaca14a02667c6be0b0a2270c8/tomli-2.4.0-cp312-cp312-win_amd64.whl", hash = "sha256:685306e2cc7da35be4ee914fd34ab801a6acacb061b6a7abca922aaf9ad368da", size = 108296, upload-time = "2026-01-11T11:22:04.86Z" }, - { url = "https://files.pythonhosted.org/packages/18/27/e267a60bbeeee343bcc279bb9e8fbed0cbe224bc7b2a3dc2975f22809a09/tomli-2.4.0-cp312-cp312-win_arm64.whl", hash = "sha256:5aa48d7c2356055feef06a43611fc401a07337d5b006be13a30f6c58f869e3c3", size = 94553, upload-time = "2026-01-11T11:22:05.854Z" }, - { url = "https://files.pythonhosted.org/packages/34/91/7f65f9809f2936e1f4ce6268ae1903074563603b2a2bd969ebbda802744f/tomli-2.4.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:84d081fbc252d1b6a982e1870660e7330fb8f90f676f6e78b052ad4e64714bf0", size = 154915, upload-time = "2026-01-11T11:22:06.703Z" }, - { url = "https://files.pythonhosted.org/packages/20/aa/64dd73a5a849c2e8f216b755599c511badde80e91e9bc2271baa7b2cdbb1/tomli-2.4.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:9a08144fa4cba33db5255f9b74f0b89888622109bd2776148f2597447f92a94e", size = 149038, upload-time = "2026-01-11T11:22:07.56Z" }, - { url = "https://files.pythonhosted.org/packages/9e/8a/6d38870bd3d52c8d1505ce054469a73f73a0fe62c0eaf5dddf61447e32fa/tomli-2.4.0-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c73add4bb52a206fd0c0723432db123c0c75c280cbd67174dd9d2db228ebb1b4", size = 242245, upload-time = "2026-01-11T11:22:08.344Z" }, - { url = "https://files.pythonhosted.org/packages/59/bb/8002fadefb64ab2669e5b977df3f5e444febea60e717e755b38bb7c41029/tomli-2.4.0-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:1fb2945cbe303b1419e2706e711b7113da57b7db31ee378d08712d678a34e51e", size = 250335, upload-time = "2026-01-11T11:22:09.951Z" }, - { url = "https://files.pythonhosted.org/packages/a5/3d/4cdb6f791682b2ea916af2de96121b3cb1284d7c203d97d92d6003e91c8d/tomli-2.4.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:bbb1b10aa643d973366dc2cb1ad94f99c1726a02343d43cbc011edbfac579e7c", size = 245962, upload-time = "2026-01-11T11:22:11.27Z" }, - { url = "https://files.pythonhosted.org/packages/f2/4a/5f25789f9a460bd858ba9756ff52d0830d825b458e13f754952dd15fb7bb/tomli-2.4.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:4cbcb367d44a1f0c2be408758b43e1ffb5308abe0ea222897d6bfc8e8281ef2f", size = 250396, upload-time = "2026-01-11T11:22:12.325Z" }, - { url = "https://files.pythonhosted.org/packages/aa/2f/b73a36fea58dfa08e8b3a268750e6853a6aac2a349241a905ebd86f3047a/tomli-2.4.0-cp313-cp313-win32.whl", hash = "sha256:7d49c66a7d5e56ac959cb6fc583aff0651094ec071ba9ad43df785abc2320d86", size = 97530, upload-time = "2026-01-11T11:22:13.865Z" }, - { url = "https://files.pythonhosted.org/packages/3b/af/ca18c134b5d75de7e8dc551c5234eaba2e8e951f6b30139599b53de9c187/tomli-2.4.0-cp313-cp313-win_amd64.whl", hash = "sha256:3cf226acb51d8f1c394c1b310e0e0e61fecdd7adcb78d01e294ac297dd2e7f87", size = 108227, upload-time = "2026-01-11T11:22:15.224Z" }, - { url = "https://files.pythonhosted.org/packages/22/c3/b386b832f209fee8073c8138ec50f27b4460db2fdae9ffe022df89a57f9b/tomli-2.4.0-cp313-cp313-win_arm64.whl", hash = "sha256:d20b797a5c1ad80c516e41bc1fb0443ddb5006e9aaa7bda2d71978346aeb9132", size = 94748, upload-time = "2026-01-11T11:22:16.009Z" }, - { url = "https://files.pythonhosted.org/packages/f3/c4/84047a97eb1004418bc10bdbcfebda209fca6338002eba2dc27cc6d13563/tomli-2.4.0-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:26ab906a1eb794cd4e103691daa23d95c6919cc2fa9160000ac02370cc9dd3f6", size = 154725, upload-time = "2026-01-11T11:22:17.269Z" }, - { url = "https://files.pythonhosted.org/packages/a8/5d/d39038e646060b9d76274078cddf146ced86dc2b9e8bbf737ad5983609a0/tomli-2.4.0-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:20cedb4ee43278bc4f2fee6cb50daec836959aadaf948db5172e776dd3d993fc", size = 148901, upload-time = "2026-01-11T11:22:18.287Z" }, - { url = "https://files.pythonhosted.org/packages/73/e5/383be1724cb30f4ce44983d249645684a48c435e1cd4f8b5cded8a816d3c/tomli-2.4.0-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:39b0b5d1b6dd03684b3fb276407ebed7090bbec989fa55838c98560c01113b66", size = 243375, upload-time = "2026-01-11T11:22:19.154Z" }, - { url = "https://files.pythonhosted.org/packages/31/f0/bea80c17971c8d16d3cc109dc3585b0f2ce1036b5f4a8a183789023574f2/tomli-2.4.0-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a26d7ff68dfdb9f87a016ecfd1e1c2bacbe3108f4e0f8bcd2228ef9a766c787d", size = 250639, upload-time = "2026-01-11T11:22:20.168Z" }, - { url = "https://files.pythonhosted.org/packages/2c/8f/2853c36abbb7608e3f945d8a74e32ed3a74ee3a1f468f1ffc7d1cb3abba6/tomli-2.4.0-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:20ffd184fb1df76a66e34bd1b36b4a4641bd2b82954befa32fe8163e79f1a702", size = 246897, upload-time = "2026-01-11T11:22:21.544Z" }, - { url = "https://files.pythonhosted.org/packages/49/f0/6c05e3196ed5337b9fe7ea003e95fd3819a840b7a0f2bf5a408ef1dad8ed/tomli-2.4.0-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:75c2f8bbddf170e8effc98f5e9084a8751f8174ea6ccf4fca5398436e0320bc8", size = 254697, upload-time = "2026-01-11T11:22:23.058Z" }, - { url = "https://files.pythonhosted.org/packages/f3/f5/2922ef29c9f2951883525def7429967fc4d8208494e5ab524234f06b688b/tomli-2.4.0-cp314-cp314-win32.whl", hash = "sha256:31d556d079d72db7c584c0627ff3a24c5d3fb4f730221d3444f3efb1b2514776", size = 98567, upload-time = "2026-01-11T11:22:24.033Z" }, - { url = "https://files.pythonhosted.org/packages/7b/31/22b52e2e06dd2a5fdbc3ee73226d763b184ff21fc24e20316a44ccc4d96b/tomli-2.4.0-cp314-cp314-win_amd64.whl", hash = "sha256:43e685b9b2341681907759cf3a04e14d7104b3580f808cfde1dfdb60ada85475", size = 108556, upload-time = "2026-01-11T11:22:25.378Z" }, - { url = "https://files.pythonhosted.org/packages/48/3d/5058dff3255a3d01b705413f64f4306a141a8fd7a251e5a495e3f192a998/tomli-2.4.0-cp314-cp314-win_arm64.whl", hash = "sha256:3d895d56bd3f82ddd6faaff993c275efc2ff38e52322ea264122d72729dca2b2", size = 96014, upload-time = "2026-01-11T11:22:26.138Z" }, - { url = "https://files.pythonhosted.org/packages/b8/4e/75dab8586e268424202d3a1997ef6014919c941b50642a1682df43204c22/tomli-2.4.0-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:5b5807f3999fb66776dbce568cc9a828544244a8eb84b84b9bafc080c99597b9", size = 163339, upload-time = "2026-01-11T11:22:27.143Z" }, - { url = "https://files.pythonhosted.org/packages/06/e3/b904d9ab1016829a776d97f163f183a48be6a4deb87304d1e0116a349519/tomli-2.4.0-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:c084ad935abe686bd9c898e62a02a19abfc9760b5a79bc29644463eaf2840cb0", size = 159490, upload-time = "2026-01-11T11:22:28.399Z" }, - { url = "https://files.pythonhosted.org/packages/e3/5a/fc3622c8b1ad823e8ea98a35e3c632ee316d48f66f80f9708ceb4f2a0322/tomli-2.4.0-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0f2e3955efea4d1cfbcb87bc321e00dc08d2bcb737fd1d5e398af111d86db5df", size = 269398, upload-time = "2026-01-11T11:22:29.345Z" }, - { url = "https://files.pythonhosted.org/packages/fd/33/62bd6152c8bdd4c305ad9faca48f51d3acb2df1f8791b1477d46ff86e7f8/tomli-2.4.0-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:0e0fe8a0b8312acf3a88077a0802565cb09ee34107813bba1c7cd591fa6cfc8d", size = 276515, upload-time = "2026-01-11T11:22:30.327Z" }, - { url = "https://files.pythonhosted.org/packages/4b/ff/ae53619499f5235ee4211e62a8d7982ba9e439a0fb4f2f351a93d67c1dd2/tomli-2.4.0-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:413540dce94673591859c4c6f794dfeaa845e98bf35d72ed59636f869ef9f86f", size = 273806, upload-time = "2026-01-11T11:22:32.56Z" }, - { url = "https://files.pythonhosted.org/packages/47/71/cbca7787fa68d4d0a9f7072821980b39fbb1b6faeb5f5cf02f4a5559fa28/tomli-2.4.0-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:0dc56fef0e2c1c470aeac5b6ca8cc7b640bb93e92d9803ddaf9ea03e198f5b0b", size = 281340, upload-time = "2026-01-11T11:22:33.505Z" }, - { url = "https://files.pythonhosted.org/packages/f5/00/d595c120963ad42474cf6ee7771ad0d0e8a49d0f01e29576ee9195d9ecdf/tomli-2.4.0-cp314-cp314t-win32.whl", hash = "sha256:d878f2a6707cc9d53a1be1414bbb419e629c3d6e67f69230217bb663e76b5087", size = 108106, upload-time = "2026-01-11T11:22:34.451Z" }, - { url = "https://files.pythonhosted.org/packages/de/69/9aa0c6a505c2f80e519b43764f8b4ba93b5a0bbd2d9a9de6e2b24271b9a5/tomli-2.4.0-cp314-cp314t-win_amd64.whl", hash = "sha256:2add28aacc7425117ff6364fe9e06a183bb0251b03f986df0e78e974047571fd", size = 120504, upload-time = "2026-01-11T11:22:35.764Z" }, - { url = "https://files.pythonhosted.org/packages/b3/9f/f1668c281c58cfae01482f7114a4b88d345e4c140386241a1a24dcc9e7bc/tomli-2.4.0-cp314-cp314t-win_arm64.whl", hash = "sha256:2b1e3b80e1d5e52e40e9b924ec43d81570f0e7d09d11081b797bc4692765a3d4", size = 99561, upload-time = "2026-01-11T11:22:36.624Z" }, - { url = "https://files.pythonhosted.org/packages/23/d1/136eb2cb77520a31e1f64cbae9d33ec6df0d78bdf4160398e86eec8a8754/tomli-2.4.0-py3-none-any.whl", hash = "sha256:1f776e7d669ebceb01dee46484485f43a4048746235e683bcdffacdf1fb4785a", size = 14477, upload-time = "2026-01-11T11:22:37.446Z" }, +sdist = { url = "https://files.pythonhosted.org/packages/52/ed/3f73f72945444548f33eba9a87fc7a6e969915e7b1acc8260b30e1f76a2f/tomli-2.3.0.tar.gz", hash = "sha256:64be704a875d2a59753d80ee8a533c3fe183e3f06807ff7dc2232938ccb01549", size = 17392, upload-time = "2025-10-08T22:01:47.119Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/b3/2e/299f62b401438d5fe1624119c723f5d877acc86a4c2492da405626665f12/tomli-2.3.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:88bd15eb972f3664f5ed4b57c1634a97153b4bac4479dcb6a495f41921eb7f45", size = 153236, upload-time = "2025-10-08T22:01:00.137Z" }, + { url = "https://files.pythonhosted.org/packages/86/7f/d8fffe6a7aefdb61bced88fcb5e280cfd71e08939da5894161bd71bea022/tomli-2.3.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:883b1c0d6398a6a9d29b508c331fa56adbcdff647f6ace4dfca0f50e90dfd0ba", size = 148084, upload-time = "2025-10-08T22:01:01.63Z" }, + { url = "https://files.pythonhosted.org/packages/47/5c/24935fb6a2ee63e86d80e4d3b58b222dafaf438c416752c8b58537c8b89a/tomli-2.3.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:d1381caf13ab9f300e30dd8feadb3de072aeb86f1d34a8569453ff32a7dea4bf", size = 234832, upload-time = "2025-10-08T22:01:02.543Z" }, + { url = "https://files.pythonhosted.org/packages/89/da/75dfd804fc11e6612846758a23f13271b76d577e299592b4371a4ca4cd09/tomli-2.3.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a0e285d2649b78c0d9027570d4da3425bdb49830a6156121360b3f8511ea3441", size = 242052, upload-time = "2025-10-08T22:01:03.836Z" }, + { url = "https://files.pythonhosted.org/packages/70/8c/f48ac899f7b3ca7eb13af73bacbc93aec37f9c954df3c08ad96991c8c373/tomli-2.3.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:0a154a9ae14bfcf5d8917a59b51ffd5a3ac1fd149b71b47a3a104ca4edcfa845", size = 239555, upload-time = "2025-10-08T22:01:04.834Z" }, + { url = "https://files.pythonhosted.org/packages/ba/28/72f8afd73f1d0e7829bfc093f4cb98ce0a40ffc0cc997009ee1ed94ba705/tomli-2.3.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:74bf8464ff93e413514fefd2be591c3b0b23231a77f901db1eb30d6f712fc42c", size = 245128, upload-time = "2025-10-08T22:01:05.84Z" }, + { url = "https://files.pythonhosted.org/packages/b6/eb/a7679c8ac85208706d27436e8d421dfa39d4c914dcf5fa8083a9305f58d9/tomli-2.3.0-cp311-cp311-win32.whl", hash = "sha256:00b5f5d95bbfc7d12f91ad8c593a1659b6387b43f054104cda404be6bda62456", size = 96445, upload-time = "2025-10-08T22:01:06.896Z" }, + { url = "https://files.pythonhosted.org/packages/0a/fe/3d3420c4cb1ad9cb462fb52967080575f15898da97e21cb6f1361d505383/tomli-2.3.0-cp311-cp311-win_amd64.whl", hash = "sha256:4dc4ce8483a5d429ab602f111a93a6ab1ed425eae3122032db7e9acf449451be", size = 107165, upload-time = "2025-10-08T22:01:08.107Z" }, + { url = "https://files.pythonhosted.org/packages/ff/b7/40f36368fcabc518bb11c8f06379a0fd631985046c038aca08c6d6a43c6e/tomli-2.3.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:d7d86942e56ded512a594786a5ba0a5e521d02529b3826e7761a05138341a2ac", size = 154891, upload-time = "2025-10-08T22:01:09.082Z" }, + { url = "https://files.pythonhosted.org/packages/f9/3f/d9dd692199e3b3aab2e4e4dd948abd0f790d9ded8cd10cbaae276a898434/tomli-2.3.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:73ee0b47d4dad1c5e996e3cd33b8a76a50167ae5f96a2607cbe8cc773506ab22", size = 148796, upload-time = "2025-10-08T22:01:10.266Z" }, + { url = "https://files.pythonhosted.org/packages/60/83/59bff4996c2cf9f9387a0f5a3394629c7efa5ef16142076a23a90f1955fa/tomli-2.3.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:792262b94d5d0a466afb5bc63c7daa9d75520110971ee269152083270998316f", size = 242121, upload-time = "2025-10-08T22:01:11.332Z" }, + { url = "https://files.pythonhosted.org/packages/45/e5/7c5119ff39de8693d6baab6c0b6dcb556d192c165596e9fc231ea1052041/tomli-2.3.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:4f195fe57ecceac95a66a75ac24d9d5fbc98ef0962e09b2eddec5d39375aae52", size = 250070, upload-time = "2025-10-08T22:01:12.498Z" }, + { url = "https://files.pythonhosted.org/packages/45/12/ad5126d3a278f27e6701abde51d342aa78d06e27ce2bb596a01f7709a5a2/tomli-2.3.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:e31d432427dcbf4d86958c184b9bfd1e96b5b71f8eb17e6d02531f434fd335b8", size = 245859, upload-time = "2025-10-08T22:01:13.551Z" }, + { url = "https://files.pythonhosted.org/packages/fb/a1/4d6865da6a71c603cfe6ad0e6556c73c76548557a8d658f9e3b142df245f/tomli-2.3.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:7b0882799624980785240ab732537fcfc372601015c00f7fc367c55308c186f6", size = 250296, upload-time = "2025-10-08T22:01:14.614Z" }, + { url = "https://files.pythonhosted.org/packages/a0/b7/a7a7042715d55c9ba6e8b196d65d2cb662578b4d8cd17d882d45322b0d78/tomli-2.3.0-cp312-cp312-win32.whl", hash = "sha256:ff72b71b5d10d22ecb084d345fc26f42b5143c5533db5e2eaba7d2d335358876", size = 97124, upload-time = "2025-10-08T22:01:15.629Z" }, + { url = "https://files.pythonhosted.org/packages/06/1e/f22f100db15a68b520664eb3328fb0ae4e90530887928558112c8d1f4515/tomli-2.3.0-cp312-cp312-win_amd64.whl", hash = "sha256:1cb4ed918939151a03f33d4242ccd0aa5f11b3547d0cf30f7c74a408a5b99878", size = 107698, upload-time = "2025-10-08T22:01:16.51Z" }, + { url = "https://files.pythonhosted.org/packages/89/48/06ee6eabe4fdd9ecd48bf488f4ac783844fd777f547b8d1b61c11939974e/tomli-2.3.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:5192f562738228945d7b13d4930baffda67b69425a7f0da96d360b0a3888136b", size = 154819, upload-time = "2025-10-08T22:01:17.964Z" }, + { url = "https://files.pythonhosted.org/packages/f1/01/88793757d54d8937015c75dcdfb673c65471945f6be98e6a0410fba167ed/tomli-2.3.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:be71c93a63d738597996be9528f4abe628d1adf5e6eb11607bc8fe1a510b5dae", size = 148766, upload-time = "2025-10-08T22:01:18.959Z" }, + { url = "https://files.pythonhosted.org/packages/42/17/5e2c956f0144b812e7e107f94f1cc54af734eb17b5191c0bbfb72de5e93e/tomli-2.3.0-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c4665508bcbac83a31ff8ab08f424b665200c0e1e645d2bd9ab3d3e557b6185b", size = 240771, upload-time = "2025-10-08T22:01:20.106Z" }, + { url = "https://files.pythonhosted.org/packages/d5/f4/0fbd014909748706c01d16824eadb0307115f9562a15cbb012cd9b3512c5/tomli-2.3.0-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:4021923f97266babc6ccab9f5068642a0095faa0a51a246a6a02fccbb3514eaf", size = 248586, upload-time = "2025-10-08T22:01:21.164Z" }, + { url = "https://files.pythonhosted.org/packages/30/77/fed85e114bde5e81ecf9bc5da0cc69f2914b38f4708c80ae67d0c10180c5/tomli-2.3.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:a4ea38c40145a357d513bffad0ed869f13c1773716cf71ccaa83b0fa0cc4e42f", size = 244792, upload-time = "2025-10-08T22:01:22.417Z" }, + { url = "https://files.pythonhosted.org/packages/55/92/afed3d497f7c186dc71e6ee6d4fcb0acfa5f7d0a1a2878f8beae379ae0cc/tomli-2.3.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:ad805ea85eda330dbad64c7ea7a4556259665bdf9d2672f5dccc740eb9d3ca05", size = 248909, upload-time = "2025-10-08T22:01:23.859Z" }, + { url = "https://files.pythonhosted.org/packages/f8/84/ef50c51b5a9472e7265ce1ffc7f24cd4023d289e109f669bdb1553f6a7c2/tomli-2.3.0-cp313-cp313-win32.whl", hash = "sha256:97d5eec30149fd3294270e889b4234023f2c69747e555a27bd708828353ab606", size = 96946, upload-time = "2025-10-08T22:01:24.893Z" }, + { url = "https://files.pythonhosted.org/packages/b2/b7/718cd1da0884f281f95ccfa3a6cc572d30053cba64603f79d431d3c9b61b/tomli-2.3.0-cp313-cp313-win_amd64.whl", hash = "sha256:0c95ca56fbe89e065c6ead5b593ee64b84a26fca063b5d71a1122bf26e533999", size = 107705, upload-time = "2025-10-08T22:01:26.153Z" }, + { url = "https://files.pythonhosted.org/packages/19/94/aeafa14a52e16163008060506fcb6aa1949d13548d13752171a755c65611/tomli-2.3.0-cp314-cp314-macosx_10_13_x86_64.whl", hash = "sha256:cebc6fe843e0733ee827a282aca4999b596241195f43b4cc371d64fc6639da9e", size = 154244, upload-time = "2025-10-08T22:01:27.06Z" }, + { url = "https://files.pythonhosted.org/packages/db/e4/1e58409aa78eefa47ccd19779fc6f36787edbe7d4cd330eeeedb33a4515b/tomli-2.3.0-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:4c2ef0244c75aba9355561272009d934953817c49f47d768070c3c94355c2aa3", size = 148637, upload-time = "2025-10-08T22:01:28.059Z" }, + { url = "https://files.pythonhosted.org/packages/26/b6/d1eccb62f665e44359226811064596dd6a366ea1f985839c566cd61525ae/tomli-2.3.0-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c22a8bf253bacc0cf11f35ad9808b6cb75ada2631c2d97c971122583b129afbc", size = 241925, upload-time = "2025-10-08T22:01:29.066Z" }, + { url = "https://files.pythonhosted.org/packages/70/91/7cdab9a03e6d3d2bb11beae108da5bdc1c34bdeb06e21163482544ddcc90/tomli-2.3.0-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:0eea8cc5c5e9f89c9b90c4896a8deefc74f518db5927d0e0e8d4a80953d774d0", size = 249045, upload-time = "2025-10-08T22:01:31.98Z" }, + { url = "https://files.pythonhosted.org/packages/15/1b/8c26874ed1f6e4f1fcfeb868db8a794cbe9f227299402db58cfcc858766c/tomli-2.3.0-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:b74a0e59ec5d15127acdabd75ea17726ac4c5178ae51b85bfe39c4f8a278e879", size = 245835, upload-time = "2025-10-08T22:01:32.989Z" }, + { url = "https://files.pythonhosted.org/packages/fd/42/8e3c6a9a4b1a1360c1a2a39f0b972cef2cc9ebd56025168c4137192a9321/tomli-2.3.0-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:b5870b50c9db823c595983571d1296a6ff3e1b88f734a4c8f6fc6188397de005", size = 253109, upload-time = "2025-10-08T22:01:34.052Z" }, + { url = "https://files.pythonhosted.org/packages/22/0c/b4da635000a71b5f80130937eeac12e686eefb376b8dee113b4a582bba42/tomli-2.3.0-cp314-cp314-win32.whl", hash = "sha256:feb0dacc61170ed7ab602d3d972a58f14ee3ee60494292d384649a3dc38ef463", size = 97930, upload-time = "2025-10-08T22:01:35.082Z" }, + { url = "https://files.pythonhosted.org/packages/b9/74/cb1abc870a418ae99cd5c9547d6bce30701a954e0e721821df483ef7223c/tomli-2.3.0-cp314-cp314-win_amd64.whl", hash = "sha256:b273fcbd7fc64dc3600c098e39136522650c49bca95df2d11cf3b626422392c8", size = 107964, upload-time = "2025-10-08T22:01:36.057Z" }, + { url = "https://files.pythonhosted.org/packages/54/78/5c46fff6432a712af9f792944f4fcd7067d8823157949f4e40c56b8b3c83/tomli-2.3.0-cp314-cp314t-macosx_10_13_x86_64.whl", hash = "sha256:940d56ee0410fa17ee1f12b817b37a4d4e4dc4d27340863cc67236c74f582e77", size = 163065, upload-time = "2025-10-08T22:01:37.27Z" }, + { url = "https://files.pythonhosted.org/packages/39/67/f85d9bd23182f45eca8939cd2bc7050e1f90c41f4a2ecbbd5963a1d1c486/tomli-2.3.0-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:f85209946d1fe94416debbb88d00eb92ce9cd5266775424ff81bc959e001acaf", size = 159088, upload-time = "2025-10-08T22:01:38.235Z" }, + { url = "https://files.pythonhosted.org/packages/26/5a/4b546a0405b9cc0659b399f12b6adb750757baf04250b148d3c5059fc4eb/tomli-2.3.0-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:a56212bdcce682e56b0aaf79e869ba5d15a6163f88d5451cbde388d48b13f530", size = 268193, upload-time = "2025-10-08T22:01:39.712Z" }, + { url = "https://files.pythonhosted.org/packages/42/4f/2c12a72ae22cf7b59a7fe75b3465b7aba40ea9145d026ba41cb382075b0e/tomli-2.3.0-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:c5f3ffd1e098dfc032d4d3af5c0ac64f6d286d98bc148698356847b80fa4de1b", size = 275488, upload-time = "2025-10-08T22:01:40.773Z" }, + { url = "https://files.pythonhosted.org/packages/92/04/a038d65dbe160c3aa5a624e93ad98111090f6804027d474ba9c37c8ae186/tomli-2.3.0-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:5e01decd096b1530d97d5d85cb4dff4af2d8347bd35686654a004f8dea20fc67", size = 272669, upload-time = "2025-10-08T22:01:41.824Z" }, + { url = "https://files.pythonhosted.org/packages/be/2f/8b7c60a9d1612a7cbc39ffcca4f21a73bf368a80fc25bccf8253e2563267/tomli-2.3.0-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:8a35dd0e643bb2610f156cca8db95d213a90015c11fee76c946aa62b7ae7e02f", size = 279709, upload-time = "2025-10-08T22:01:43.177Z" }, + { url = "https://files.pythonhosted.org/packages/7e/46/cc36c679f09f27ded940281c38607716c86cf8ba4a518d524e349c8b4874/tomli-2.3.0-cp314-cp314t-win32.whl", hash = "sha256:a1f7f282fe248311650081faafa5f4732bdbfef5d45fe3f2e702fbc6f2d496e0", size = 107563, upload-time = "2025-10-08T22:01:44.233Z" }, + { url = "https://files.pythonhosted.org/packages/84/ff/426ca8683cf7b753614480484f6437f568fd2fda2edbdf57a2d3d8b27a0b/tomli-2.3.0-cp314-cp314t-win_amd64.whl", hash = "sha256:70a251f8d4ba2d9ac2542eecf008b3c8a9fc5c3f9f02c56a9d7952612be2fdba", size = 119756, upload-time = "2025-10-08T22:01:45.234Z" }, + { url = "https://files.pythonhosted.org/packages/77/b8/0135fadc89e73be292b473cb820b4f5a08197779206b33191e801feeae40/tomli-2.3.0-py3-none-any.whl", hash = "sha256:e95b1af3c5b07d9e643909b5abbec77cd9f1217e6d0bca72b0234736b9fb1f1b", size = 14408, upload-time = "2025-10-08T22:01:46.04Z" }, ] [[package]] @@ -8828,14 +8821,14 @@ wheels = [ [[package]] name = "types-jsonschema" -version = "4.26.0.20260109" +version = "4.25.1.20251009" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "referencing" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/04/03/a1509b0c13fc7a1fca1494c84bde8cce8a5c0582b6255b9640ebd3034017/types_jsonschema-4.26.0.20260109.tar.gz", hash = "sha256:340fe91e6ea517900d6ababb6262a86c176473b5bf8455b96e85a89e3cfb5daa", size = 15886, upload-time = "2026-01-09T03:21:45.464Z" } +sdist = { url = "https://files.pythonhosted.org/packages/ef/da/5b901088da5f710690b422137e8ae74197fb1ca471e4aa84dd3ef0d6e295/types_jsonschema-4.25.1.20251009.tar.gz", hash = "sha256:75d0f5c5dd18dc23b664437a0c1a625743e8d2e665ceaf3aecb29841f3a5f97f", size = 15661, upload-time = "2025-10-09T02:54:36.963Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/2f/d6/3db3134f35f1e4bf9a13517d759c1ae64086eddb8ad0047caee140021e64/types_jsonschema-4.26.0.20260109-py3-none-any.whl", hash = "sha256:e0276640d228732fb75d883905d607359b24a4ff745ba7f9a5f50e6fda891926", size = 15923, upload-time = "2026-01-09T03:21:43.828Z" }, + { url = "https://files.pythonhosted.org/packages/7f/6a/e5146754c0dfc272f176db9c245bc43cc19030262d891a5a85d472797e60/types_jsonschema-4.25.1.20251009-py3-none-any.whl", hash = "sha256:f30b329037b78e7a60146b1146feb0b6fb0b71628637584409bada83968dad3e", size = 15925, upload-time = "2025-10-09T02:54:35.847Z" }, ] [[package]] @@ -8994,7 +8987,7 @@ wheels = [ [[package]] name = "ultralytics" -version = "8.3.252" +version = "8.3.250" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "matplotlib" }, @@ -9007,14 +9000,14 @@ dependencies = [ { name = "pyyaml" }, { name = "requests" }, { name = "scipy", version = "1.15.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "scipy", version = "1.17.0", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "scipy", version = "1.16.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, { name = "torch" }, { name = "torchvision" }, { name = "ultralytics-thop" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/d9/6e/77cbcc445edfc51e9e5278f52757625ec57455a4ef163ea698f827521a6c/ultralytics-8.3.252.tar.gz", hash = "sha256:0973d55c84e77bc729d49217da183914401954cb61e8c0ff059082963d88fa73", size = 993056, upload-time = "2026-01-10T16:36:12.307Z" } +sdist = { url = "https://files.pythonhosted.org/packages/d7/80/b59ee8aac9b46f0cd933a571d10925a7ce9def0d41dc9ddba335143bf520/ultralytics-8.3.250.tar.gz", hash = "sha256:af1a99afbfc23d8c888811bebe7930b0bdc2ae7a2f71ee9f412b77568bfc0297", size = 992533, upload-time = "2026-01-08T18:48:38.45Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/57/2c/84f61b8fd8a594c2c3e54560575af2580da17d4647de7bc1ca7c55bf37f6/ultralytics-8.3.252-py3-none-any.whl", hash = "sha256:7b30f8fd5ac03e6bf91a2bf8e27e20814d7e8efad431cd6cd25c7b950c397ccc", size = 1157267, upload-time = "2026-01-10T16:36:07.876Z" }, + { url = "https://files.pythonhosted.org/packages/cb/7e/17af4263d4e139a0153bdf60b590ecad079df992545af35ea356a602548a/ultralytics-8.3.250-py3-none-any.whl", hash = "sha256:3578a10095b54b8707c622ad15588140eb5bcf4ff99629cff544faa04b39b7b3", size = 1156491, upload-time = "2026-01-08T18:48:35.335Z" }, ] [[package]] @@ -9164,7 +9157,7 @@ wheels = [ [[package]] name = "virtualenv" -version = "20.36.1" +version = "20.36.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "distlib" }, @@ -9172,9 +9165,9 @@ dependencies = [ { name = "platformdirs" }, { name = "typing-extensions", marker = "python_full_version < '3.11'" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/aa/a3/4d310fa5f00863544e1d0f4de93bddec248499ccf97d4791bc3122c9d4f3/virtualenv-20.36.1.tar.gz", hash = "sha256:8befb5c81842c641f8ee658481e42641c68b5eab3521d8e092d18320902466ba", size = 6032239, upload-time = "2026-01-09T18:21:01.296Z" } +sdist = { url = "https://files.pythonhosted.org/packages/78/49/87e23d8f742f10f965bce5d6b285fc88a4f436b11daf6b6225d4d66f8492/virtualenv-20.36.0.tar.gz", hash = "sha256:a3601f540b515a7983508113f14e78993841adc3d83710fa70f0ac50f43b23ed", size = 6032237, upload-time = "2026-01-07T17:20:04.975Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/6a/2a/dc2228b2888f51192c7dc766106cd475f1b768c10caaf9727659726f7391/virtualenv-20.36.1-py3-none-any.whl", hash = "sha256:575a8d6b124ef88f6f51d56d656132389f961062a9177016a50e4f507bbcc19f", size = 6008258, upload-time = "2026-01-09T18:20:59.425Z" }, + { url = "https://files.pythonhosted.org/packages/eb/6a/0af36875e0023a1f2d0b66b4051721fc26740e947696922df1665b75e5d3/virtualenv-20.36.0-py3-none-any.whl", hash = "sha256:e7ded577f3af534fd0886d4ca03277f5542053bedb98a70a989d3c22cfa5c9ac", size = 6008261, upload-time = "2026-01-07T17:20:02.87Z" }, ] [[package]] @@ -9366,70 +9359,61 @@ wheels = [ [[package]] name = "websockets" -version = "16.0" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/04/24/4b2031d72e840ce4c1ccb255f693b15c334757fc50023e4db9537080b8c4/websockets-16.0.tar.gz", hash = "sha256:5f6261a5e56e8d5c42a4497b364ea24d94d9563e8fbd44e78ac40879c60179b5", size = 179346, upload-time = "2026-01-10T09:23:47.181Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/20/74/221f58decd852f4b59cc3354cccaf87e8ef695fede361d03dc9a7396573b/websockets-16.0-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:04cdd5d2d1dacbad0a7bf36ccbcd3ccd5a30ee188f2560b7a62a30d14107b31a", size = 177343, upload-time = "2026-01-10T09:22:21.28Z" }, - { url = "https://files.pythonhosted.org/packages/19/0f/22ef6107ee52ab7f0b710d55d36f5a5d3ef19e8a205541a6d7ffa7994e5a/websockets-16.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:8ff32bb86522a9e5e31439a58addbb0166f0204d64066fb955265c4e214160f0", size = 175021, upload-time = "2026-01-10T09:22:22.696Z" }, - { url = "https://files.pythonhosted.org/packages/10/40/904a4cb30d9b61c0e278899bf36342e9b0208eb3c470324a9ecbaac2a30f/websockets-16.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:583b7c42688636f930688d712885cf1531326ee05effd982028212ccc13e5957", size = 175320, upload-time = "2026-01-10T09:22:23.94Z" }, - { url = "https://files.pythonhosted.org/packages/9d/2f/4b3ca7e106bc608744b1cdae041e005e446124bebb037b18799c2d356864/websockets-16.0-cp310-cp310-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:7d837379b647c0c4c2355c2499723f82f1635fd2c26510e1f587d89bc2199e72", size = 183815, upload-time = "2026-01-10T09:22:25.469Z" }, - { url = "https://files.pythonhosted.org/packages/86/26/d40eaa2a46d4302becec8d15b0fc5e45bdde05191e7628405a19cf491ccd/websockets-16.0-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:df57afc692e517a85e65b72e165356ed1df12386ecb879ad5693be08fac65dde", size = 185054, upload-time = "2026-01-10T09:22:27.101Z" }, - { url = "https://files.pythonhosted.org/packages/b0/ba/6500a0efc94f7373ee8fefa8c271acdfd4dca8bd49a90d4be7ccabfc397e/websockets-16.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:2b9f1e0d69bc60a4a87349d50c09a037a2607918746f07de04df9e43252c77a3", size = 184565, upload-time = "2026-01-10T09:22:28.293Z" }, - { url = "https://files.pythonhosted.org/packages/04/b4/96bf2cee7c8d8102389374a2616200574f5f01128d1082f44102140344cc/websockets-16.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:335c23addf3d5e6a8633f9f8eda77efad001671e80b95c491dd0924587ece0b3", size = 183848, upload-time = "2026-01-10T09:22:30.394Z" }, - { url = "https://files.pythonhosted.org/packages/02/8e/81f40fb00fd125357814e8c3025738fc4ffc3da4b6b4a4472a82ba304b41/websockets-16.0-cp310-cp310-win32.whl", hash = "sha256:37b31c1623c6605e4c00d466c9d633f9b812ea430c11c8a278774a1fde1acfa9", size = 178249, upload-time = "2026-01-10T09:22:32.083Z" }, - { url = "https://files.pythonhosted.org/packages/b4/5f/7e40efe8df57db9b91c88a43690ac66f7b7aa73a11aa6a66b927e44f26fa/websockets-16.0-cp310-cp310-win_amd64.whl", hash = "sha256:8e1dab317b6e77424356e11e99a432b7cb2f3ec8c5ab4dabbcee6add48f72b35", size = 178685, upload-time = "2026-01-10T09:22:33.345Z" }, - { url = "https://files.pythonhosted.org/packages/f2/db/de907251b4ff46ae804ad0409809504153b3f30984daf82a1d84a9875830/websockets-16.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:31a52addea25187bde0797a97d6fc3d2f92b6f72a9370792d65a6e84615ac8a8", size = 177340, upload-time = "2026-01-10T09:22:34.539Z" }, - { url = "https://files.pythonhosted.org/packages/f3/fa/abe89019d8d8815c8781e90d697dec52523fb8ebe308bf11664e8de1877e/websockets-16.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:417b28978cdccab24f46400586d128366313e8a96312e4b9362a4af504f3bbad", size = 175022, upload-time = "2026-01-10T09:22:36.332Z" }, - { url = "https://files.pythonhosted.org/packages/58/5d/88ea17ed1ded2079358b40d31d48abe90a73c9e5819dbcde1606e991e2ad/websockets-16.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:af80d74d4edfa3cb9ed973a0a5ba2b2a549371f8a741e0800cb07becdd20f23d", size = 175319, upload-time = "2026-01-10T09:22:37.602Z" }, - { url = "https://files.pythonhosted.org/packages/d2/ae/0ee92b33087a33632f37a635e11e1d99d429d3d323329675a6022312aac2/websockets-16.0-cp311-cp311-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:08d7af67b64d29823fed316505a89b86705f2b7981c07848fb5e3ea3020c1abe", size = 184631, upload-time = "2026-01-10T09:22:38.789Z" }, - { url = "https://files.pythonhosted.org/packages/c8/c5/27178df583b6c5b31b29f526ba2da5e2f864ecc79c99dae630a85d68c304/websockets-16.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:7be95cfb0a4dae143eaed2bcba8ac23f4892d8971311f1b06f3c6b78952ee70b", size = 185870, upload-time = "2026-01-10T09:22:39.893Z" }, - { url = "https://files.pythonhosted.org/packages/87/05/536652aa84ddc1c018dbb7e2c4cbcd0db884580bf8e95aece7593fde526f/websockets-16.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:d6297ce39ce5c2e6feb13c1a996a2ded3b6832155fcfc920265c76f24c7cceb5", size = 185361, upload-time = "2026-01-10T09:22:41.016Z" }, - { url = "https://files.pythonhosted.org/packages/6d/e2/d5332c90da12b1e01f06fb1b85c50cfc489783076547415bf9f0a659ec19/websockets-16.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:1c1b30e4f497b0b354057f3467f56244c603a79c0d1dafce1d16c283c25f6e64", size = 184615, upload-time = "2026-01-10T09:22:42.442Z" }, - { url = "https://files.pythonhosted.org/packages/77/fb/d3f9576691cae9253b51555f841bc6600bf0a983a461c79500ace5a5b364/websockets-16.0-cp311-cp311-win32.whl", hash = "sha256:5f451484aeb5cafee1ccf789b1b66f535409d038c56966d6101740c1614b86c6", size = 178246, upload-time = "2026-01-10T09:22:43.654Z" }, - { url = "https://files.pythonhosted.org/packages/54/67/eaff76b3dbaf18dcddabc3b8c1dba50b483761cccff67793897945b37408/websockets-16.0-cp311-cp311-win_amd64.whl", hash = "sha256:8d7f0659570eefb578dacde98e24fb60af35350193e4f56e11190787bee77dac", size = 178684, upload-time = "2026-01-10T09:22:44.941Z" }, - { url = "https://files.pythonhosted.org/packages/84/7b/bac442e6b96c9d25092695578dda82403c77936104b5682307bd4deb1ad4/websockets-16.0-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:71c989cbf3254fbd5e84d3bff31e4da39c43f884e64f2551d14bb3c186230f00", size = 177365, upload-time = "2026-01-10T09:22:46.787Z" }, - { url = "https://files.pythonhosted.org/packages/b0/fe/136ccece61bd690d9c1f715baaeefd953bb2360134de73519d5df19d29ca/websockets-16.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:8b6e209ffee39ff1b6d0fa7bfef6de950c60dfb91b8fcead17da4ee539121a79", size = 175038, upload-time = "2026-01-10T09:22:47.999Z" }, - { url = "https://files.pythonhosted.org/packages/40/1e/9771421ac2286eaab95b8575b0cb701ae3663abf8b5e1f64f1fd90d0a673/websockets-16.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:86890e837d61574c92a97496d590968b23c2ef0aeb8a9bc9421d174cd378ae39", size = 175328, upload-time = "2026-01-10T09:22:49.809Z" }, - { url = "https://files.pythonhosted.org/packages/18/29/71729b4671f21e1eaa5d6573031ab810ad2936c8175f03f97f3ff164c802/websockets-16.0-cp312-cp312-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:9b5aca38b67492ef518a8ab76851862488a478602229112c4b0d58d63a7a4d5c", size = 184915, upload-time = "2026-01-10T09:22:51.071Z" }, - { url = "https://files.pythonhosted.org/packages/97/bb/21c36b7dbbafc85d2d480cd65df02a1dc93bf76d97147605a8e27ff9409d/websockets-16.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:e0334872c0a37b606418ac52f6ab9cfd17317ac26365f7f65e203e2d0d0d359f", size = 186152, upload-time = "2026-01-10T09:22:52.224Z" }, - { url = "https://files.pythonhosted.org/packages/4a/34/9bf8df0c0cf88fa7bfe36678dc7b02970c9a7d5e065a3099292db87b1be2/websockets-16.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:a0b31e0b424cc6b5a04b8838bbaec1688834b2383256688cf47eb97412531da1", size = 185583, upload-time = "2026-01-10T09:22:53.443Z" }, - { url = "https://files.pythonhosted.org/packages/47/88/4dd516068e1a3d6ab3c7c183288404cd424a9a02d585efbac226cb61ff2d/websockets-16.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:485c49116d0af10ac698623c513c1cc01c9446c058a4e61e3bf6c19dff7335a2", size = 184880, upload-time = "2026-01-10T09:22:55.033Z" }, - { url = "https://files.pythonhosted.org/packages/91/d6/7d4553ad4bf1c0421e1ebd4b18de5d9098383b5caa1d937b63df8d04b565/websockets-16.0-cp312-cp312-win32.whl", hash = "sha256:eaded469f5e5b7294e2bdca0ab06becb6756ea86894a47806456089298813c89", size = 178261, upload-time = "2026-01-10T09:22:56.251Z" }, - { url = "https://files.pythonhosted.org/packages/c3/f0/f3a17365441ed1c27f850a80b2bc680a0fa9505d733fe152fdf5e98c1c0b/websockets-16.0-cp312-cp312-win_amd64.whl", hash = "sha256:5569417dc80977fc8c2d43a86f78e0a5a22fee17565d78621b6bb264a115d4ea", size = 178693, upload-time = "2026-01-10T09:22:57.478Z" }, - { url = "https://files.pythonhosted.org/packages/cc/9c/baa8456050d1c1b08dd0ec7346026668cbc6f145ab4e314d707bb845bf0d/websockets-16.0-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:878b336ac47938b474c8f982ac2f7266a540adc3fa4ad74ae96fea9823a02cc9", size = 177364, upload-time = "2026-01-10T09:22:59.333Z" }, - { url = "https://files.pythonhosted.org/packages/7e/0c/8811fc53e9bcff68fe7de2bcbe75116a8d959ac699a3200f4847a8925210/websockets-16.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:52a0fec0e6c8d9a784c2c78276a48a2bdf099e4ccc2a4cad53b27718dbfd0230", size = 175039, upload-time = "2026-01-10T09:23:01.171Z" }, - { url = "https://files.pythonhosted.org/packages/aa/82/39a5f910cb99ec0b59e482971238c845af9220d3ab9fa76dd9162cda9d62/websockets-16.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:e6578ed5b6981005df1860a56e3617f14a6c307e6a71b4fff8c48fdc50f3ed2c", size = 175323, upload-time = "2026-01-10T09:23:02.341Z" }, - { url = "https://files.pythonhosted.org/packages/bd/28/0a25ee5342eb5d5f297d992a77e56892ecb65e7854c7898fb7d35e9b33bd/websockets-16.0-cp313-cp313-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:95724e638f0f9c350bb1c2b0a7ad0e83d9cc0c9259f3ea94e40d7b02a2179ae5", size = 184975, upload-time = "2026-01-10T09:23:03.756Z" }, - { url = "https://files.pythonhosted.org/packages/f9/66/27ea52741752f5107c2e41fda05e8395a682a1e11c4e592a809a90c6a506/websockets-16.0-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:c0204dc62a89dc9d50d682412c10b3542d748260d743500a85c13cd1ee4bde82", size = 186203, upload-time = "2026-01-10T09:23:05.01Z" }, - { url = "https://files.pythonhosted.org/packages/37/e5/8e32857371406a757816a2b471939d51c463509be73fa538216ea52b792a/websockets-16.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:52ac480f44d32970d66763115edea932f1c5b1312de36df06d6b219f6741eed8", size = 185653, upload-time = "2026-01-10T09:23:06.301Z" }, - { url = "https://files.pythonhosted.org/packages/9b/67/f926bac29882894669368dc73f4da900fcdf47955d0a0185d60103df5737/websockets-16.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:6e5a82b677f8f6f59e8dfc34ec06ca6b5b48bc4fcda346acd093694cc2c24d8f", size = 184920, upload-time = "2026-01-10T09:23:07.492Z" }, - { url = "https://files.pythonhosted.org/packages/3c/a1/3d6ccdcd125b0a42a311bcd15a7f705d688f73b2a22d8cf1c0875d35d34a/websockets-16.0-cp313-cp313-win32.whl", hash = "sha256:abf050a199613f64c886ea10f38b47770a65154dc37181bfaff70c160f45315a", size = 178255, upload-time = "2026-01-10T09:23:09.245Z" }, - { url = "https://files.pythonhosted.org/packages/6b/ae/90366304d7c2ce80f9b826096a9e9048b4bb760e44d3b873bb272cba696b/websockets-16.0-cp313-cp313-win_amd64.whl", hash = "sha256:3425ac5cf448801335d6fdc7ae1eb22072055417a96cc6b31b3861f455fbc156", size = 178689, upload-time = "2026-01-10T09:23:10.483Z" }, - { url = "https://files.pythonhosted.org/packages/f3/1d/e88022630271f5bd349ed82417136281931e558d628dd52c4d8621b4a0b2/websockets-16.0-cp314-cp314-macosx_10_15_universal2.whl", hash = "sha256:8cc451a50f2aee53042ac52d2d053d08bf89bcb31ae799cb4487587661c038a0", size = 177406, upload-time = "2026-01-10T09:23:12.178Z" }, - { url = "https://files.pythonhosted.org/packages/f2/78/e63be1bf0724eeb4616efb1ae1c9044f7c3953b7957799abb5915bffd38e/websockets-16.0-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:daa3b6ff70a9241cf6c7fc9e949d41232d9d7d26fd3522b1ad2b4d62487e9904", size = 175085, upload-time = "2026-01-10T09:23:13.511Z" }, - { url = "https://files.pythonhosted.org/packages/bb/f4/d3c9220d818ee955ae390cf319a7c7a467beceb24f05ee7aaaa2414345ba/websockets-16.0-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:fd3cb4adb94a2a6e2b7c0d8d05cb94e6f1c81a0cf9dc2694fb65c7e8d94c42e4", size = 175328, upload-time = "2026-01-10T09:23:14.727Z" }, - { url = "https://files.pythonhosted.org/packages/63/bc/d3e208028de777087e6fb2b122051a6ff7bbcca0d6df9d9c2bf1dd869ae9/websockets-16.0-cp314-cp314-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:781caf5e8eee67f663126490c2f96f40906594cb86b408a703630f95550a8c3e", size = 185044, upload-time = "2026-01-10T09:23:15.939Z" }, - { url = "https://files.pythonhosted.org/packages/ad/6e/9a0927ac24bd33a0a9af834d89e0abc7cfd8e13bed17a86407a66773cc0e/websockets-16.0-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:caab51a72c51973ca21fa8a18bd8165e1a0183f1ac7066a182ff27107b71e1a4", size = 186279, upload-time = "2026-01-10T09:23:17.148Z" }, - { url = "https://files.pythonhosted.org/packages/b9/ca/bf1c68440d7a868180e11be653c85959502efd3a709323230314fda6e0b3/websockets-16.0-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:19c4dc84098e523fd63711e563077d39e90ec6702aff4b5d9e344a60cb3c0cb1", size = 185711, upload-time = "2026-01-10T09:23:18.372Z" }, - { url = "https://files.pythonhosted.org/packages/c4/f8/fdc34643a989561f217bb477cbc47a3a07212cbda91c0e4389c43c296ebf/websockets-16.0-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:a5e18a238a2b2249c9a9235466b90e96ae4795672598a58772dd806edc7ac6d3", size = 184982, upload-time = "2026-01-10T09:23:19.652Z" }, - { url = "https://files.pythonhosted.org/packages/dd/d1/574fa27e233764dbac9c52730d63fcf2823b16f0856b3329fc6268d6ae4f/websockets-16.0-cp314-cp314-win32.whl", hash = "sha256:a069d734c4a043182729edd3e9f247c3b2a4035415a9172fd0f1b71658a320a8", size = 177915, upload-time = "2026-01-10T09:23:21.458Z" }, - { url = "https://files.pythonhosted.org/packages/8a/f1/ae6b937bf3126b5134ce1f482365fde31a357c784ac51852978768b5eff4/websockets-16.0-cp314-cp314-win_amd64.whl", hash = "sha256:c0ee0e63f23914732c6d7e0cce24915c48f3f1512ec1d079ed01fc629dab269d", size = 178381, upload-time = "2026-01-10T09:23:22.715Z" }, - { url = "https://files.pythonhosted.org/packages/06/9b/f791d1db48403e1f0a27577a6beb37afae94254a8c6f08be4a23e4930bc0/websockets-16.0-cp314-cp314t-macosx_10_15_universal2.whl", hash = "sha256:a35539cacc3febb22b8f4d4a99cc79b104226a756aa7400adc722e83b0d03244", size = 177737, upload-time = "2026-01-10T09:23:24.523Z" }, - { url = "https://files.pythonhosted.org/packages/bd/40/53ad02341fa33b3ce489023f635367a4ac98b73570102ad2cdd770dacc9a/websockets-16.0-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:b784ca5de850f4ce93ec85d3269d24d4c82f22b7212023c974c401d4980ebc5e", size = 175268, upload-time = "2026-01-10T09:23:25.781Z" }, - { url = "https://files.pythonhosted.org/packages/74/9b/6158d4e459b984f949dcbbb0c5d270154c7618e11c01029b9bbd1bb4c4f9/websockets-16.0-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:569d01a4e7fba956c5ae4fc988f0d4e187900f5497ce46339c996dbf24f17641", size = 175486, upload-time = "2026-01-10T09:23:27.033Z" }, - { url = "https://files.pythonhosted.org/packages/e5/2d/7583b30208b639c8090206f95073646c2c9ffd66f44df967981a64f849ad/websockets-16.0-cp314-cp314t-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:50f23cdd8343b984957e4077839841146f67a3d31ab0d00e6b824e74c5b2f6e8", size = 185331, upload-time = "2026-01-10T09:23:28.259Z" }, - { url = "https://files.pythonhosted.org/packages/45/b0/cce3784eb519b7b5ad680d14b9673a31ab8dcb7aad8b64d81709d2430aa8/websockets-16.0-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:152284a83a00c59b759697b7f9e9cddf4e3c7861dd0d964b472b70f78f89e80e", size = 186501, upload-time = "2026-01-10T09:23:29.449Z" }, - { url = "https://files.pythonhosted.org/packages/19/60/b8ebe4c7e89fb5f6cdf080623c9d92789a53636950f7abacfc33fe2b3135/websockets-16.0-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:bc59589ab64b0022385f429b94697348a6a234e8ce22544e3681b2e9331b5944", size = 186062, upload-time = "2026-01-10T09:23:31.368Z" }, - { url = "https://files.pythonhosted.org/packages/88/a8/a080593f89b0138b6cba1b28f8df5673b5506f72879322288b031337c0b8/websockets-16.0-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:32da954ffa2814258030e5a57bc73a3635463238e797c7375dc8091327434206", size = 185356, upload-time = "2026-01-10T09:23:32.627Z" }, - { url = "https://files.pythonhosted.org/packages/c2/b6/b9afed2afadddaf5ebb2afa801abf4b0868f42f8539bfe4b071b5266c9fe/websockets-16.0-cp314-cp314t-win32.whl", hash = "sha256:5a4b4cc550cb665dd8a47f868c8d04c8230f857363ad3c9caf7a0c3bf8c61ca6", size = 178085, upload-time = "2026-01-10T09:23:33.816Z" }, - { url = "https://files.pythonhosted.org/packages/9f/3e/28135a24e384493fa804216b79a6a6759a38cc4ff59118787b9fb693df93/websockets-16.0-cp314-cp314t-win_amd64.whl", hash = "sha256:b14dc141ed6d2dde437cddb216004bcac6a1df0935d79656387bd41632ba0bbd", size = 178531, upload-time = "2026-01-10T09:23:35.016Z" }, - { url = "https://files.pythonhosted.org/packages/72/07/c98a68571dcf256e74f1f816b8cc5eae6eb2d3d5cfa44d37f801619d9166/websockets-16.0-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:349f83cd6c9a415428ee1005cadb5c2c56f4389bc06a9af16103c3bc3dcc8b7d", size = 174947, upload-time = "2026-01-10T09:23:36.166Z" }, - { url = "https://files.pythonhosted.org/packages/7e/52/93e166a81e0305b33fe416338be92ae863563fe7bce446b0f687b9df5aea/websockets-16.0-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:4a1aba3340a8dca8db6eb5a7986157f52eb9e436b74813764241981ca4888f03", size = 175260, upload-time = "2026-01-10T09:23:37.409Z" }, - { url = "https://files.pythonhosted.org/packages/56/0c/2dbf513bafd24889d33de2ff0368190a0e69f37bcfa19009ef819fe4d507/websockets-16.0-pp311-pypy311_pp73-manylinux1_x86_64.manylinux_2_28_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:f4a32d1bd841d4bcbffdcb3d2ce50c09c3909fbead375ab28d0181af89fd04da", size = 176071, upload-time = "2026-01-10T09:23:39.158Z" }, - { url = "https://files.pythonhosted.org/packages/a5/8f/aea9c71cc92bf9b6cc0f7f70df8f0b420636b6c96ef4feee1e16f80f75dd/websockets-16.0-pp311-pypy311_pp73-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0298d07ee155e2e9fda5be8a9042200dd2e3bb0b8a38482156576f863a9d457c", size = 176968, upload-time = "2026-01-10T09:23:41.031Z" }, - { url = "https://files.pythonhosted.org/packages/9a/3f/f70e03f40ffc9a30d817eef7da1be72ee4956ba8d7255c399a01b135902a/websockets-16.0-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:a653aea902e0324b52f1613332ddf50b00c06fdaf7e92624fbf8c77c78fa5767", size = 178735, upload-time = "2026-01-10T09:23:42.259Z" }, - { url = "https://files.pythonhosted.org/packages/6f/28/258ebab549c2bf3e64d2b0217b973467394a9cea8c42f70418ca2c5d0d2e/websockets-16.0-py3-none-any.whl", hash = "sha256:1637db62fad1dc833276dded54215f2c7fa46912301a24bd94d45d46a011ceec", size = 171598, upload-time = "2026-01-10T09:23:45.395Z" }, +version = "15.0.1" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/21/e6/26d09fab466b7ca9c7737474c52be4f76a40301b08362eb2dbc19dcc16c1/websockets-15.0.1.tar.gz", hash = "sha256:82544de02076bafba038ce055ee6412d68da13ab47f0c60cab827346de828dee", size = 177016, upload-time = "2025-03-05T20:03:41.606Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/1e/da/6462a9f510c0c49837bbc9345aca92d767a56c1fb2939e1579df1e1cdcf7/websockets-15.0.1-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:d63efaa0cd96cf0c5fe4d581521d9fa87744540d4bc999ae6e08595a1014b45b", size = 175423, upload-time = "2025-03-05T20:01:35.363Z" }, + { url = "https://files.pythonhosted.org/packages/1c/9f/9d11c1a4eb046a9e106483b9ff69bce7ac880443f00e5ce64261b47b07e7/websockets-15.0.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:ac60e3b188ec7574cb761b08d50fcedf9d77f1530352db4eef1707fe9dee7205", size = 173080, upload-time = "2025-03-05T20:01:37.304Z" }, + { url = "https://files.pythonhosted.org/packages/d5/4f/b462242432d93ea45f297b6179c7333dd0402b855a912a04e7fc61c0d71f/websockets-15.0.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:5756779642579d902eed757b21b0164cd6fe338506a8083eb58af5c372e39d9a", size = 173329, upload-time = "2025-03-05T20:01:39.668Z" }, + { url = "https://files.pythonhosted.org/packages/6e/0c/6afa1f4644d7ed50284ac59cc70ef8abd44ccf7d45850d989ea7310538d0/websockets-15.0.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0fdfe3e2a29e4db3659dbd5bbf04560cea53dd9610273917799f1cde46aa725e", size = 182312, upload-time = "2025-03-05T20:01:41.815Z" }, + { url = "https://files.pythonhosted.org/packages/dd/d4/ffc8bd1350b229ca7a4db2a3e1c482cf87cea1baccd0ef3e72bc720caeec/websockets-15.0.1-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:4c2529b320eb9e35af0fa3016c187dffb84a3ecc572bcee7c3ce302bfeba52bf", size = 181319, upload-time = "2025-03-05T20:01:43.967Z" }, + { url = "https://files.pythonhosted.org/packages/97/3a/5323a6bb94917af13bbb34009fac01e55c51dfde354f63692bf2533ffbc2/websockets-15.0.1-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ac1e5c9054fe23226fb11e05a6e630837f074174c4c2f0fe442996112a6de4fb", size = 181631, upload-time = "2025-03-05T20:01:46.104Z" }, + { url = "https://files.pythonhosted.org/packages/a6/cc/1aeb0f7cee59ef065724041bb7ed667b6ab1eeffe5141696cccec2687b66/websockets-15.0.1-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:5df592cd503496351d6dc14f7cdad49f268d8e618f80dce0cd5a36b93c3fc08d", size = 182016, upload-time = "2025-03-05T20:01:47.603Z" }, + { url = "https://files.pythonhosted.org/packages/79/f9/c86f8f7af208e4161a7f7e02774e9d0a81c632ae76db2ff22549e1718a51/websockets-15.0.1-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:0a34631031a8f05657e8e90903e656959234f3a04552259458aac0b0f9ae6fd9", size = 181426, upload-time = "2025-03-05T20:01:48.949Z" }, + { url = "https://files.pythonhosted.org/packages/c7/b9/828b0bc6753db905b91df6ae477c0b14a141090df64fb17f8a9d7e3516cf/websockets-15.0.1-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:3d00075aa65772e7ce9e990cab3ff1de702aa09be3940d1dc88d5abf1ab8a09c", size = 181360, upload-time = "2025-03-05T20:01:50.938Z" }, + { url = "https://files.pythonhosted.org/packages/89/fb/250f5533ec468ba6327055b7d98b9df056fb1ce623b8b6aaafb30b55d02e/websockets-15.0.1-cp310-cp310-win32.whl", hash = "sha256:1234d4ef35db82f5446dca8e35a7da7964d02c127b095e172e54397fb6a6c256", size = 176388, upload-time = "2025-03-05T20:01:52.213Z" }, + { url = "https://files.pythonhosted.org/packages/1c/46/aca7082012768bb98e5608f01658ff3ac8437e563eca41cf068bd5849a5e/websockets-15.0.1-cp310-cp310-win_amd64.whl", hash = "sha256:39c1fec2c11dc8d89bba6b2bf1556af381611a173ac2b511cf7231622058af41", size = 176830, upload-time = "2025-03-05T20:01:53.922Z" }, + { url = "https://files.pythonhosted.org/packages/9f/32/18fcd5919c293a398db67443acd33fde142f283853076049824fc58e6f75/websockets-15.0.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:823c248b690b2fd9303ba00c4f66cd5e2d8c3ba4aa968b2779be9532a4dad431", size = 175423, upload-time = "2025-03-05T20:01:56.276Z" }, + { url = "https://files.pythonhosted.org/packages/76/70/ba1ad96b07869275ef42e2ce21f07a5b0148936688c2baf7e4a1f60d5058/websockets-15.0.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:678999709e68425ae2593acf2e3ebcbcf2e69885a5ee78f9eb80e6e371f1bf57", size = 173082, upload-time = "2025-03-05T20:01:57.563Z" }, + { url = "https://files.pythonhosted.org/packages/86/f2/10b55821dd40eb696ce4704a87d57774696f9451108cff0d2824c97e0f97/websockets-15.0.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d50fd1ee42388dcfb2b3676132c78116490976f1300da28eb629272d5d93e905", size = 173330, upload-time = "2025-03-05T20:01:59.063Z" }, + { url = "https://files.pythonhosted.org/packages/a5/90/1c37ae8b8a113d3daf1065222b6af61cc44102da95388ac0018fcb7d93d9/websockets-15.0.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d99e5546bf73dbad5bf3547174cd6cb8ba7273062a23808ffea025ecb1cf8562", size = 182878, upload-time = "2025-03-05T20:02:00.305Z" }, + { url = "https://files.pythonhosted.org/packages/8e/8d/96e8e288b2a41dffafb78e8904ea7367ee4f891dafc2ab8d87e2124cb3d3/websockets-15.0.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:66dd88c918e3287efc22409d426c8f729688d89a0c587c88971a0faa2c2f3792", size = 181883, upload-time = "2025-03-05T20:02:03.148Z" }, + { url = "https://files.pythonhosted.org/packages/93/1f/5d6dbf551766308f6f50f8baf8e9860be6182911e8106da7a7f73785f4c4/websockets-15.0.1-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8dd8327c795b3e3f219760fa603dcae1dcc148172290a8ab15158cf85a953413", size = 182252, upload-time = "2025-03-05T20:02:05.29Z" }, + { url = "https://files.pythonhosted.org/packages/d4/78/2d4fed9123e6620cbf1706c0de8a1632e1a28e7774d94346d7de1bba2ca3/websockets-15.0.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:8fdc51055e6ff4adeb88d58a11042ec9a5eae317a0a53d12c062c8a8865909e8", size = 182521, upload-time = "2025-03-05T20:02:07.458Z" }, + { url = "https://files.pythonhosted.org/packages/e7/3b/66d4c1b444dd1a9823c4a81f50231b921bab54eee2f69e70319b4e21f1ca/websockets-15.0.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:693f0192126df6c2327cce3baa7c06f2a117575e32ab2308f7f8216c29d9e2e3", size = 181958, upload-time = "2025-03-05T20:02:09.842Z" }, + { url = "https://files.pythonhosted.org/packages/08/ff/e9eed2ee5fed6f76fdd6032ca5cd38c57ca9661430bb3d5fb2872dc8703c/websockets-15.0.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:54479983bd5fb469c38f2f5c7e3a24f9a4e70594cd68cd1fa6b9340dadaff7cf", size = 181918, upload-time = "2025-03-05T20:02:11.968Z" }, + { url = "https://files.pythonhosted.org/packages/d8/75/994634a49b7e12532be6a42103597b71098fd25900f7437d6055ed39930a/websockets-15.0.1-cp311-cp311-win32.whl", hash = "sha256:16b6c1b3e57799b9d38427dda63edcbe4926352c47cf88588c0be4ace18dac85", size = 176388, upload-time = "2025-03-05T20:02:13.32Z" }, + { url = "https://files.pythonhosted.org/packages/98/93/e36c73f78400a65f5e236cd376713c34182e6663f6889cd45a4a04d8f203/websockets-15.0.1-cp311-cp311-win_amd64.whl", hash = "sha256:27ccee0071a0e75d22cb35849b1db43f2ecd3e161041ac1ee9d2352ddf72f065", size = 176828, upload-time = "2025-03-05T20:02:14.585Z" }, + { url = "https://files.pythonhosted.org/packages/51/6b/4545a0d843594f5d0771e86463606a3988b5a09ca5123136f8a76580dd63/websockets-15.0.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:3e90baa811a5d73f3ca0bcbf32064d663ed81318ab225ee4f427ad4e26e5aff3", size = 175437, upload-time = "2025-03-05T20:02:16.706Z" }, + { url = "https://files.pythonhosted.org/packages/f4/71/809a0f5f6a06522af902e0f2ea2757f71ead94610010cf570ab5c98e99ed/websockets-15.0.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:592f1a9fe869c778694f0aa806ba0374e97648ab57936f092fd9d87f8bc03665", size = 173096, upload-time = "2025-03-05T20:02:18.832Z" }, + { url = "https://files.pythonhosted.org/packages/3d/69/1a681dd6f02180916f116894181eab8b2e25b31e484c5d0eae637ec01f7c/websockets-15.0.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:0701bc3cfcb9164d04a14b149fd74be7347a530ad3bbf15ab2c678a2cd3dd9a2", size = 173332, upload-time = "2025-03-05T20:02:20.187Z" }, + { url = "https://files.pythonhosted.org/packages/a6/02/0073b3952f5bce97eafbb35757f8d0d54812b6174ed8dd952aa08429bcc3/websockets-15.0.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e8b56bdcdb4505c8078cb6c7157d9811a85790f2f2b3632c7d1462ab5783d215", size = 183152, upload-time = "2025-03-05T20:02:22.286Z" }, + { url = "https://files.pythonhosted.org/packages/74/45/c205c8480eafd114b428284840da0b1be9ffd0e4f87338dc95dc6ff961a1/websockets-15.0.1-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:0af68c55afbd5f07986df82831c7bff04846928ea8d1fd7f30052638788bc9b5", size = 182096, upload-time = "2025-03-05T20:02:24.368Z" }, + { url = "https://files.pythonhosted.org/packages/14/8f/aa61f528fba38578ec553c145857a181384c72b98156f858ca5c8e82d9d3/websockets-15.0.1-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:64dee438fed052b52e4f98f76c5790513235efaa1ef7f3f2192c392cd7c91b65", size = 182523, upload-time = "2025-03-05T20:02:25.669Z" }, + { url = "https://files.pythonhosted.org/packages/ec/6d/0267396610add5bc0d0d3e77f546d4cd287200804fe02323797de77dbce9/websockets-15.0.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:d5f6b181bb38171a8ad1d6aa58a67a6aa9d4b38d0f8c5f496b9e42561dfc62fe", size = 182790, upload-time = "2025-03-05T20:02:26.99Z" }, + { url = "https://files.pythonhosted.org/packages/02/05/c68c5adbf679cf610ae2f74a9b871ae84564462955d991178f95a1ddb7dd/websockets-15.0.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:5d54b09eba2bada6011aea5375542a157637b91029687eb4fdb2dab11059c1b4", size = 182165, upload-time = "2025-03-05T20:02:30.291Z" }, + { url = "https://files.pythonhosted.org/packages/29/93/bb672df7b2f5faac89761cb5fa34f5cec45a4026c383a4b5761c6cea5c16/websockets-15.0.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:3be571a8b5afed347da347bfcf27ba12b069d9d7f42cb8c7028b5e98bbb12597", size = 182160, upload-time = "2025-03-05T20:02:31.634Z" }, + { url = "https://files.pythonhosted.org/packages/ff/83/de1f7709376dc3ca9b7eeb4b9a07b4526b14876b6d372a4dc62312bebee0/websockets-15.0.1-cp312-cp312-win32.whl", hash = "sha256:c338ffa0520bdb12fbc527265235639fb76e7bc7faafbb93f6ba80d9c06578a9", size = 176395, upload-time = "2025-03-05T20:02:33.017Z" }, + { url = "https://files.pythonhosted.org/packages/7d/71/abf2ebc3bbfa40f391ce1428c7168fb20582d0ff57019b69ea20fa698043/websockets-15.0.1-cp312-cp312-win_amd64.whl", hash = "sha256:fcd5cf9e305d7b8338754470cf69cf81f420459dbae8a3b40cee57417f4614a7", size = 176841, upload-time = "2025-03-05T20:02:34.498Z" }, + { url = "https://files.pythonhosted.org/packages/cb/9f/51f0cf64471a9d2b4d0fc6c534f323b664e7095640c34562f5182e5a7195/websockets-15.0.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:ee443ef070bb3b6ed74514f5efaa37a252af57c90eb33b956d35c8e9c10a1931", size = 175440, upload-time = "2025-03-05T20:02:36.695Z" }, + { url = "https://files.pythonhosted.org/packages/8a/05/aa116ec9943c718905997412c5989f7ed671bc0188ee2ba89520e8765d7b/websockets-15.0.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:5a939de6b7b4e18ca683218320fc67ea886038265fd1ed30173f5ce3f8e85675", size = 173098, upload-time = "2025-03-05T20:02:37.985Z" }, + { url = "https://files.pythonhosted.org/packages/ff/0b/33cef55ff24f2d92924923c99926dcce78e7bd922d649467f0eda8368923/websockets-15.0.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:746ee8dba912cd6fc889a8147168991d50ed70447bf18bcda7039f7d2e3d9151", size = 173329, upload-time = "2025-03-05T20:02:39.298Z" }, + { url = "https://files.pythonhosted.org/packages/31/1d/063b25dcc01faa8fada1469bdf769de3768b7044eac9d41f734fd7b6ad6d/websockets-15.0.1-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:595b6c3969023ecf9041b2936ac3827e4623bfa3ccf007575f04c5a6aa318c22", size = 183111, upload-time = "2025-03-05T20:02:40.595Z" }, + { url = "https://files.pythonhosted.org/packages/93/53/9a87ee494a51bf63e4ec9241c1ccc4f7c2f45fff85d5bde2ff74fcb68b9e/websockets-15.0.1-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3c714d2fc58b5ca3e285461a4cc0c9a66bd0e24c5da9911e30158286c9b5be7f", size = 182054, upload-time = "2025-03-05T20:02:41.926Z" }, + { url = "https://files.pythonhosted.org/packages/ff/b2/83a6ddf56cdcbad4e3d841fcc55d6ba7d19aeb89c50f24dd7e859ec0805f/websockets-15.0.1-cp313-cp313-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0f3c1e2ab208db911594ae5b4f79addeb3501604a165019dd221c0bdcabe4db8", size = 182496, upload-time = "2025-03-05T20:02:43.304Z" }, + { url = "https://files.pythonhosted.org/packages/98/41/e7038944ed0abf34c45aa4635ba28136f06052e08fc2168520bb8b25149f/websockets-15.0.1-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:229cf1d3ca6c1804400b0a9790dc66528e08a6a1feec0d5040e8b9eb14422375", size = 182829, upload-time = "2025-03-05T20:02:48.812Z" }, + { url = "https://files.pythonhosted.org/packages/e0/17/de15b6158680c7623c6ef0db361da965ab25d813ae54fcfeae2e5b9ef910/websockets-15.0.1-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:756c56e867a90fb00177d530dca4b097dd753cde348448a1012ed6c5131f8b7d", size = 182217, upload-time = "2025-03-05T20:02:50.14Z" }, + { url = "https://files.pythonhosted.org/packages/33/2b/1f168cb6041853eef0362fb9554c3824367c5560cbdaad89ac40f8c2edfc/websockets-15.0.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:558d023b3df0bffe50a04e710bc87742de35060580a293c2a984299ed83bc4e4", size = 182195, upload-time = "2025-03-05T20:02:51.561Z" }, + { url = "https://files.pythonhosted.org/packages/86/eb/20b6cdf273913d0ad05a6a14aed4b9a85591c18a987a3d47f20fa13dcc47/websockets-15.0.1-cp313-cp313-win32.whl", hash = "sha256:ba9e56e8ceeeedb2e080147ba85ffcd5cd0711b89576b83784d8605a7df455fa", size = 176393, upload-time = "2025-03-05T20:02:53.814Z" }, + { url = "https://files.pythonhosted.org/packages/1b/6c/c65773d6cab416a64d191d6ee8a8b1c68a09970ea6909d16965d26bfed1e/websockets-15.0.1-cp313-cp313-win_amd64.whl", hash = "sha256:e09473f095a819042ecb2ab9465aee615bd9c2028e4ef7d933600a8401c79561", size = 176837, upload-time = "2025-03-05T20:02:55.237Z" }, + { url = "https://files.pythonhosted.org/packages/02/9e/d40f779fa16f74d3468357197af8d6ad07e7c5a27ea1ca74ceb38986f77a/websockets-15.0.1-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:0c9e74d766f2818bb95f84c25be4dea09841ac0f734d1966f415e4edfc4ef1c3", size = 173109, upload-time = "2025-03-05T20:03:17.769Z" }, + { url = "https://files.pythonhosted.org/packages/bc/cd/5b887b8585a593073fd92f7c23ecd3985cd2c3175025a91b0d69b0551372/websockets-15.0.1-pp310-pypy310_pp73-macosx_11_0_arm64.whl", hash = "sha256:1009ee0c7739c08a0cd59de430d6de452a55e42d6b522de7aa15e6f67db0b8e1", size = 173343, upload-time = "2025-03-05T20:03:19.094Z" }, + { url = "https://files.pythonhosted.org/packages/fe/ae/d34f7556890341e900a95acf4886833646306269f899d58ad62f588bf410/websockets-15.0.1-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:76d1f20b1c7a2fa82367e04982e708723ba0e7b8d43aa643d3dcd404d74f1475", size = 174599, upload-time = "2025-03-05T20:03:21.1Z" }, + { url = "https://files.pythonhosted.org/packages/71/e6/5fd43993a87db364ec60fc1d608273a1a465c0caba69176dd160e197ce42/websockets-15.0.1-pp310-pypy310_pp73-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f29d80eb9a9263b8d109135351caf568cc3f80b9928bccde535c235de55c22d9", size = 174207, upload-time = "2025-03-05T20:03:23.221Z" }, + { url = "https://files.pythonhosted.org/packages/2b/fb/c492d6daa5ec067c2988ac80c61359ace5c4c674c532985ac5a123436cec/websockets-15.0.1-pp310-pypy310_pp73-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b359ed09954d7c18bbc1680f380c7301f92c60bf924171629c5db97febb12f04", size = 174155, upload-time = "2025-03-05T20:03:25.321Z" }, + { url = "https://files.pythonhosted.org/packages/68/a1/dcb68430b1d00b698ae7a7e0194433bce4f07ded185f0ee5fb21e2a2e91e/websockets-15.0.1-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:cad21560da69f4ce7658ca2cb83138fb4cf695a2ba3e475e0559e05991aa8122", size = 176884, upload-time = "2025-03-05T20:03:27.934Z" }, + { url = "https://files.pythonhosted.org/packages/fa/a8/5b41e0da817d64113292ab1f8247140aac61cbf6cfd085d6a0fa77f4984f/websockets-15.0.1-py3-none-any.whl", hash = "sha256:f7a866fbc1e97b5c617ee4116daaa09b722101d4a3c170c787450ba409f9736f", size = 169743, upload-time = "2025-03-05T20:03:39.41Z" }, ] [[package]] From 008cafe7d5c8659be400a1acec54e8822f2ec3f8 Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Mon, 12 Jan 2026 17:54:08 -0800 Subject: [PATCH 11/19] fixed the last mypy error --- dimos/perception/detection/detectors/types.py | 3 ++- dimos/perception/detection/detectors/yoloe.py | 5 +++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/dimos/perception/detection/detectors/types.py b/dimos/perception/detection/detectors/types.py index e85c5ae18e..87fa183ac3 100644 --- a/dimos/perception/detection/detectors/types.py +++ b/dimos/perception/detection/detectors/types.py @@ -16,8 +16,9 @@ from dimos.msgs.sensor_msgs import Image from dimos.perception.detection.type import ImageDetections2D +from dimos.perception.detection.type.detection2d.base import Detection2D class Detector(ABC): @abstractmethod - def process_image(self, image: Image) -> ImageDetections2D: ... + def process_image(self, image: Image) -> ImageDetections2D[Detection2D]: ... diff --git a/dimos/perception/detection/detectors/yoloe.py b/dimos/perception/detection/detectors/yoloe.py index 960ed1e2b6..1cbbce9cd8 100644 --- a/dimos/perception/detection/detectors/yoloe.py +++ b/dimos/perception/detection/detectors/yoloe.py @@ -18,11 +18,12 @@ import numpy as np from numpy.typing import NDArray -from ultralytics import YOLOE # type: ignore[attr-defined] +from ultralytics import YOLOE # type: ignore[attr-defined, import-not-found] from dimos.msgs.sensor_msgs import Image from dimos.perception.detection.detectors.types import Detector from dimos.perception.detection.type import ImageDetections2D +from dimos.perception.detection.type.detection2d.base import Detection2D from dimos.utils.data import get_data from dimos.utils.gpu_utils import is_cuda_available @@ -107,7 +108,7 @@ def set_prompts( cls = np.arange(len(bboxes), dtype=np.int16) # type: ignore[arg-type] self._visual_prompts = {"bboxes": bboxes, "cls": cls} # type: ignore[dict-item] - def process_image(self, image: Image) -> "ImageDetections2D[Any]": # type: ignore[override] + def process_image(self, image: Image) -> ImageDetections2D[Detection2D]: """ Process an image and return detection results. From 6893e3fb90e3c7aaf222be68fca69ff90cf55e50 Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Mon, 12 Jan 2026 18:08:28 -0800 Subject: [PATCH 12/19] fixed mypy errors from source --- dimos/perception/detection/detectors/person/yolo.py | 3 +-- dimos/perception/detection/detectors/types.py | 3 +-- dimos/perception/detection/detectors/yolo.py | 3 +-- dimos/perception/detection/detectors/yoloe.py | 3 +-- dimos/perception/detection/module2D.py | 6 +++--- .../detection/type/detection2d/imageDetections2D.py | 6 +++--- .../detection/type/detection2d/test_imageDetections2D.py | 4 +--- 7 files changed, 11 insertions(+), 17 deletions(-) diff --git a/dimos/perception/detection/detectors/person/yolo.py b/dimos/perception/detection/detectors/person/yolo.py index 3f491a2c9a..519f45f2f6 100644 --- a/dimos/perception/detection/detectors/person/yolo.py +++ b/dimos/perception/detection/detectors/person/yolo.py @@ -17,7 +17,6 @@ from dimos.msgs.sensor_msgs import Image from dimos.perception.detection.detectors.types import Detector from dimos.perception.detection.type import ImageDetections2D -from dimos.perception.detection.type.detection2d.base import Detection2D from dimos.utils.data import get_data from dimos.utils.gpu_utils import is_cuda_available from dimos.utils.logging_config import setup_logger @@ -47,7 +46,7 @@ def __init__( self.device = "cpu" logger.info("Using CPU for YOLO person detector") - def process_image(self, image: Image) -> ImageDetections2D[Detection2D]: + def process_image(self, image: Image) -> ImageDetections2D: """Process image and return detection results. Args: diff --git a/dimos/perception/detection/detectors/types.py b/dimos/perception/detection/detectors/types.py index 87fa183ac3..e85c5ae18e 100644 --- a/dimos/perception/detection/detectors/types.py +++ b/dimos/perception/detection/detectors/types.py @@ -16,9 +16,8 @@ from dimos.msgs.sensor_msgs import Image from dimos.perception.detection.type import ImageDetections2D -from dimos.perception.detection.type.detection2d.base import Detection2D class Detector(ABC): @abstractmethod - def process_image(self, image: Image) -> ImageDetections2D[Detection2D]: ... + def process_image(self, image: Image) -> ImageDetections2D: ... diff --git a/dimos/perception/detection/detectors/yolo.py b/dimos/perception/detection/detectors/yolo.py index 727d24f1d1..c9a65a120e 100644 --- a/dimos/perception/detection/detectors/yolo.py +++ b/dimos/perception/detection/detectors/yolo.py @@ -17,7 +17,6 @@ from dimos.msgs.sensor_msgs import Image from dimos.perception.detection.detectors.types import Detector from dimos.perception.detection.type import ImageDetections2D -from dimos.perception.detection.type.detection2d.base import Detection2D from dimos.utils.data import get_data from dimos.utils.gpu_utils import is_cuda_available from dimos.utils.logging_config import setup_logger @@ -48,7 +47,7 @@ def __init__( self.device = "cpu" logger.debug("Using CPU for YOLO 2d detector") - def process_image(self, image: Image) -> ImageDetections2D[Detection2D]: + def process_image(self, image: Image) -> ImageDetections2D: """ Process an image and return detection results. diff --git a/dimos/perception/detection/detectors/yoloe.py b/dimos/perception/detection/detectors/yoloe.py index 1cbbce9cd8..9c9881209c 100644 --- a/dimos/perception/detection/detectors/yoloe.py +++ b/dimos/perception/detection/detectors/yoloe.py @@ -23,7 +23,6 @@ from dimos.msgs.sensor_msgs import Image from dimos.perception.detection.detectors.types import Detector from dimos.perception.detection.type import ImageDetections2D -from dimos.perception.detection.type.detection2d.base import Detection2D from dimos.utils.data import get_data from dimos.utils.gpu_utils import is_cuda_available @@ -108,7 +107,7 @@ def set_prompts( cls = np.arange(len(bboxes), dtype=np.int16) # type: ignore[arg-type] self._visual_prompts = {"bboxes": bboxes, "cls": cls} # type: ignore[dict-item] - def process_image(self, image: Image) -> ImageDetections2D[Detection2D]: + def process_image(self, image: Image) -> "ImageDetections2D[Any]": """ Process an image and return detection results. diff --git a/dimos/perception/detection/module2D.py b/dimos/perception/detection/module2D.py index cfca3b2192..7e23f0e1cb 100644 --- a/dimos/perception/detection/module2D.py +++ b/dimos/perception/detection/module2D.py @@ -18,9 +18,9 @@ from dimos_lcm.foxglove_msgs.ImageAnnotations import ( ImageAnnotations, ) -from reactivex import operators as ops -from reactivex.observable import Observable -from reactivex.subject import Subject +from reactivex import operators as ops # type: ignore[import-not-found] +from reactivex.observable import Observable # type: ignore[import-not-found] +from reactivex.subject import Subject # type: ignore[import-not-found] from dimos import spec from dimos.core import DimosCluster, In, Module, Out, rpc diff --git a/dimos/perception/detection/type/detection2d/imageDetections2D.py b/dimos/perception/detection/type/detection2d/imageDetections2D.py index 92bd0bf506..743b3317ac 100644 --- a/dimos/perception/detection/type/detection2d/imageDetections2D.py +++ b/dimos/perception/detection/type/detection2d/imageDetections2D.py @@ -57,7 +57,7 @@ def from_ultralytics_result( cls, image: Image, results: list[Results], - ) -> ImageDetections2D[Detection2D]: + ) -> ImageDetections2D[Detection2DBBox]: """Create ImageDetections2D from ultralytics Results. Dispatches to appropriate Detection2D subclass based on result type: @@ -73,14 +73,14 @@ def from_ultralytics_result( ImageDetections2D containing appropriate detection types """ - detections: list[Detection2D] = [] + detections: list[Detection2DBBox] = [] for result in results: if result.boxes is None: continue num_detections = len(result.boxes.xyxy) for i in range(num_detections): - detection: Detection2D + detection: Detection2DBBox if result.masks is not None: # Segmentation detection with mask detection = Detection2DSeg.from_ultralytics_result(result, i, image) diff --git a/dimos/perception/detection/type/detection2d/test_imageDetections2D.py b/dimos/perception/detection/type/detection2d/test_imageDetections2D.py index 93f75dc422..83487d2c25 100644 --- a/dimos/perception/detection/type/detection2d/test_imageDetections2D.py +++ b/dimos/perception/detection/type/detection2d/test_imageDetections2D.py @@ -11,14 +11,12 @@ # 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 typing import Any - import pytest from dimos.perception.detection.type import ImageDetections2D -def test_from_ros_detection2d_array(get_moment_2d: Any) -> None: +def test_from_ros_detection2d_array(get_moment_2d) -> None: moment = get_moment_2d() detections2d = moment["detections2d"] From 73363cd09f6e09bc236a15a13466fd72a9f99daf Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Mon, 12 Jan 2026 18:28:48 -0800 Subject: [PATCH 13/19] reverted mypy import error fixes --- dimos/perception/detection/module2D.py | 6 +++--- .../detection/type/detection2d/imageDetections2D.py | 2 +- dimos/perception/detection/type/detection3d/object.py | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/dimos/perception/detection/module2D.py b/dimos/perception/detection/module2D.py index 7e23f0e1cb..cfca3b2192 100644 --- a/dimos/perception/detection/module2D.py +++ b/dimos/perception/detection/module2D.py @@ -18,9 +18,9 @@ from dimos_lcm.foxglove_msgs.ImageAnnotations import ( ImageAnnotations, ) -from reactivex import operators as ops # type: ignore[import-not-found] -from reactivex.observable import Observable # type: ignore[import-not-found] -from reactivex.subject import Subject # type: ignore[import-not-found] +from reactivex import operators as ops +from reactivex.observable import Observable +from reactivex.subject import Subject from dimos import spec from dimos.core import DimosCluster, In, Module, Out, rpc diff --git a/dimos/perception/detection/type/detection2d/imageDetections2D.py b/dimos/perception/detection/type/detection2d/imageDetections2D.py index 743b3317ac..c805c3ac7f 100644 --- a/dimos/perception/detection/type/detection2d/imageDetections2D.py +++ b/dimos/perception/detection/type/detection2d/imageDetections2D.py @@ -16,7 +16,7 @@ from typing import TYPE_CHECKING, Any, Generic -import cv2 # type: ignore[import-untyped] +import cv2 import numpy as np from typing_extensions import TypeVar diff --git a/dimos/perception/detection/type/detection3d/object.py b/dimos/perception/detection/type/detection3d/object.py index 955f16d61e..eb2cb104e3 100644 --- a/dimos/perception/detection/type/detection3d/object.py +++ b/dimos/perception/detection/type/detection3d/object.py @@ -19,7 +19,7 @@ from typing import TYPE_CHECKING, Any import uuid -import cv2 # type: ignore[import-untyped] +import cv2 from dimos_lcm.geometry_msgs import Pose import numpy as np import open3d as o3d # type: ignore[import-untyped] From 96f206900f3bd167ef6a4309746daf59353d519b Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Tue, 13 Jan 2026 00:44:17 -0800 Subject: [PATCH 14/19] fixed Ivan's comment --- dimos/msgs/vision_msgs/Detection3D.py | 90 --------------------------- 1 file changed, 90 deletions(-) diff --git a/dimos/msgs/vision_msgs/Detection3D.py b/dimos/msgs/vision_msgs/Detection3D.py index 57e8f686fc..e074ecb0b1 100644 --- a/dimos/msgs/vision_msgs/Detection3D.py +++ b/dimos/msgs/vision_msgs/Detection3D.py @@ -11,35 +11,8 @@ # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and # limitations under the License. -from __future__ import annotations - from dimos_lcm.vision_msgs.Detection3D import Detection3D as LCMDetection3D -try: - from geometry_msgs.msg import ( # type: ignore[attr-defined] - Point as ROSPoint, - Pose as ROSPose, - Quaternion as ROSQuaternion, - Vector3 as ROSVector3, - ) - from std_msgs.msg import Header as ROSHeader # type: ignore[attr-defined] - from vision_msgs.msg import ( # type: ignore[attr-defined, import-untyped] - BoundingBox3D as ROSBoundingBox3D, - Detection3D as ROSDetection3D, - ObjectHypothesis as ROSObjectHypothesis, - ObjectHypothesisWithPose as ROSObjectHypothesisWithPose, - ) -except ImportError: - ROSPoint = None # type: ignore[assignment, misc] - ROSPose = None # type: ignore[assignment, misc] - ROSQuaternion = None # type: ignore[assignment, misc] - ROSVector3 = None # type: ignore[assignment, misc] - ROSHeader = None # type: ignore[assignment, misc] - ROSBoundingBox3D = None # type: ignore[assignment, misc] - ROSDetection3D = None # type: ignore[assignment, misc] - ROSObjectHypothesis = None # type: ignore[assignment, misc] - ROSObjectHypothesisWithPose = None # type: ignore[assignment, misc] - from dimos.types.timestamped import to_timestamp @@ -49,69 +22,6 @@ class Detection3D(LCMDetection3D): # type: ignore[misc] # for _get_field_type() to work when decoding in _decode_one() __annotations__ = LCMDetection3D.__annotations__ - def __init__(self, **kwargs) -> None: # type: ignore[no-untyped-def] - """Initialize with fresh mutable objects to avoid shared state.""" - super().__init__() - # Create fresh instances to avoid shared mutable state from LCM class defaults - from dimos_lcm.std_msgs import Header - from dimos_lcm.vision_msgs import BoundingBox3D - - self.header = Header() - from dimos_lcm.vision_msgs import ObjectHypothesisWithPose - - self.results: list[ObjectHypothesisWithPose] = [] - self.bbox = BoundingBox3D() - self.id = "" - - # Apply any kwargs - for key, value in kwargs.items(): - setattr(self, key, value) - @property def ts(self) -> float: return to_timestamp(self.header.stamp) - - def to_ros_msg(self) -> ROSDetection3D: - """Convert to ROS vision_msgs/Detection3D message. - - Returns: - ROS Detection3D message - """ - ros_msg = ROSDetection3D() - - # Set header - ros_msg.header = ROSHeader() - ros_msg.header.frame_id = self.header.frame_id - ros_msg.header.stamp.sec = self.header.stamp.sec - ros_msg.header.stamp.nanosec = self.header.stamp.nsec - - # Set bounding box - ros_msg.bbox = ROSBoundingBox3D() - ros_msg.bbox.center = ROSPose() - ros_msg.bbox.center.position = ROSPoint() - ros_msg.bbox.center.position.x = float(self.bbox.center.position.x) - ros_msg.bbox.center.position.y = float(self.bbox.center.position.y) - ros_msg.bbox.center.position.z = float(self.bbox.center.position.z) - ros_msg.bbox.center.orientation = ROSQuaternion() - ros_msg.bbox.center.orientation.x = float(self.bbox.center.orientation.x) - ros_msg.bbox.center.orientation.y = float(self.bbox.center.orientation.y) - ros_msg.bbox.center.orientation.z = float(self.bbox.center.orientation.z) - ros_msg.bbox.center.orientation.w = float(self.bbox.center.orientation.w) - ros_msg.bbox.size = ROSVector3() - ros_msg.bbox.size.x = float(self.bbox.size.x) - ros_msg.bbox.size.y = float(self.bbox.size.y) - ros_msg.bbox.size.z = float(self.bbox.size.z) - - # Set results (object hypotheses) - for result in self.results: - ros_result = ROSObjectHypothesisWithPose() - ros_result.hypothesis = ROSObjectHypothesis() - ros_result.hypothesis.class_id = str(result.hypothesis.class_id) - ros_result.hypothesis.score = float(result.hypothesis.score) - ros_msg.results.append(ros_result) - - # Set ID if available - if hasattr(self, "id"): - ros_msg.id = str(self.id) - - return ros_msg From 9803c070f3f87c72fce84bc48c534474562d0c38 Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Tue, 13 Jan 2026 03:33:48 -0800 Subject: [PATCH 15/19] fixed last of ivan's comment --- .../type/detection2d/imageDetections2D.py | 71 +------------------ .../detection/type/detection2d/seg.py | 4 +- dimos/perception/object_scene_registration.py | 7 +- 3 files changed, 7 insertions(+), 75 deletions(-) diff --git a/dimos/perception/detection/type/detection2d/imageDetections2D.py b/dimos/perception/detection/type/detection2d/imageDetections2D.py index c805c3ac7f..34033a9c50 100644 --- a/dimos/perception/detection/type/detection2d/imageDetections2D.py +++ b/dimos/perception/detection/type/detection2d/imageDetections2D.py @@ -16,11 +16,8 @@ from typing import TYPE_CHECKING, Any, Generic -import cv2 -import numpy as np from typing_extensions import TypeVar -from dimos.msgs.sensor_msgs import Image from dimos.perception.detection.type.detection2d.base import Detection2D from dimos.perception.detection.type.detection2d.bbox import Detection2DBBox from dimos.perception.detection.type.detection2d.person import Detection2DPerson @@ -30,6 +27,7 @@ if TYPE_CHECKING: from ultralytics.engine.results import Results + from dimos.msgs.sensor_msgs import Image from dimos.msgs.vision_msgs import Detection2DArray T2D = TypeVar("T2D", bound=Detection2D, default=Detection2DBBox) @@ -94,70 +92,3 @@ def from_ultralytics_result( detections.append(detection) return ImageDetections2D(image=image, detections=detections) - - def overlay(self, alpha: float = 0.4) -> Image: - """Overlay detection bboxes and masks onto the image. - - Args: - alpha: Transparency for mask overlay (default: 0.4) - - Returns: - Image with detection bboxes, masks, and labels drawn - """ - img = self.image.to_opencv().copy() - img = cv2.cvtColor(img, cv2.COLOR_BGR2RGB) - - for i, det in enumerate(self.detections): - track_id = det.track_id if hasattr(det, "track_id") else i - name = det.name if hasattr(det, "name") else "" - confidence = det.confidence if hasattr(det, "confidence") else 0.0 - - # Generate consistent color from track_id - np.random.seed(abs(track_id) if track_id >= 0 else i) - color = tuple(np.random.randint(50, 255, 3).tolist()) - - # Draw mask if available - if hasattr(det, "mask") and det.mask is not None: - mask = det.mask - mask_indices = mask > 0 - if np.any(mask_indices): - # Create colored mask overlay - colored_mask = np.zeros_like(img) - colored_mask[mask_indices] = color - img[mask_indices] = cv2.addWeighted( - img[mask_indices], 1 - alpha, colored_mask[mask_indices], alpha, 0 - ) - - # Draw contour - mask_uint8 = mask.astype(np.uint8) if mask.dtype == bool else mask - contours, _ = cv2.findContours( - mask_uint8, cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_SIMPLE - ) - cv2.drawContours(img, contours, -1, color, 2) - - # Draw bbox - x1, y1, x2, y2 = map(int, det.bbox) # type: ignore[attr-defined] - cv2.rectangle(img, (x1, y1), (x2, y2), color, 2) - - # Draw label - label = f"{name}" if name else f"ID:{track_id}" - if track_id >= 0: - label += f":{track_id}" - if confidence > 0: - label += f" ({confidence:.2f})" - - (text_w, text_h), baseline = cv2.getTextSize(label, cv2.FONT_HERSHEY_SIMPLEX, 0.5, 1) - cv2.rectangle(img, (x1, y1 - text_h - baseline - 2), (x1 + text_w, y1), color, -1) - cv2.putText( - img, - label, - (x1, y1 - baseline - 2), - cv2.FONT_HERSHEY_SIMPLEX, - 0.5, - (255, 255, 255), - 1, - ) - - return Image.from_numpy( - img, format=self.image.format, ts=self.image.ts, frame_id=self.image.frame_id - ) diff --git a/dimos/perception/detection/type/detection2d/seg.py b/dimos/perception/detection/type/detection2d/seg.py index 4de4fd2098..21f8e8e689 100644 --- a/dimos/perception/detection/type/detection2d/seg.py +++ b/dimos/perception/detection/type/detection2d/seg.py @@ -192,8 +192,8 @@ def to_points_annotation(self) -> list[PointsAnnotation]: annotations.append( PointsAnnotation( timestamp=to_ros_stamp(self.ts), - outline_color=Color.from_string(self.name, alpha=1.0, brightness=1.25), - fill_color=Color.from_string(self.name, alpha=0.4), + outline_color=Color.from_string(str(self.class_id), alpha=1.0, brightness=1.25), + fill_color=Color.from_string(str(self.track_id), alpha=0.4), thickness=1.0, points_length=len(points), points=points, diff --git a/dimos/perception/object_scene_registration.py b/dimos/perception/object_scene_registration.py index 830f186bc0..c21e31bf33 100644 --- a/dimos/perception/object_scene_registration.py +++ b/dimos/perception/object_scene_registration.py @@ -20,6 +20,7 @@ from dimos.core import In, Out, rpc from dimos.core.skill_module import SkillModule +from dimos.msgs.foxglove_msgs import ImageAnnotations from dimos.msgs.sensor_msgs import CameraInfo, Image, PointCloud2 from dimos.msgs.std_msgs import Header from dimos.msgs.vision_msgs import Detection2DArray, Detection3DArray @@ -48,7 +49,7 @@ class ObjectSceneRegistrationModule(SkillModule): detections_2d: Out[Detection2DArray] detections_3d: Out[Detection3DArray] - overlay: Out[Image] + overlay: Out[ImageAnnotations] pointcloud: Out[PointCloud2] _detector: Yoloe2DDetector | None = None @@ -190,8 +191,8 @@ def _process_images(self, color_msg: Image, depth_msg: Image) -> None: ) self.detections_2d.publish(detections_2d_msg) - overlay_image = detections_2d.overlay() - self.overlay.publish(overlay_image) + overlay_annotations = detections_2d.to_foxglove_annotations() + self.overlay.publish(overlay_annotations) # Process 3D detections self._process_3d_detections(detections_2d, color_image, depth_image) From ffa283372c5cf3a225579c2eac3207f5d0a3b71a Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Tue, 13 Jan 2026 11:35:07 -0800 Subject: [PATCH 16/19] remove all to_ros_msgs stuff in this commit --- dimos/msgs/vision_msgs/Detection3DArray.py | 63 +++------------------- 1 file changed, 7 insertions(+), 56 deletions(-) diff --git a/dimos/msgs/vision_msgs/Detection3DArray.py b/dimos/msgs/vision_msgs/Detection3DArray.py index 75826d75b2..2eba82204d 100644 --- a/dimos/msgs/vision_msgs/Detection3DArray.py +++ b/dimos/msgs/vision_msgs/Detection3DArray.py @@ -11,66 +11,17 @@ # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and # limitations under the License. -from __future__ import annotations +from dimos_lcm.vision_msgs.Detection3DArray import Detection3DArray as LCMDetection3DArray -from dimos_lcm.vision_msgs.Detection3DArray import ( # type: ignore[import-untyped] - Detection3DArray as LCMDetection3DArray, -) - -try: - from std_msgs.msg import Header as ROSHeader # type: ignore[attr-defined] - from vision_msgs.msg import ( # type: ignore[import-untyped] - Detection3DArray as ROSDetection3DArray, # type: ignore[attr-defined] - ) -except ImportError: - ROSHeader = None # type: ignore[assignment, misc] - ROSDetection3DArray = None # type: ignore[assignment, misc] - -from dimos.msgs.vision_msgs.Detection3D import Detection3D +from dimos.types.timestamped import to_timestamp class Detection3DArray(LCMDetection3DArray): # type: ignore[misc] msg_name = "vision_msgs.Detection3DArray" - def __init__(self, **kwargs) -> None: # type: ignore[no-untyped-def] - """Initialize with fresh mutable objects to avoid shared state.""" - super().__init__() - # Create fresh instances to avoid shared mutable state from LCM class defaults - from dimos_lcm.std_msgs import Header - - self.header = Header() - from dimos.msgs.vision_msgs import Detection3D - - self.detections: list[Detection3D] = [] - - # Apply any kwargs - for key, value in kwargs.items(): - setattr(self, key, value) - - def to_ros_msg(self) -> ROSDetection3DArray: - """Convert to ROS vision_msgs/Detection3DArray message. - - Returns: - ROS Detection3DArray message - """ - ros_msg = ROSDetection3DArray() - - # Set header - ros_msg.header = ROSHeader() - ros_msg.header.frame_id = self.header.frame_id - ros_msg.header.stamp.sec = self.header.stamp.sec - ros_msg.header.stamp.nanosec = self.header.stamp.nsec - - # Convert each detection - for det in self.detections: - # Wrap in our Detection3D class if needed to get to_ros_msg - if not isinstance(det, Detection3D): - det = Detection3D( - header=det.header, - results=det.results, - bbox=det.bbox, - id=getattr(det, "id", ""), - ) - ros_msg.detections.append(det.to_ros_msg()) + # for _get_field_type() to work when decoding in _decode_one() + __annotations__ = LCMDetection3DArray.__annotations__ - return ros_msg + @property + def ts(self) -> float: + return to_timestamp(self.header.stamp) From 371a550ee6ff33c61feafd07e42db3396e0f7533 Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Tue, 13 Jan 2026 19:23:47 -0800 Subject: [PATCH 17/19] passed Ivan's detector tests --- dimos/perception/detection/detectors/conftest.py | 7 +++++++ .../perception/detection/detectors/test_bbox_detectors.py | 2 +- 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/dimos/perception/detection/detectors/conftest.py b/dimos/perception/detection/detectors/conftest.py index 9cb600aeff..6a2c041a8b 100644 --- a/dimos/perception/detection/detectors/conftest.py +++ b/dimos/perception/detection/detectors/conftest.py @@ -17,6 +17,7 @@ from dimos.msgs.sensor_msgs import Image from dimos.perception.detection.detectors.person.yolo import YoloPersonDetector from dimos.perception.detection.detectors.yolo import Yolo2DDetector +from dimos.perception.detection.detectors.yoloe import Yoloe2DDetector, YoloePromptMode from dimos.utils.data import get_data @@ -36,3 +37,9 @@ def person_detector(): def bbox_detector(): """Create a Yolo2DDetector instance for general object detection.""" return Yolo2DDetector() + + +@pytest.fixture(scope="session") +def yoloe_detector(): + """Create a Yoloe2DDetector instance for general object detection.""" + return Yoloe2DDetector(prompt_mode=YoloePromptMode.LRPC) diff --git a/dimos/perception/detection/detectors/test_bbox_detectors.py b/dimos/perception/detection/detectors/test_bbox_detectors.py index bd9c1358b5..4047e35e7b 100644 --- a/dimos/perception/detection/detectors/test_bbox_detectors.py +++ b/dimos/perception/detection/detectors/test_bbox_detectors.py @@ -17,7 +17,7 @@ from dimos.perception.detection.type import Detection2D, ImageDetections2D -@pytest.fixture(params=["bbox_detector", "person_detector"], scope="session") +@pytest.fixture(params=["bbox_detector", "person_detector", "yoloe_detector"], scope="session") def detector(request): """Parametrized fixture that provides both bbox and person detectors.""" return request.getfixturevalue(request.param) From 9284cea26a6c6f4351cf4bd27e3ae31997c44039 Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Tue, 13 Jan 2026 19:24:10 -0800 Subject: [PATCH 18/19] added README for depth camera integration --- .../sensors/camera/realsense/README.md | 9 ++ docs/depth_camera_integration.md | 147 ++++++++++++++++++ 2 files changed, 156 insertions(+) create mode 100644 dimos/hardware/sensors/camera/realsense/README.md create mode 100644 docs/depth_camera_integration.md diff --git a/dimos/hardware/sensors/camera/realsense/README.md b/dimos/hardware/sensors/camera/realsense/README.md new file mode 100644 index 0000000000..665833047e --- /dev/null +++ b/dimos/hardware/sensors/camera/realsense/README.md @@ -0,0 +1,9 @@ +# RealSense SDK Install + +1) Install the Intel RealSense SDK: + - https://github.com/IntelRealSense/librealsense + +2) Install the Python bindings: + ```bash + pip install pyrealsense2 + ``` diff --git a/docs/depth_camera_integration.md b/docs/depth_camera_integration.md new file mode 100644 index 0000000000..1c8760d5cb --- /dev/null +++ b/docs/depth_camera_integration.md @@ -0,0 +1,147 @@ +# Depth Camera Integration Guide + +This folder contains camera drivers and modules for RGB-D (depth) cameras such as RealSense and ZED. +Use this guide to add a new depth camera, wire TF correctly, and publish the required streams. + +## Add a New Depth Camera + +1) **Create a new driver module** + - Path: `dimos/dimos/hardware/sensors/camera//camera.py` + - Export a blueprint in `/__init__.py` (match the `realsense` / `zed` pattern). + +2) **Define config** + - Inherit from `ModuleConfig` and `DepthCameraConfig`: + ```python + @dataclass + class MyDepthCameraConfig(ModuleConfig, DepthCameraConfig): + width: int = 1280 + height: int = 720 + fps: int = 15 + camera_name: str = "camera" + base_frame_id: str = "base_link" + base_transform: Transform | None = field(default_factory=default_base_transform) + align_depth_to_color: bool = True + enable_depth: bool = True + enable_pointcloud: bool = False + pointcloud_fps: float = 5.0 + camera_info_fps: float = 1.0 + ``` + +3) **Implement the module** + - Inherit from `DepthCameraHardware` and `Module` (see `RealSenseCamera` / `ZEDCamera`). + - Provide these outputs (matching `RealSenseCamera` / `ZEDCamera`): + - `color_image: Out[Image]` + - `depth_image: Out[Image]` + - `pointcloud: Out[PointCloud2]` (optional, can be disabled by config) + - `camera_info: Out[CameraInfo]` + - `depth_camera_info: Out[CameraInfo]` + - Implement RPCs: + - `start()` / `stop()` + - `get_color_camera_info()` / `get_depth_camera_info()` + - `get_depth_scale()` (meters per depth unit) + +4) **Publish frames** + - Color images: `Image(format=ImageFormat.RGB, frame_id=_color_optical_frame)` + - Depth images: + - If `align_depth_to_color`: use `_color_optical_frame` + - Else: use `_depth_optical_frame` + - CameraInfo frame_id must match the image frame_id you publish. + +5) **Publish camera info** + - Build `CameraInfo` from camera intrinsics. + - Publish at `camera_info_fps`. + +6) **Publish pointcloud (optional)** + - Use `PointCloud2.from_rgbd(color_image, depth_image, camera_info, depth_scale)`. + - Publish at `pointcloud_fps`. + +## TF: Required Frames and Transforms + +Frame names are defined by the abstract depth camera spec (`dimos/dimos/hardware/sensors/camera/spec.py`). +Use the properties below to ensure consistent naming: + +- `_camera_link`: base link for the camera module (usually `{camera_name}_link`) +- `_color_frame`: non-optical color frame +- `_color_optical_frame`: optical color frame +- `_depth_frame`: non-optical depth frame +- `_depth_optical_frame`: optical depth frame + +Recommended transform chain (publish every frame or at your preferred TF rate): + +1) **Mounting transform** (from config): + - `base_frame_id -> _camera_link` + - Use `config.base_transform` if provided + +2) **Depth frame** + - `_camera_link -> _depth_frame` (identity unless the camera provides extrinsics) + - `_depth_frame -> _depth_optical_frame` using `OPTICAL_ROTATION` + +3) **Color frame** + - `_camera_link -> _color_frame` (from extrinsics, or identity if unavailable) + - `_color_frame -> _color_optical_frame` using `OPTICAL_ROTATION` + +Notes: +- If you align depth to color, keep TFs the same but publish depth images in `_color_optical_frame`. +- Ensure `color_image.frame_id` and `camera_info.frame_id` match; same for depth. + +## Required Streams / Topics + +Use these stream names in your module and attach transports as needed. +Default LCM topics in `realsense` / `zed` demos are shown below. + +| Stream name | Type | Suggested topic | Frame_id source | +|-------------------|--------------|-------------------------|-----------------| +| `color_image` | `Image` | `/camera/color` | `_color_optical_frame` | +| `depth_image` | `Image` | `/camera/depth` | `_depth_optical_frame` or `_color_optical_frame` | +| `pointcloud` | `PointCloud2`| `/camera/pointcloud` | (derived from CameraInfo) | +| `camera_info` | `CameraInfo` | `/camera/color_info` | matches `color_image` | +| `depth_camera_info` | `CameraInfo` | `/camera/depth_info` | matches `depth_image` | + +For `ObjectSceneRegistrationModule`, the required inputs are: +- `color_image` +- `depth_image` +- `camera_info` +- TF tree resolving `target_frame` to `color_image.frame_id` + +## Object Scene Registration (Brief Overview) + +`ObjectSceneRegistrationModule` consumes synchronized RGB + depth + camera intrinsics and produces: +- 2D detections (YOLO‑E) +- 3D detections (projected via depth + intrinsics + TF) +- Overlay annotations and aggregated pointclouds + +See: +- `dimos/dimos/perception/object_scene_registration.py` +- `dimos/dimos/perception/demo_object_scene_registration.py` + +Quick wiring example: + +```python +from dimos.core.blueprints import autoconnect +from dimos.hardware.sensors.camera.realsense import realsense_camera +from dimos.perception.object_scene_registration import object_scene_registration_module + +pipeline = autoconnect( + realsense_camera(enable_pointcloud=False), + object_scene_registration_module(target_frame="world"), +) +``` + +Run the demo via CLI: +```bash +dimos run demo-object-scene-registration +``` + +## Foxglove (Viewer) + +Install Foxglove from: +- https://foxglove.dev/download + +## Modules and Skills (Short Intro) + +- **Modules** are typed components with `In[...]` / `Out[...]` streams and `start()` / `stop()` lifecycles. +- **Skills** are callable methods (decorated with `@skill`) exposed by `SkillModule` for agents. + +Reference: +- Modules overview: `dimos/docs/concepts/modules.md` +- TF fundamentals: `dimos/docs/api/transforms.md` From 257cbecc97bb927d01c2b7acdc0ed926c7e24f92 Mon Sep 17 00:00:00 2001 From: alexlin2 Date: Wed, 14 Jan 2026 20:58:16 -0500 Subject: [PATCH 19/19] fixed last of Stash's comments --- dimos/msgs/sensor_msgs/Image.py | 9 --------- dimos/perception/detection/type/detection3d/bbox.py | 2 +- dimos/perception/detection/type/detection3d/object.py | 4 ++-- 3 files changed, 3 insertions(+), 12 deletions(-) diff --git a/dimos/msgs/sensor_msgs/Image.py b/dimos/msgs/sensor_msgs/Image.py index a4a71d3565..de3e7abeca 100644 --- a/dimos/msgs/sensor_msgs/Image.py +++ b/dimos/msgs/sensor_msgs/Image.py @@ -252,15 +252,6 @@ def frame_id(self) -> str: def frame_id(self, value: str) -> None: self._impl.frame_id = str(value) - def from_ros_header(self, header) -> None: # type: ignore[no-untyped-def] - """Set the image timestamp and frame_id from a ROS header. - - Args: - header: ROS std_msgs/Header message with stamp and frame_id fields - """ - self.ts = header.stamp.sec + (header.stamp.nanosec / 1_000_000_000) - self.frame_id = header.frame_id - @property def ts(self) -> float: return self._impl.ts diff --git a/dimos/perception/detection/type/detection3d/bbox.py b/dimos/perception/detection/type/detection3d/bbox.py index 15a23ce7c2..cf7f4ea3cc 100644 --- a/dimos/perception/detection/type/detection3d/bbox.py +++ b/dimos/perception/detection/type/detection3d/bbox.py @@ -52,7 +52,7 @@ def pose(self) -> PoseStamped: orientation=self.orientation, ) - def to_ros_detection3d(self) -> Detection3D: + def to_detection3d_msg(self) -> Detection3D: """Convert to ROS Detection3D message.""" msg = Detection3D() msg.header = Header(self.ts, self.frame_id) diff --git a/dimos/perception/detection/type/detection3d/object.py b/dimos/perception/detection/type/detection3d/object.py index eb2cb104e3..00d4d88661 100644 --- a/dimos/perception/detection/type/detection3d/object.py +++ b/dimos/perception/detection/type/detection3d/object.py @@ -103,7 +103,7 @@ def scene_entity_label(self) -> str: return f"{self.name} ({self.detections_count})" return f"{self.track_id}/{self.name} ({self.confidence:.0%})" - def to_ros_detection3d(self) -> ROSDetection3D: + def to_detection3d_msg(self) -> ROSDetection3D: """Convert to ROS Detection3D message.""" obb = self.get_oriented_bounding_box() # type: ignore[no-untyped-call] orientation = Quaternion.from_rotation_matrix(obb.R) @@ -358,6 +358,6 @@ def to_detection3d_array(objects: list[Object]) -> Detection3DArray: array.header = Header(objects[0].ts, objects[0].frame_id) for obj in objects: - array.detections.append(obj.to_ros_detection3d()) + array.detections.append(obj.to_detection3d_msg()) return array