From 20ab83a3644a59152fcd93e6244747ac5147d616 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 02:38:03 +0200 Subject: [PATCH 01/30] Add MuJoCo scene playground with Viser nav --- dimos/mapping/mesh_scene.py | 591 ++++++++++++++ dimos/mapping/pointcloud_map_module.py | 77 ++ dimos/mapping/usdz_to_mjcf.py | 309 +++++++ dimos/robot/all_blueprints.py | 1 + dimos/simulation/engines/mujoco_engine.py | 109 ++- dimos/simulation/engines/mujoco_shm.py | 8 +- dimos/simulation/engines/mujoco_sim_module.py | 208 ++++- dimos/simulation/mujoco_scene_playground.py | 213 +++++ dimos/visualization/viser/camera.py | 207 +++++ dimos/visualization/viser/robot_meshes.py | 230 ++++++ dimos/visualization/viser/splat.py | 217 +++++ .../viser/viser_render_module.py | 765 ++++++++++++++++++ .../web/websocket_vis/websocket_vis_module.py | 7 - pyproject.toml | 8 + uv.lock | 484 ++++++++++- 15 files changed, 3384 insertions(+), 50 deletions(-) create mode 100644 dimos/mapping/mesh_scene.py create mode 100644 dimos/mapping/pointcloud_map_module.py create mode 100644 dimos/mapping/usdz_to_mjcf.py create mode 100644 dimos/simulation/mujoco_scene_playground.py create mode 100644 dimos/visualization/viser/camera.py create mode 100644 dimos/visualization/viser/robot_meshes.py create mode 100644 dimos/visualization/viser/splat.py create mode 100644 dimos/visualization/viser/viser_render_module.py diff --git a/dimos/mapping/mesh_scene.py b/dimos/mapping/mesh_scene.py new file mode 100644 index 0000000000..9036813365 --- /dev/null +++ b/dimos/mapping/mesh_scene.py @@ -0,0 +1,591 @@ +# 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. + +"""Load a 3D scene mesh from disk for ray-casting + visualization. + +Supports: + * ``.glb`` / ``.gltf`` / ``.obj`` / ``.ply`` / ``.stl`` — via Open3D's + ``read_triangle_mesh``. + * ``.usdz`` / ``.usd`` / ``.usdc`` — via ``pxr.Usd`` (install ``usd-core``). + +Returned form is a single concatenated ``open3d.geometry.TriangleMesh`` +in world frame, with optional scale + Y-up→Z-up + translation applied. + +The same mesh can feed browser visualization, ray-casting, and MJCF +collision wrapping so the visual and physical scene share one transform. +""" + +from __future__ import annotations + +from dataclasses import dataclass +from pathlib import Path +from typing import Any + +import numpy as np +import open3d as o3d + + +@dataclass +class SceneMeshAlignment: + """How to transform a raw scene mesh into dimos world frame. + + Apply order: scale → rotation (y_up swap then zyx euler) → translation. + """ + + scale: float = 1.0 + """Multiplicative scale. Use 0.01 if the source is centimeters.""" + + rotation_zyx_deg: tuple[float, float, float] = (0.0, 0.0, 0.0) + """Yaw / pitch / roll in degrees, applied after the y_up swap.""" + + translation: tuple[float, float, float] = (0.0, 0.0, 0.0) + """World-frame offset applied last.""" + + y_up: bool = True + """Most exporters (Blender, glTF, Apple USDZ) are Y-up. When ``True`` + rotate the mesh -90 deg about world X to match dimos's Z-up convention.""" + + +def _world_rotation(alignment: SceneMeshAlignment) -> np.ndarray: + """Compose the y-up swap + ZYX Euler into one 3x3.""" + rad = np.radians(alignment.rotation_zyx_deg) + cz, sz = np.cos(rad[0]), np.sin(rad[0]) + cy, sy = np.cos(rad[1]), np.sin(rad[1]) + cx, sx = np.cos(rad[2]), np.sin(rad[2]) + rz = np.array([[cz, -sz, 0], [sz, cz, 0], [0, 0, 1]], dtype=np.float64) + ry = np.array([[cy, 0, sy], [0, 1, 0], [-sy, 0, cy]], dtype=np.float64) + rx = np.array([[1, 0, 0], [0, cx, -sx], [0, sx, cx]], dtype=np.float64) + rzyx = rz @ ry @ rx + if alignment.y_up: + y_to_z = np.array( + [[1, 0, 0], [0, 0, -1], [0, 1, 0]], + dtype=np.float64, + ) + return rzyx @ y_to_z + return rzyx + + +def _average_per_face_vertex( + per_fv: np.ndarray, face_verts: np.ndarray, n_verts: int +) -> np.ndarray: + """Scatter-average ``(n_face_verts, 3)`` values onto ``(n_verts, 3)`` indices.""" + out = np.zeros((n_verts, 3), dtype=np.float32) + counts = np.zeros(n_verts, dtype=np.int32) + np.add.at(out, face_verts, per_fv) + np.add.at(counts, face_verts, 1) + counts = np.maximum(counts, 1)[:, None] + return out / counts + + +def _color_from_displaycolor( + mesh: Any, + n_verts: int, + face_counts: np.ndarray, + face_verts: np.ndarray, +) -> np.ndarray | None: + """Per-vertex RGB from ``primvars:displayColor`` if present and valued. + + Handles the four standard interpolations: ``constant`` / ``vertex`` / + ``uniform`` / ``faceVarying``. Returns ``None`` when the primvar + isn't authored with a value (Sketchfab USDZ exports typically declare + the primvar but leave it empty — colors live on the bound material). + """ + from pxr import UsdGeom + + pv = UsdGeom.PrimvarsAPI(mesh.GetPrim()).GetPrimvar("displayColor") + if not pv or not pv.HasValue(): + return None + raw = pv.Get() + if raw is None: + return None + colors = np.asarray(raw, dtype=np.float32) + if colors.ndim != 2 or colors.shape[1] != 3 or colors.size == 0: + return None + interp = pv.GetInterpolation() + + if interp == UsdGeom.Tokens.constant: + return np.tile(colors[0:1], (n_verts, 1)) + + if interp == UsdGeom.Tokens.vertex and len(colors) == n_verts: + return colors + + if interp == UsdGeom.Tokens.uniform and len(colors) == len(face_counts): + per_fv = np.repeat(colors, face_counts, axis=0) + return _average_per_face_vertex(per_fv, face_verts, n_verts) + + if interp == UsdGeom.Tokens.faceVarying and len(colors) == len(face_verts): + return _average_per_face_vertex(colors, face_verts, n_verts) + + return None + + +def _color_from_material( + prim: Any, material_color_cache: dict[str, np.ndarray | None] +) -> np.ndarray | None: + """Per-prim RGB from the bound material's ``inputs:diffuseColor``. + + Walks ``UsdShadeMaterialBindingAPI`` → surface shader → ``inputs:diffuseColor``, + handling ``UsdPreviewSurface`` (the format Sketchfab USDZ uses). Texture + inputs aren't sampled — if ``diffuseColor`` is connected to a ``UsdUVTexture`` + rather than authored as a literal, this returns ``None`` and the caller + falls back to the next strategy. + + Results are cached per material path so we don't re-walk the shader graph + for every prim that shares a material. + """ + from pxr import UsdShade + + mat_api = UsdShade.MaterialBindingAPI(prim) + bound = mat_api.ComputeBoundMaterial()[0] + if not bound: + return None + mat_path = str(bound.GetPath()) + if mat_path in material_color_cache: + return material_color_cache[mat_path] + + color = _resolve_diffuse_color(bound) + material_color_cache[mat_path] = color + return color + + +def _resolve_diffuse_color(material: Any) -> np.ndarray | None: + """Pull a literal ``diffuseColor`` out of a UsdShade material's surface shader.""" + from pxr import UsdShade + + surface = material.ComputeSurfaceSource("")[0] + if not surface: + return None + diffuse_input = surface.GetInput("diffuseColor") + if not diffuse_input: + return None + # If the input is connected (texture-driven), bail — we don't sample images. + if diffuse_input.HasConnectedSource(): + connected = diffuse_input.GetConnectedSource()[0] + if connected: + shader = UsdShade.Shader(connected.GetPrim()) + if shader and shader.GetIdAttr().Get() == "UsdUVTexture": + return None + val = diffuse_input.Get() + if val is None: + return None + arr = np.asarray(val, dtype=np.float32).reshape(-1) + if arr.size != 3: + return None + return arr # (3,) RGB in [0, 1] + + +def _load_usd_mesh(path: Path) -> o3d.geometry.TriangleMesh: + """Walk every Mesh prim in a USD stage and concatenate to one o3d mesh. + + Also extracts per-vertex colors from ``primvars:displayColor`` when + present so downstream consumers (viser) can render textured-looking + Sketchfab exports without having to chase materials/textures. + """ + try: + from pxr import Usd, UsdGeom + except ImportError as e: + raise ImportError("loading .usdz/.usd requires usd-core: `uv pip install usd-core`") from e + + stage = Usd.Stage.Open(str(path)) + if stage is None: + raise RuntimeError(f"could not open USD stage: {path}") + + all_pts: list[np.ndarray] = [] + all_tris: list[np.ndarray] = [] + all_colors: list[np.ndarray] = [] + any_color = False + vtx_offset = 0 + material_color_cache: dict[str, np.ndarray | None] = {} + + for prim in stage.Traverse(): + if not prim.IsA(UsdGeom.Mesh): + continue + mesh = UsdGeom.Mesh(prim) + pts_attr = mesh.GetPointsAttr().Get() + if pts_attr is None or len(pts_attr) == 0: + continue + pts = np.asarray(pts_attr, dtype=np.float32) + face_verts = np.asarray(mesh.GetFaceVertexIndicesAttr().Get(), dtype=np.int32) + face_counts = np.asarray(mesh.GetFaceVertexCountsAttr().Get(), dtype=np.int32) + + # Bake the prim's local-to-world transform into the points so the + # composite scene comes out in stage-root coordinates. + xform = UsdGeom.Xformable(prim).ComputeLocalToWorldTransform(Usd.TimeCode.Default()) + m = np.asarray(xform, dtype=np.float64).T # USD matrices are row-major + pts_h = np.hstack([pts, np.ones((len(pts), 1), dtype=np.float32)]) + pts_world = (m @ pts_h.T).T[:, :3].astype(np.float32) + + # Per-prim color resolution. Try in order: + # 1. ``primvars:displayColor`` (vertex / faceVarying / uniform / constant) + # 2. Bound material's ``inputs:diffuseColor`` (UsdPreviewSurface — what + # Sketchfab USDZ uses, with one constant color per material). + # 3. Neutral grey fallback. + prim_colors = _color_from_displaycolor(mesh, len(pts), face_counts, face_verts) + if prim_colors is None: + mat_color = _color_from_material(prim, material_color_cache) + if mat_color is not None: + prim_colors = np.tile(mat_color[None, :], (len(pts), 1)) + if prim_colors is not None: + any_color = True + else: + prim_colors = np.full((len(pts), 3), 0.7, dtype=np.float32) + + # USD allows quads / n-gons; fan-triangulate so o3d gets pure tris. + tris: list[tuple[int, int, int]] = [] + cursor = 0 + for n in face_counts: + for k in range(1, n - 1): + tris.append( + ( + int(face_verts[cursor]) + vtx_offset, + int(face_verts[cursor + k]) + vtx_offset, + int(face_verts[cursor + k + 1]) + vtx_offset, + ) + ) + cursor += n + + if not tris: + continue + all_pts.append(pts_world) + all_tris.append(np.asarray(tris, dtype=np.int32)) + all_colors.append(prim_colors) + vtx_offset += len(pts_world) + + if not all_pts: + raise RuntimeError(f"no Mesh prims with triangles found in {path}") + + pts = np.concatenate(all_pts, axis=0).astype(np.float64) + tris = np.concatenate(all_tris, axis=0) + + mesh = o3d.geometry.TriangleMesh() + mesh.vertices = o3d.utility.Vector3dVector(pts) + mesh.triangles = o3d.utility.Vector3iVector(tris) + if any_color: + colors = np.concatenate(all_colors, axis=0).astype(np.float64) + mesh.vertex_colors = o3d.utility.Vector3dVector(np.clip(colors, 0.0, 1.0)) + return mesh + + +def load_scene_mesh( + path: str | Path, + alignment: SceneMeshAlignment | None = None, +) -> o3d.geometry.TriangleMesh: + """Load a scene mesh from disk and apply alignment to put it in dimos world frame. + + Args: + path: file path. Supported extensions: ``.usdz``, ``.usd``, ``.usdc``, + ``.glb``, ``.gltf``, ``.obj``, ``.ply``, ``.stl``. + alignment: scale / rotation / translation to apply. + + Returns: + an ``open3d.geometry.TriangleMesh`` in dimos world frame with vertex + normals computed. + """ + path = Path(path) + if not path.exists(): + raise FileNotFoundError(f"scene mesh not found: {path}") + suffix = path.suffix.lower() + if suffix in {".usdz", ".usd", ".usdc", ".usda"}: + mesh = _load_usd_mesh(path) + elif suffix in {".glb", ".gltf"}: + # GEOMETRY-ONLY GLB load. Used by floor-z probing and ``MeshCameraModule`` + # ray-casting — neither needs PBR materials. The Viser viewer takes the + # GLB-native path (``add_glb`` from raw bytes) so it doesn't go through + # here. ``trimesh.load(path, force="mesh")`` would flatten the scene by + # decompressing every embedded texture and sampling per-vertex colors — + # for a scene with hundreds of 4K PBR textures (~895 MP total in dimos's + # office mesh) that allocates ~10 GB transiently and OOMs 32 GB boxes. + # We open in Scene mode (no flattening, no texture decode), walk the + # instance graph applying each instance's world transform, and emit a + # single concatenated mesh — peak stays under ~1 GB. + import trimesh + + scene_or_mesh = trimesh.load(str(path)) + if isinstance(scene_or_mesh, trimesh.Trimesh): + verts_world = np.asarray(scene_or_mesh.vertices, dtype=np.float64) + faces_world = np.asarray(scene_or_mesh.faces, dtype=np.int64) + else: + scene = scene_or_mesh + verts_chunks: list[np.ndarray] = [] + faces_chunks: list[np.ndarray] = [] + v_off = 0 + for node_name in scene.graph.nodes_geometry: + xform, geom_name = scene.graph[node_name] + geom = scene.geometry.get(geom_name) + if geom is None or not isinstance(geom, trimesh.Trimesh) or len(geom.faces) == 0: + continue + v_local = np.asarray(geom.vertices, dtype=np.float64) + f_local = np.asarray(geom.faces, dtype=np.int64) + m = np.asarray(xform, dtype=np.float64) + v_h = np.hstack([v_local, np.ones((len(v_local), 1), dtype=np.float64)]) + v_world = (m @ v_h.T).T[:, :3] + verts_chunks.append(v_world) + faces_chunks.append(f_local + v_off) + v_off += len(v_local) + if not verts_chunks: + raise RuntimeError(f"glTF loaded but no Trimesh instances found: {path}") + verts_world = np.concatenate(verts_chunks, axis=0) + faces_world = np.concatenate(faces_chunks, axis=0) + + mesh = o3d.geometry.TriangleMesh() + mesh.vertices = o3d.utility.Vector3dVector(verts_world) + mesh.triangles = o3d.utility.Vector3iVector(faces_world.astype(np.int32)) + else: + mesh = o3d.io.read_triangle_mesh(str(path)) + if len(mesh.triangles) == 0: + raise RuntimeError(f"o3d.io.read_triangle_mesh returned an empty mesh for {path}") + + align = alignment or SceneMeshAlignment() + if align.scale != 1.0: + mesh.scale(align.scale, center=np.zeros(3)) + rot = _world_rotation(align) + if not np.allclose(rot, np.eye(3)): + mesh.rotate(rot, center=np.zeros(3)) + if any(align.translation): + mesh.translate(np.asarray(align.translation, dtype=np.float64)) + + mesh.compute_vertex_normals() + return mesh + + +def make_raycasting_scene( + mesh: o3d.geometry.TriangleMesh, +) -> o3d.t.geometry.RaycastingScene: + """Wrap a TriangleMesh into Open3D's BVH-backed ray-casting scene.""" + scene = o3d.t.geometry.RaycastingScene() + scene.add_triangles(o3d.t.geometry.TriangleMesh.from_legacy(mesh)) + return scene + + +@dataclass +class ScenePrimMesh: + """One USD ``Mesh`` prim's geometry, ready to write to OBJ. + + Used by ``load_scene_prims`` to keep prims separate so MuJoCo can + treat each as its own (approximately convex) collision shape. When + the loader handles a non-USD format the input is returned as a + single-element list with the whole mesh in it. + """ + + name: str + """Sanitized identifier (safe for MJCF asset names) — typically the + USD prim path with non-alphanumerics replaced.""" + + vertices: np.ndarray + """``(N, 3)`` float32, in world frame after alignment.""" + + triangles: np.ndarray + """``(M, 3)`` int32 vertex indices.""" + + +def _load_glb_prims(path: Path, alignment: SceneMeshAlignment) -> list[ScenePrimMesh]: + """Enumerate per-instance prims from a glTF/GLB. + + ``trimesh.load(file.glb)`` returns a ``Scene`` whose ``graph`` records + the world transform for every geometry instance. Iterating + ``graph.nodes_geometry`` is the trimesh equivalent of USD's + ``stage.Traverse()`` — it yields one entry per instance, even when + multiple instances share the same underlying mesh (typical for chairs, + cabinets, etc.). Without this enumeration, ``trimesh.load(... force="mesh")`` + collapses the whole scene to one mesh and CoACD produces a single coarse + decomposition, which is essentially useless for collision against + multi-object scenes. + """ + import trimesh + + loaded = trimesh.load(str(path)) + R = _world_rotation(alignment) + T = np.asarray(alignment.translation, dtype=np.float64) + s = float(alignment.scale) + + if isinstance(loaded, trimesh.Trimesh): + # Single-mesh GLB (no scene graph). Treat as one prim. + pts = np.asarray(loaded.vertices, dtype=np.float64) + faces = np.asarray(loaded.faces, dtype=np.int32) + if len(faces) == 0: + return [] + pts_world = (R @ (s * pts).T).T + T + return [ + ScenePrimMesh( + name="scene", + vertices=pts_world.astype(np.float32), + triangles=faces, + ) + ] + + scene = loaded + prims: list[ScenePrimMesh] = [] + for node_name in scene.graph.nodes_geometry: + xform, geom_name = scene.graph[node_name] + geom = scene.geometry.get(geom_name) + if geom is None or not isinstance(geom, trimesh.Trimesh): + continue + if len(geom.faces) == 0: + continue + + pts_local = np.asarray(geom.vertices, dtype=np.float64) + faces = np.asarray(geom.faces, dtype=np.int32) + + # Local → scene-root via the instance transform. + m = np.asarray(xform, dtype=np.float64) + pts_h = np.hstack([pts_local, np.ones((len(pts_local), 1), dtype=np.float64)]) + pts_stage = (m @ pts_h.T).T[:, :3] + + # Scene-root → dimos world via SceneMeshAlignment. + pts_world = (R @ (s * pts_stage).T).T + T + + clean = "".join(c if c.isalnum() else "_" for c in str(node_name)) + prims.append( + ScenePrimMesh( + name=f"{clean}__{len(prims)}", + vertices=pts_world.astype(np.float32), + triangles=faces, + ) + ) + return prims + + +def load_scene_prims( + path: str | Path, + alignment: SceneMeshAlignment | None = None, +) -> list[ScenePrimMesh]: + """Load a USD/USDZ scene as one ``ScenePrimMesh`` per Mesh prim. + + Per-prim splitting is what MuJoCo wants for non-trivial scenes: + each prim's convex hull approximates the prim well, while the + convex hull of the *whole* scene is its bounding box. Falls back + to a single ScenePrimMesh for non-USD inputs (a single ``.obj`` or + ``.glb`` doesn't carry per-part semantics in our loader). + + Same alignment rules as ``load_scene_mesh``. + """ + path = Path(path) + align = alignment or SceneMeshAlignment() + suffix = path.suffix.lower() + + if suffix in {".glb", ".gltf"}: + return _load_glb_prims(path, align) + + if suffix not in {".usdz", ".usd", ".usdc", ".usda"}: + # Non-USD, non-glTF (e.g. .obj/.ply/.stl): one part, whole mesh. + whole = load_scene_mesh(path, alignment=align) + return [ + ScenePrimMesh( + name="scene", + vertices=np.asarray(whole.vertices, dtype=np.float32), + triangles=np.asarray(whole.triangles, dtype=np.int32), + ) + ] + + try: + from pxr import Usd, UsdGeom + except ImportError as e: + raise ImportError("loading .usdz/.usd requires usd-core: `uv pip install usd-core`") from e + + stage = Usd.Stage.Open(str(path)) + if stage is None: + raise RuntimeError(f"could not open USD stage: {path}") + + R = _world_rotation(align) + T = np.asarray(align.translation, dtype=np.float64) + s = float(align.scale) + + prims: list[ScenePrimMesh] = [] + for prim in stage.Traverse(): + if not prim.IsA(UsdGeom.Mesh): + continue + usd_mesh = UsdGeom.Mesh(prim) + pts_attr = usd_mesh.GetPointsAttr().Get() + if pts_attr is None or len(pts_attr) == 0: + continue + pts = np.asarray(pts_attr, dtype=np.float64) + face_verts = np.asarray(usd_mesh.GetFaceVertexIndicesAttr().Get(), dtype=np.int32) + face_counts = np.asarray(usd_mesh.GetFaceVertexCountsAttr().Get(), dtype=np.int32) + + # Local → stage-root via the USD prim's accumulated transform. + xform = UsdGeom.Xformable(prim).ComputeLocalToWorldTransform(Usd.TimeCode.Default()) + m = np.asarray(xform, dtype=np.float64).T + pts_h = np.hstack([pts, np.ones((len(pts), 1), dtype=np.float64)]) + pts_stage = (m @ pts_h.T).T[:, :3] + + # Stage-root → dimos world via SceneMeshAlignment (scale → rot → trans). + pts_world = (R @ (s * pts_stage).T).T + T + + # Triangulate any quads / n-gons (vertex indices are local to this prim now). + tris: list[tuple[int, int, int]] = [] + cursor = 0 + for n in face_counts: + for k in range(1, n - 1): + tris.append( + ( + int(face_verts[cursor]), + int(face_verts[cursor + k]), + int(face_verts[cursor + k + 1]), + ) + ) + cursor += n + if not tris: + continue + + # MJCF asset names: strip the leading slash, swap remaining + # path separators / dots for underscores. USD prim paths can + # collide on the same leaf; suffix the index so each is unique. + raw = str(prim.GetPath()).lstrip("/") + clean = "".join(c if c.isalnum() else "_" for c in raw) + prims.append( + ScenePrimMesh( + name=f"{clean}__{len(prims)}", + vertices=pts_world.astype(np.float32), + triangles=np.asarray(tris, dtype=np.int32), + ) + ) + + if not prims: + raise RuntimeError(f"no Mesh prims with triangles found in {path}") + return prims + + +def floor_z_under_origin( + scene_mesh_path: str | Path, + alignment: SceneMeshAlignment | None = None, +) -> float: + """Return the z of the first surface ``(x=0, y=0)`` falls onto. + + Casts one ray straight down from a high z; the first hit defines + the local floor at origin. Falls back to the mesh's bbox min-z + when origin is over a hole (or outside the bbox xy footprint). + Used by the GR00T sim blueprint to align the loaded scene with + the robot's default spawn pose so all three downstream views + (viser, mesh camera, MuJoCo physics) share one world frame. + """ + import open3d.core as o3c + + mesh = load_scene_mesh(scene_mesh_path, alignment=alignment) + scene = make_raycasting_scene(mesh) + rays = o3c.Tensor( + np.array([[0.0, 0.0, 1000.0, 0.0, 0.0, -1.0]], dtype=np.float32), + dtype=o3c.Dtype.Float32, + ) + t = float(scene.cast_rays(rays)["t_hit"].numpy()[0]) + if np.isfinite(t): + return 1000.0 - t + bb = mesh.get_axis_aligned_bounding_box() + return float(bb.min_bound[2]) + + +__all__ = [ + "SceneMeshAlignment", + "load_scene_mesh", + "make_raycasting_scene", +] diff --git a/dimos/mapping/pointcloud_map_module.py b/dimos/mapping/pointcloud_map_module.py new file mode 100644 index 0000000000..b0e050e7ec --- /dev/null +++ b/dimos/mapping/pointcloud_map_module.py @@ -0,0 +1,77 @@ +# Copyright 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. + +"""Generic pointcloud map module backed by DimOS's existing accumulator.""" + +from __future__ import annotations + +import time +from typing import Any + +from reactivex import interval +from reactivex.disposable import Disposable + +from dimos.core.core import rpc +from dimos.core.module import Module, ModuleConfig +from dimos.core.stream import In, Out +from dimos.mapping.pointclouds.accumulators.general import GeneralPointCloudAccumulator +from dimos.msgs.sensor_msgs.PointCloud2 import PointCloud2 + + +class PointCloudMapConfig(ModuleConfig): + voxel_size: float = 0.05 + publish_interval: float = 0.5 + + +class PointCloudMapModule(Module): + """Accumulate lidar pointclouds and publish a global map.""" + + config: PointCloudMapConfig + + lidar: In[PointCloud2] + global_map: Out[PointCloud2] + + def __init__(self, **kwargs: Any) -> None: + super().__init__(**kwargs) + self._accumulator = GeneralPointCloudAccumulator( + voxel_size=self.config.voxel_size, + global_config=self.config.g, + ) + + @rpc + def start(self) -> None: + super().start() + self.register_disposable(Disposable(self.lidar.subscribe(self._add_frame))) + self.register_disposable( + interval(self.config.publish_interval).subscribe(lambda _: self._publish()) + ) + + @rpc + def stop(self) -> None: + super().stop() + + def _add_frame(self, msg: PointCloud2) -> None: + self._accumulator.add(msg.pointcloud) + + def _publish(self) -> None: + self.global_map.publish( + PointCloud2( + pointcloud=self._accumulator.get_point_cloud(), + ts=time.time(), + frame_id="world", + ) + ) + + +__all__ = ["PointCloudMapConfig", "PointCloudMapModule"] diff --git a/dimos/mapping/usdz_to_mjcf.py b/dimos/mapping/usdz_to_mjcf.py new file mode 100644 index 0000000000..2566126fd3 --- /dev/null +++ b/dimos/mapping/usdz_to_mjcf.py @@ -0,0 +1,309 @@ +# 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. + +"""Bake a USDZ/GLB/OBJ scene mesh into an MJCF wrapper around a robot MJCF. + +MuJoCo only reads ``.stl`` / ``.obj`` / ``.msh`` meshes — not USD. This +module loads a scene mesh through the existing ``mesh_scene`` loader, +writes the welded geometry out as OBJ, and emits a tiny MJCF that +````s the robot MJCF and adds the scene mesh as a single +static collidable body. + +Pipeline: + + 1. ``load_scene_mesh()`` → ``open3d.geometry.TriangleMesh`` in dimos + world frame (Z-up, meters), with all per-prim transforms baked in. + 2. ``open3d.io.write_triangle_mesh()`` → OBJ on disk. + 3. Wrapper MJCF references both the robot MJCF (via absolute-path + ````) and the scene OBJ, declares one body with one mesh + geom (``contype=1 conaffinity=1`` — collides with anything that's + also enabled). ``meshdir`` / ``texturedir`` in the wrapper's + ```` are pinned to the robot MJCF's directory so the + robot's STLs still resolve through the include. + +Output is cached at ``~/.cache/dimos/scene_meshes//`` keyed on +the source mesh, robot MJCF, alignment params, and mesh directory. +""" + +from __future__ import annotations + +from dataclasses import asdict +import hashlib +from pathlib import Path + +import numpy as np +import open3d as o3d # type: ignore[import-untyped] + +from dimos.mapping.mesh_scene import SceneMeshAlignment +from dimos.utils.logging_config import setup_logger + +logger = setup_logger() + + +CACHE_DIR = Path.home() / ".cache" / "dimos" / "scene_meshes" + + +_WRAPPER_TEMPLATE = """\ + + + + +{asset_meshes} + + + +{scene_geoms} + + + +""" + +_ASSET_LINE = ' ' +_GEOM_LINE = ( + ' ' +) + + +def bake_scene_mjcf( + scene_mesh_path: str | Path, + robot_mjcf_path: str | Path, + alignment: SceneMeshAlignment | None = None, + meshdir: str | Path | None = None, + cache_root: Path | None = None, +) -> Path: + """Convert ``scene_mesh_path`` to OBJ and emit a wrapped MJCF. + + Args: + scene_mesh_path: ``.usdz`` / ``.glb`` / ``.obj`` etc. — anything + ``mesh_scene.load_scene_mesh`` accepts. + robot_mjcf_path: the base robot MJCF the wrapper will + ````. + alignment: scale / translation / rotation / y-up swap to bake + into the OBJ before MuJoCo sees it. Authoritative for all + three views (MuJoCo physics, viser, mesh camera) — the + blueprint passes the same ``SceneMeshAlignment`` to each + so the world frames agree to the millimeter. + meshdir: directory MuJoCo should resolve unqualified mesh + filenames against. ``None`` uses the robot MJCF's parent + directory. Blueprints for robot assets stored elsewhere + should pass this explicitly. + cache_root: override for the cache directory (defaults to + ``~/.cache/dimos/scene_meshes``). + + Returns: + Path to the wrapper MJCF. Pass this to ``MujocoSimModule`` + instead of the raw robot MJCF. + """ + scene_mesh_path = Path(scene_mesh_path).expanduser().resolve() + robot_mjcf_path = Path(robot_mjcf_path).expanduser().resolve() + align = alignment or SceneMeshAlignment() + + if not scene_mesh_path.exists(): + raise FileNotFoundError(f"scene mesh not found: {scene_mesh_path}") + if not robot_mjcf_path.exists(): + raise FileNotFoundError(f"robot MJCF not found: {robot_mjcf_path}") + + meshdir = Path(meshdir).expanduser().resolve() if meshdir else robot_mjcf_path.parent + + # Cache key — invalidates when any input changes. + h = hashlib.sha256() + h.update(scene_mesh_path.read_bytes()) + h.update(robot_mjcf_path.read_bytes()) + h.update(repr(sorted(asdict(align).items())).encode()) + h.update(str(meshdir).encode()) + cache_key = h.hexdigest()[:12] + + root = (cache_root or CACHE_DIR).expanduser() + cache_dir = root / cache_key + wrapper_path = cache_dir / "wrapper.xml" + + # Cache hit: wrapper exists + at least one prim OBJ next to it. + if wrapper_path.exists() and any(cache_dir.glob("*.obj")): + logger.info(f"bake_scene_mjcf: cache hit at {cache_dir}") + return wrapper_path + + cache_dir.mkdir(parents=True, exist_ok=True) + + from dimos.mapping.mesh_scene import load_scene_prims + + logger.info(f"bake_scene_mjcf: loading + aligning {scene_mesh_path} (per-prim)") + prims = load_scene_prims(scene_mesh_path, alignment=align) + logger.info(f"bake_scene_mjcf: {len(prims)} prims to bake") + + import trimesh + + asset_lines: list[str] = [] + geom_lines: list[str] = [] + total_tris = 0 + skipped_degenerate = 0 + n_hulls = 0 + _DEGENERATE_EPS = 1e-3 + # Furniture-scale prims are fine as one hull. Large shell-like prims + # need decomposition or MuJoCo sees the room as a solid block. + _SHELL_VOLUME_M3 = 2.0 + n_decomposed = 0 + logger.info(f"bake_scene_mjcf: per-prim convex-hulling {len(prims)} prims (one-time)…") + for prim in prims: + tm = trimesh.Trimesh( + vertices=prim.vertices.astype(np.float64), + faces=prim.triangles, + process=False, + ) + try: + single_hull = tm.convex_hull + except Exception as e: + logger.warning(f" convex_hull failed for {prim.name}: {e}; skipping") + continue + + if float(single_hull.volume) > _SHELL_VOLUME_M3: + try: + parts = tm.convex_decomposition(maxConvexHulls=64, resolution=200_000) + if not isinstance(parts, list): + parts = [parts] + hulls = parts + n_decomposed += 1 + logger.info( + f" {prim.name}: VHACD decomposed " + f"({single_hull.volume:.1f} m³ shell → {len(parts)} sub-hulls)" + ) + except Exception as e: + logger.warning( + f" VHACD failed for {prim.name}: {e}; " + f"using single hull (will swallow robot spawn area)" + ) + hulls = [single_hull] + else: + hulls = [single_hull] + + for j, hull in enumerate(hulls): + v = np.asarray(hull.vertices, dtype=np.float32) + f = np.asarray(hull.faces, dtype=np.int32) + if len(v) < 4 or len(f) < 4: + skipped_degenerate += 1 + continue + extent = v.max(axis=0) - v.min(axis=0) + if (extent < _DEGENERATE_EPS).any(): + skipped_degenerate += 1 + continue + min_ext = float(extent.min()) + max_ext = float(extent.max()) + if max_ext > 0 and (min_ext / max_ext) < 0.05: + skipped_degenerate += 1 + continue + if min_ext < 5e-3: + skipped_degenerate += 1 + continue + try: + from scipy.spatial import ConvexHull, QhullError + + ConvexHull(v, qhull_options="Qt") + except (QhullError, ValueError): + skipped_degenerate += 1 + continue + + asset_name = f"{prim.name}_h{j:03d}" + obj_file = cache_dir / f"{asset_name}.obj" + o3d_mesh = o3d.geometry.TriangleMesh() + o3d_mesh.vertices = o3d.utility.Vector3dVector(v.astype(np.float64)) + o3d_mesh.triangles = o3d.utility.Vector3iVector(f) + o3d_mesh.compute_vertex_normals() + if not o3d.io.write_triangle_mesh( + str(obj_file), + o3d_mesh, + write_vertex_normals=True, + write_vertex_colors=False, + ): + raise RuntimeError(f"open3d failed to write OBJ: {obj_file}") + + total_tris += len(f) + n_hulls += 1 + asset_lines.append(_ASSET_LINE.format(name=asset_name, file=str(obj_file))) + geom_lines.append(_GEOM_LINE.format(name=f"{asset_name}_geom", mesh=asset_name)) + + if not asset_lines: + raise RuntimeError( + "bake_scene_mjcf: every hull came out degenerate; nothing left to collide against" + ) + logger.info( + f"bake_scene_mjcf: baked {n_hulls} convex hulls from {len(prims)} prims " + f"({total_tris} tris total), VHACD-decomposed {n_decomposed} shell prims, " + f"skipped {skipped_degenerate} degenerate hulls" + ) + + wrapper_xml = _WRAPPER_TEMPLATE.format( + model_name=f"robot_with_scene_{cache_key}", + meshdir=str(meshdir), + robot_mjcf_abs=str(robot_mjcf_path), + asset_meshes="\n".join(asset_lines), + scene_geoms="\n".join(geom_lines), + ) + wrapper_path.write_text(wrapper_xml) + logger.info(f"bake_scene_mjcf: wrote wrapper {wrapper_path}") + return wrapper_path + + +def cli_main() -> None: + """``python -m dimos.mapping.usdz_to_mjcf [scale] [--view]``. + + Bake the wrapper, verify it loads, optionally open MuJoCo's native + viewer for visual inspection. ``--view`` works on macOS without + ``mjpython`` because we're invoking ``mujoco.viewer.launch`` from + the main thread of a fresh process — the issue dimos hits in + workers is that ``launch_passive`` in a *non-main* thread requires + mjpython. + """ + import sys + + args = list(sys.argv[1:]) + view = False + if "--view" in args: + view = True + args.remove("--view") + if len(args) < 2: + print( + "usage: python -m dimos.mapping.usdz_to_mjcf [scale] [--view]" + ) + sys.exit(2) + scene = Path(args[0]) + robot = Path(args[1]) + scale = float(args[2]) if len(args) >= 3 else 0.05 + align = SceneMeshAlignment(scale=scale) + wrapper = bake_scene_mjcf(scene, robot, alignment=align) + print(f"wrapper: {wrapper}") + + import mujoco # type: ignore[import-untyped] + + model = mujoco.MjModel.from_xml_path(str(wrapper)) + print(f"loaded: {model.nbody} bodies, {model.ngeom} geoms, {model.nmesh} meshes") + print(f"joints: {model.njnt}, dof: {model.nv}") + + if view: + import mujoco.viewer # type: ignore[import-untyped] + + # ``launch`` runs MuJoCo's interactive viewer with its own + # internal physics loop. Blocks until the user closes it. + # Press F1 in the viewer for the keyboard cheatsheet; ``Tab`` + # toggles the rendering panel where you can switch geom groups + # (group 3 = our scene collision hulls, group 1 = robot + # visual mesh, group 0 = robot collision mesh). + print("\n→ launching MuJoCo viewer (press Esc / close window to exit)") + mujoco.viewer.launch(model) + + +if __name__ == "__main__": + cli_main() + + +__all__ = ["bake_scene_mjcf"] diff --git a/dimos/robot/all_blueprints.py b/dimos/robot/all_blueprints.py index b88159dd8e..cfae58530c 100644 --- a/dimos/robot/all_blueprints.py +++ b/dimos/robot/all_blueprints.py @@ -62,6 +62,7 @@ "mid360-fastlio": "dimos.hardware.sensors.lidar.fastlio2.fastlio_blueprints:mid360_fastlio", "mid360-fastlio-voxels": "dimos.hardware.sensors.lidar.fastlio2.fastlio_blueprints:mid360_fastlio_voxels", "mid360-fastlio-voxels-native": "dimos.hardware.sensors.lidar.fastlio2.fastlio_blueprints:mid360_fastlio_voxels_native", + "mujoco-scene-playground": "dimos.simulation.mujoco_scene_playground:mujoco_scene_playground", "openarm-mock-planner-coordinator": "dimos.robot.manipulators.openarm.blueprints:openarm_mock_planner_coordinator", "openarm-planner-coordinator": "dimos.robot.manipulators.openarm.blueprints:openarm_planner_coordinator", "teleop-phone": "dimos.teleop.phone.blueprints:teleop_phone", diff --git a/dimos/simulation/engines/mujoco_engine.py b/dimos/simulation/engines/mujoco_engine.py index ada85dd477..8644021e2b 100644 --- a/dimos/simulation/engines/mujoco_engine.py +++ b/dimos/simulation/engines/mujoco_engine.py @@ -18,10 +18,12 @@ from collections.abc import Callable from dataclasses import dataclass +import math from pathlib import Path import threading import time from typing import TYPE_CHECKING +import xml.etree.ElementTree as ET import mujoco import mujoco.viewer as viewer # type: ignore[import-untyped] @@ -48,6 +50,7 @@ class CameraConfig: width: int = 640 height: int = 480 fps: float = 15.0 + scene_option: mujoco.MjvOption | None = None @dataclass @@ -84,6 +87,7 @@ def __init__( config_path: Path, headless: bool, cameras: list[CameraConfig] | None = None, + meshdir: str | Path | None = None, on_before_step: StepHook | None = None, on_after_step: StepHook | None = None, ) -> None: @@ -92,7 +96,7 @@ def __init__( self._on_after_step: StepHook | None = on_after_step xml_path = self._resolve_xml_path(config_path) - self._model = mujoco.MjModel.from_xml_path(str(xml_path)) + self._model = self._load_model(xml_path, meshdir=meshdir) self._xml_path = xml_path self._data = mujoco.MjData(self._model) @@ -101,6 +105,13 @@ def __init__( self._num_joints = len(self._joint_names) timestep = float(self._model.opt.timestep) self._control_frequency = 1.0 / timestep if timestep > 0.0 else 100.0 + self._root_free_qpos_adr: int | None = None + self._root_free_qvel_adr: int | None = None + for joint_id in range(self._model.njnt): + if self._model.jnt_type[joint_id] == mujoco.mjtJoint.mjJNT_FREE: + self._root_free_qpos_adr = int(self._model.jnt_qposadr[joint_id]) + self._root_free_qvel_adr = int(self._model.jnt_dofadr[joint_id]) + break self._connected = False self._lock = threading.Lock() @@ -134,6 +145,22 @@ def _resolve_xml_path(self, config_path: Path) -> Path: raise FileNotFoundError(f"MuJoCo XML not found: {xml_path}") return xml_path + def _load_model(self, xml_path: Path, *, meshdir: str | Path | None) -> mujoco.MjModel: + if meshdir is None: + return mujoco.MjModel.from_xml_path(str(xml_path)) + + root = ET.parse(xml_path).getroot() + compiler = root.find("compiler") + if compiler is None: + compiler = ET.Element("compiler") + root.insert(0, compiler) + compiler.set("meshdir", str(Path(meshdir).expanduser().resolve())) + for include in root.iter("include"): + include_file = include.get("file") + if include_file and not Path(include_file).is_absolute(): + include.set("file", str((xml_path.parent / include_file).resolve())) + return mujoco.MjModel.from_xml_string(ET.tostring(root, encoding="unicode")) + def _current_position(self, mapping: JointMapping) -> float: if mapping.joint_id is not None and mapping.qpos_adr is not None: return float(self._data.qpos[mapping.qpos_adr]) @@ -250,10 +277,24 @@ def _render_cameras(self, now: float, cam_renderers: dict[str, _CameraRendererSt continue state.last_render_time = now - state.rgb_renderer.update_scene(self._data, camera=state.cam_id) + if state.cfg.scene_option is None: + state.rgb_renderer.update_scene(self._data, camera=state.cam_id) + else: + state.rgb_renderer.update_scene( + self._data, + camera=state.cam_id, + scene_option=state.cfg.scene_option, + ) rgb = state.rgb_renderer.render().copy() - state.depth_renderer.update_scene(self._data, camera=state.cam_id) + if state.cfg.scene_option is None: + state.depth_renderer.update_scene(self._data, camera=state.cam_id) + else: + state.depth_renderer.update_scene( + self._data, + camera=state.cam_id, + scene_option=state.cfg.scene_option, + ) depth = state.depth_renderer.render().copy() frame = CameraFrame( @@ -417,6 +458,59 @@ def hold_current_position(self) -> None: for i, mapping in enumerate(self._joint_mappings): self._joint_position_targets[i] = self._current_position(mapping) + @property + def has_root_freejoint(self) -> bool: + return self._root_free_qpos_adr is not None + + def apply_root_twist( + self, + linear_x: float, + linear_y: float, + angular_z: float, + *, + fixed_z: float | None = None, + ) -> bool: + """Integrate planar velocity onto the first freejoint root.""" + qpos_adr = self._root_free_qpos_adr + if qpos_adr is None: + return False + + dt = 1.0 / self._control_frequency + with self._lock: + qpos = self._data.qpos + qw, qx, qy, qz = qpos[qpos_adr + 3 : qpos_adr + 7] + yaw = math.atan2( + 2.0 * (qw * qz + qx * qy), + 1.0 - 2.0 * (qy * qy + qz * qz), + ) + + qpos[qpos_adr] += (math.cos(yaw) * linear_x - math.sin(yaw) * linear_y) * dt + qpos[qpos_adr + 1] += (math.sin(yaw) * linear_x + math.cos(yaw) * linear_y) * dt + if fixed_z is not None: + qpos[qpos_adr + 2] = fixed_z + + yaw += angular_z * dt + qpos[qpos_adr + 3 : qpos_adr + 7] = [ + math.cos(yaw * 0.5), + 0.0, + 0.0, + math.sin(yaw * 0.5), + ] + + qvel_adr = self._root_free_qvel_adr + if qvel_adr is not None: + self._data.qvel[qvel_adr : qvel_adr + 6] = 0.0 + return True + + def get_root_pose(self) -> tuple[NDArray[np.float64], NDArray[np.float64]] | None: + qpos_adr = self._root_free_qpos_adr + if qpos_adr is None: + return None + with self._lock: + position = self._data.qpos[qpos_adr : qpos_adr + 3].copy() + qw, qx, qy, qz = self._data.qpos[qpos_adr + 3 : qpos_adr + 7].copy() + return position, np.array([qx, qy, qz, qw], dtype=np.float64) + def get_actuator_ctrl_range(self, joint_index: int) -> tuple[float, float] | None: mapping = self._joint_mappings[joint_index] if mapping.actuator_id is None: @@ -457,6 +551,15 @@ def get_camera_fovy(self, camera_name: str) -> float | None: return None return float(self._model.cam_fovy[cam_id]) + def get_camera_pose( + self, camera_name: str + ) -> tuple[NDArray[np.float64], NDArray[np.float64]] | None: + """Get a named camera's latest world pose from MuJoCo data.""" + cam_id = mujoco.mj_name2id(self._model, mujoco.mjtObj.mjOBJ_CAMERA, camera_name) + if cam_id < 0: + return None + return self._data.cam_xpos[cam_id].copy(), self._data.cam_xmat[cam_id].copy() + __all__ = [ "CameraConfig", diff --git a/dimos/simulation/engines/mujoco_shm.py b/dimos/simulation/engines/mujoco_shm.py index c0623c7915..f0021f8cd6 100644 --- a/dimos/simulation/engines/mujoco_shm.py +++ b/dimos/simulation/engines/mujoco_shm.py @@ -40,8 +40,8 @@ logger = setup_logger() -# Upper bound on joint count per sim. Arms + gripper are typically <= 10. -MAX_JOINTS = 16 +# Upper bound on joint count per sim. G1 is 29 DoF; leave room for hands. +MAX_JOINTS = 64 _FLOAT_BYTES = 8 # float64 _INT32_BYTES = 4 @@ -132,13 +132,13 @@ def create(cls, key: str) -> ManipShmSet: for buffer_name, size in _shm_sizes.items(): name = _buffer_name(key, buffer_name) try: - stale = _unregister(SharedMemory(name=name)) - stale.close() + stale = SharedMemory(name=name) try: stale.unlink() logger.info("ManipShmSet: unlinked stale SHM", name=name) except FileNotFoundError: pass + stale.close() except FileNotFoundError: pass buffers[buffer_name] = SharedMemory(create=True, size=size, name=name) diff --git a/dimos/simulation/engines/mujoco_sim_module.py b/dimos/simulation/engines/mujoco_sim_module.py index 3d2ff927fe..3918ddd00d 100644 --- a/dimos/simulation/engines/mujoco_sim_module.py +++ b/dimos/simulation/engines/mujoco_sim_module.py @@ -32,16 +32,22 @@ import time from typing import Any +import mujoco +import numpy as np +import open3d as o3d from pydantic import Field import reactivex as rx +from reactivex.disposable import Disposable from scipy.spatial.transform import Rotation as R from dimos.core.core import rpc from dimos.core.module import Module, ModuleConfig -from dimos.core.stream import Out +from dimos.core.stream import In, Out from dimos.hardware.sensors.camera.spec import DepthCameraConfig, DepthCameraHardware +from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped from dimos.msgs.geometry_msgs.Quaternion import Quaternion from dimos.msgs.geometry_msgs.Transform import Transform +from dimos.msgs.geometry_msgs.Twist import Twist from dimos.msgs.geometry_msgs.Vector3 import Vector3 from dimos.msgs.sensor_msgs.CameraInfo import CameraInfo from dimos.msgs.sensor_msgs.Image import Image, ImageFormat @@ -75,6 +81,7 @@ class MujocoSimModuleConfig(ModuleConfig, DepthCameraConfig): """Configuration for the unified MuJoCo simulation module.""" address: str = "" + meshdir: str | None = None headless: bool = False dof: int = 7 @@ -86,10 +93,16 @@ class MujocoSimModuleConfig(ModuleConfig, DepthCameraConfig): base_frame_id: str = "link7" base_transform: Transform | None = Field(default_factory=_default_identity_transform) align_depth_to_color: bool = True + enable_color: bool = True enable_depth: bool = True enable_pointcloud: bool = False pointcloud_fps: float = 5.0 camera_info_fps: float = 1.0 + lidar_camera_names: list[str] = Field(default_factory=list) + lidar_camera_width: int = 640 + lidar_camera_height: int = 360 + lidar_voxel_size: float = 0.05 + enable_kinematic_base_control: bool = False class MujocoSimModule( @@ -111,6 +124,9 @@ class MujocoSimModule( pointcloud: Out[PointCloud2] camera_info: Out[CameraInfo] depth_camera_info: Out[CameraInfo] + joint_state: Out[JointState] + odom: Out[PoseStamped] + cmd_vel: In[Twist] def __init__(self, **kwargs: Any) -> None: super().__init__(**kwargs) @@ -122,6 +138,14 @@ def __init__(self, **kwargs: Any) -> None: self._stop_event = threading.Event() self._publish_thread: threading.Thread | None = None self._camera_info_base: CameraInfo | None = None + self._cmd_vel_lock = threading.Lock() + self._cmd_vel = Twist.zero() + self._last_cmd_vel_time = 0.0 + self._kinematic_base_z: float | None = None + + @property + def _camera_enabled(self) -> bool: + return self.config.enable_color or self.config.enable_depth or self.config.enable_pointcloud @property def _camera_link(self) -> str: @@ -168,18 +192,50 @@ def start(self) -> None: shm_key = shm_key_from_path(self.config.address) self._shm = ManipShmWriter(shm_key) - # Build engine with SHM hooks installed. - self._engine = MujocoEngine( - config_path=Path(self.config.address), - headless=self.config.headless, - cameras=[ + camera_configs: list[CameraConfig] = [] + primary_needed = ( + self.config.enable_color + or self.config.enable_depth + or (self.config.enable_pointcloud and not self.config.lidar_camera_names) + ) + if primary_needed: + camera_configs.append( CameraConfig( name=self.config.camera_name, width=self.config.width, height=self.config.height, fps=float(self.config.fps), ) - ], + ) + + lidar_scene_option = mujoco.MjvOption() + lidar_scene_option.geomgroup[0] = 0 + lidar_scene_option.geomgroup[1] = 0 + lidar_scene_option.geomgroup[2] = 1 + lidar_scene_option.geomgroup[3] = 1 + lidar_scene_option.geomgroup[4] = 0 + lidar_scene_option.geomgroup[5] = 0 + for lidar_name in self.config.lidar_camera_names: + if lidar_name == self.config.camera_name and primary_needed: + continue + camera_configs.append( + CameraConfig( + name=lidar_name, + width=self.config.lidar_camera_width, + height=self.config.lidar_camera_height, + fps=float(self.config.pointcloud_fps), + scene_option=lidar_scene_option, + ) + ) + + # Build engine with SHM hooks installed. Camera configs are optional: + # physics and SHM state exchange must keep working in headless/no-render + # deployments. + self._engine = MujocoEngine( + config_path=Path(self.config.address), + headless=self.config.headless, + cameras=camera_configs, + meshdir=self.config.meshdir, on_before_step=self._apply_shm_commands, on_after_step=self._publish_shm_state, ) @@ -208,26 +264,35 @@ def start(self) -> None: self._shm.signal_ready(num_joints=len(joint_names)) - # Camera intrinsics. - self._build_camera_info() - self._stop_event.clear() - self._publish_thread = threading.Thread( - target=self._publish_loop, daemon=True, name="MujocoSimPublish" - ) - self._publish_thread.start() - - # Periodic camera_info publishing. - interval_sec = 1.0 / self.config.camera_info_fps - self.register_disposable( - rx.interval(interval_sec).subscribe( - on_next=lambda _: self._publish_camera_info(), - on_error=lambda e: logger.error("CameraInfo publish error", error=str(e)), + + if self.config.enable_kinematic_base_control: + if not self._engine.has_root_freejoint: + logger.warning("Kinematic base control requested, but MJCF has no freejoint root") + root_pose = self._engine.get_root_pose() + self._kinematic_base_z = None if root_pose is None else float(root_pose[0][2]) + self.register_disposable(Disposable(self.cmd_vel.subscribe(self._on_cmd_vel))) + + if primary_needed: + # Camera intrinsics. + self._build_camera_info() + + self._publish_thread = threading.Thread( + target=self._publish_loop, daemon=True, name="MujocoSimPublish" + ) + self._publish_thread.start() + + # Periodic camera_info publishing. + interval_sec = 1.0 / self.config.camera_info_fps + self.register_disposable( + rx.interval(interval_sec).subscribe( + on_next=lambda _: self._publish_camera_info(), + on_error=lambda e: logger.error("CameraInfo publish error", error=str(e)), + ) ) - ) # Optional pointcloud generation. - if self.config.enable_pointcloud and self.config.enable_depth: + if self.config.enable_pointcloud and (primary_needed or self.config.lidar_camera_names): pc_interval = 1.0 / self.config.pointcloud_fps self.register_disposable( rx.interval(pc_interval).subscribe( @@ -241,6 +306,7 @@ def start(self) -> None: address=self.config.address, dof=dof, camera=self.config.camera_name, + camera_enabled=self._camera_enabled, shm_key=shm_key, ) @@ -296,8 +362,30 @@ def _apply_shm_commands(self, engine: MujocoEngine) -> None: ctrl_value = self._gripper_joint_to_ctrl(gripper_cmd) engine.set_position_target(self._gripper_idx, ctrl_value) + def _on_cmd_vel(self, msg: Twist) -> None: + with self._cmd_vel_lock: + self._cmd_vel = Twist(msg) + self._last_cmd_vel_time = time.monotonic() + + def _apply_cmd_vel(self, engine: MujocoEngine) -> None: + if not self.config.enable_kinematic_base_control: + return + with self._cmd_vel_lock: + cmd = Twist(self._cmd_vel) + age = time.monotonic() - self._last_cmd_vel_time + if age > 0.5: + cmd = Twist.zero() + engine.apply_root_twist( + cmd.linear.x, + cmd.linear.y, + cmd.angular.z, + fixed_z=self._kinematic_base_z, + ) + def _publish_shm_state(self, engine: MujocoEngine) -> None: """Post-step hook: publish joint state to SHM.""" + self._apply_cmd_vel(engine) + shm = self._shm if shm is None: return @@ -306,6 +394,26 @@ def _publish_shm_state(self, engine: MujocoEngine) -> None: velocities=engine.joint_velocities, efforts=engine.joint_efforts, ) + self.joint_state.publish( + JointState( + frame_id="mujoco", + name=engine.joint_names, + position=engine.joint_positions, + velocity=engine.joint_velocities, + effort=engine.joint_efforts, + ) + ) + root_pose = engine.get_root_pose() + if root_pose is not None: + position, quat_xyzw = root_pose + self.odom.publish( + PoseStamped( + ts=time.time(), + frame_id="world", + position=Vector3(position), + orientation=Quaternion(quat_xyzw), + ) + ) if self._gripper_idx is not None: positions = engine.joint_positions if self._gripper_idx < len(positions): @@ -382,13 +490,14 @@ def _publish_loop(self) -> None: last_timestamp = frame.timestamp ts = time.time() - color_img = Image( - data=frame.rgb, - format=ImageFormat.RGB, - frame_id=self._color_optical_frame, - ts=ts, - ) - self.color_image.publish(color_img) + if self.config.enable_color: + color_img = Image( + data=frame.rgb, + format=ImageFormat.RGB, + frame_id=self._color_optical_frame, + ts=ts, + ) + self.color_image.publish(color_img) if self.config.enable_depth: depth_img = Image( @@ -469,7 +578,12 @@ def _publish_tf(self, ts: float, frame: CameraFrame | None) -> None: ) def _generate_pointcloud(self) -> None: - if self._engine is None or self._camera_info_base is None: + if self._engine is None: + return + if self.config.lidar_camera_names: + self._generate_lidar_pointcloud() + return + if self._camera_info_base is None: return frame = self._engine.read_camera(self.config.camera_name) if frame is None: @@ -498,5 +612,37 @@ def _generate_pointcloud(self) -> None: except Exception as exc: logger.error("Pointcloud generation error", error=str(exc)) + def _generate_lidar_pointcloud(self) -> None: + if self._engine is None: + return + try: + from dimos.simulation.mujoco.depth_camera import depth_image_to_point_cloud + + all_points: list[np.ndarray] = [] + latest_ts = 0.0 + for camera_name in self.config.lidar_camera_names: + frame = self._engine.read_camera(camera_name) + if frame is None: + continue + points = depth_image_to_point_cloud( + frame.depth, + frame.cam_pos, + frame.cam_mat.reshape(3, 3), + fov_degrees=frame.fovy, + ) + if points.size: + all_points.append(points) + latest_ts = max(latest_ts, frame.timestamp) + if not all_points: + return + cloud = o3d.geometry.PointCloud() + cloud.points = o3d.utility.Vector3dVector(np.vstack(all_points)) + cloud = cloud.voxel_down_sample(self.config.lidar_voxel_size) + self.pointcloud.publish( + PointCloud2(pointcloud=cloud, ts=latest_ts or time.time(), frame_id="world") + ) + except Exception as exc: + logger.error("Multi-camera lidar fusion error", error=str(exc)) + __all__ = ["MujocoSimModule", "MujocoSimModuleConfig"] diff --git a/dimos/simulation/mujoco_scene_playground.py b/dimos/simulation/mujoco_scene_playground.py new file mode 100644 index 0000000000..c15ae9de03 --- /dev/null +++ b/dimos/simulation/mujoco_scene_playground.py @@ -0,0 +1,213 @@ +# 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. + +"""MuJoCo scene playground with optional Viser mesh/splat visualization.""" + +from __future__ import annotations + +import os +from pathlib import Path +import tempfile + +from dimos_lcm.std_msgs import Bool # type: ignore[import-untyped] + +from dimos.core.coordination.blueprints import Blueprint, autoconnect +from dimos.core.transport import LCMTransport +from dimos.mapping.costmapper import CostMapper +from dimos.mapping.pointcloud_map_module import PointCloudMapModule +from dimos.msgs.geometry_msgs.PointStamped import PointStamped +from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped +from dimos.msgs.geometry_msgs.Twist import Twist +from dimos.msgs.nav_msgs.OccupancyGrid import OccupancyGrid +from dimos.msgs.nav_msgs.Path import Path as PathMsg +from dimos.msgs.sensor_msgs.JointState import JointState +from dimos.msgs.sensor_msgs.PointCloud2 import PointCloud2 +from dimos.navigation.movement_manager.movement_manager import MovementManager +from dimos.navigation.replanning_a_star.module import ReplanningAStarPlanner +from dimos.simulation.engines.mujoco_sim_module import MujocoSimModule +from dimos.visualization.viser.viser_render_module import ViserRenderModule + + +def _env_float(name: str, default: float) -> float: + raw = os.environ.get(name) + return default if raw is None or raw == "" else float(raw) + + +def _env_xyz(name: str, default: tuple[float, float, float]) -> tuple[float, float, float]: + raw = os.environ.get(name) + if raw is None or raw.strip() == "": + return default + parts = [float(p.strip()) for p in raw.split(",")] + if len(parts) != 3: + raise ValueError(f"{name} must be 'x,y,z'") + return (parts[0], parts[1], parts[2]) + + +def _command_center_blueprints() -> list[Blueprint]: + if os.environ.get("DIMOS_ENABLE_COMMAND_CENTER", "1") in {"", "0"}: + return [] + try: + from dimos.web.websocket_vis.websocket_vis_module import WebsocketVisModule + except ModuleNotFoundError: + import logging + + logging.getLogger(__name__).warning( + "Command Center unavailable; install the web extra to enable WASD controls" + ) + return [] + return [ + WebsocketVisModule.blueprint(port=int(os.environ.get("DIMOS_COMMAND_CENTER_PORT", "7779"))) + ] + + +_default_mjcf = Path("data/mujoco_sim/g1_gear_wbc.xml") +_default_scene_mesh = Path("data/dimos_office_mesh/dimos_office_mesh.glb") +_default_splat = Path("data/dimos_office/dimos_office.ply") +_mjcf_path = os.environ.get("DIMOS_MJCF_PATH") or str(_default_mjcf) +_mjcf_meshdir = os.environ.get("DIMOS_MJCF_MESHDIR") +if _mjcf_meshdir is None and Path(_mjcf_path) == _default_mjcf: + _mjcf_meshdir = "data/g1_urdf/meshes" +_dof = int(os.environ.get("DIMOS_MUJOCO_DOF", "29")) +_scene_mesh_path_override = os.environ.get("DIMOS_SCENE_MESH_PATH") or None +_scene_mesh_path = _scene_mesh_path_override or ( + str(_default_scene_mesh) if _default_scene_mesh.exists() else None +) +_scene_mesh_scale = _env_float( + "DIMOS_SCENE_MESH_SCALE", + 0.05 if _scene_mesh_path_override else 2.0, +) +_scene_mesh_y_up = ( + os.environ.get( + "DIMOS_SCENE_MESH_Y_UP", + "1" if _scene_mesh_path_override else "0", + ) + != "0" +) +_scene_mesh_rotation = _env_xyz("DIMOS_SCENE_MESH_ROTATION_ZYX_DEG", (0.0, 0.0, 0.0)) +_scene_mesh_translation = _env_xyz("DIMOS_SCENE_MESH_TRANSLATION", (0.0, 0.0, 0.0)) +_scene_mesh_collision = os.environ.get("DIMOS_SCENE_MESH_COLLISION", "1") not in {"", "0"} +_splat_path_override = os.environ.get("DIMOS_SPLAT_PATH") or None +_splat_path = _splat_path_override or ( + str(_default_splat) if _scene_mesh_path_override is None and _default_splat.exists() else None +) +_splat_alignment_yaml = os.environ.get("DIMOS_SPLAT_ALIGNMENT") +if _splat_alignment_yaml is None and _splat_path == str(_default_splat): + _office_splat_yaml = Path(tempfile.gettempdir()) / "dimos_office_to_artist_mesh.yaml" + _office_splat_yaml.write_text( + "# Maps the original Y-up dimos_office.ply into the artist mesh frame.\n" + f"scale: {_scene_mesh_scale}\n" + f"translation: [0.0, 0.0, {0.7734 * _scene_mesh_scale}]\n" + "rotation_zyx: [164.6633, -0.0865, -95.4786]\n" + "y_up: false\n" + ) + _splat_alignment_yaml = str(_office_splat_yaml) +_enable_depth_cloud = os.environ.get("DIMOS_ENABLE_DEPTH_CLOUD", "0").lower() in { + "1", + "true", + "yes", + "on", +} +_disable_lidar = os.environ.get("DIMOS_DISABLE_LIDAR", "0") not in {"", "0"} + +_sim_mjcf_path = _mjcf_path +if _scene_mesh_path and _scene_mesh_collision: + try: + from dimos.mapping.mesh_scene import SceneMeshAlignment + from dimos.mapping.usdz_to_mjcf import bake_scene_mjcf + + _sim_mjcf_path = str( + bake_scene_mjcf( + scene_mesh_path=_scene_mesh_path, + robot_mjcf_path=_mjcf_path, + alignment=SceneMeshAlignment( + scale=_scene_mesh_scale, + rotation_zyx_deg=_scene_mesh_rotation, + translation=_scene_mesh_translation, + y_up=_scene_mesh_y_up, + ), + meshdir=_mjcf_meshdir, + ) + ) + except Exception as exc: + import logging + + logging.getLogger(__name__).warning( + "Failed to bake scene mesh into MuJoCo; lidar will only see the base MJCF: %s", + exc, + ) + +mujoco_scene_playground = autoconnect( + MujocoSimModule.blueprint( + address=_sim_mjcf_path, + meshdir=_mjcf_meshdir, + headless=True, + dof=_dof, + camera_name=os.environ.get("DIMOS_MUJOCO_CAMERA", "head_color"), + enable_color=False, + enable_depth=True, + enable_pointcloud=(not _disable_lidar) or _enable_depth_cloud, + lidar_camera_names=( + [] + if _disable_lidar + else ["lidar_front_camera", "lidar_left_camera", "lidar_right_camera"] + ), + lidar_camera_width=int(os.environ.get("DIMOS_LIDAR_CAMERA_WIDTH", "640")), + lidar_camera_height=int(os.environ.get("DIMOS_LIDAR_CAMERA_HEIGHT", "360")), + lidar_voxel_size=_env_float("DIMOS_LIDAR_VOXEL_SIZE", 0.05), + enable_kinematic_base_control=os.environ.get("DIMOS_KINEMATIC_BASE_CONTROL", "1") + not in {"", "0"}, + ), + MovementManager.blueprint(), + PointCloudMapModule.blueprint( + voxel_size=_env_float("DIMOS_GLOBAL_MAP_VOXEL_SIZE", 0.05), + publish_interval=_env_float("DIMOS_GLOBAL_MAP_PUBLISH_INTERVAL", 0.5), + ), + CostMapper.blueprint(), + ReplanningAStarPlanner.blueprint(), + ViserRenderModule.blueprint( + splat_path=_splat_path, + mjcf_path=_sim_mjcf_path, + mjcf_meshdir=_mjcf_meshdir, + port=int(os.environ.get("DIMOS_VISER_PORT", "8082")), + alignment_yaml=_splat_alignment_yaml, + scene_mesh_path=_scene_mesh_path, + scene_mesh_scale=_scene_mesh_scale, + scene_mesh_translation=_scene_mesh_translation, + scene_mesh_rotation_zyx_deg=_scene_mesh_rotation, + scene_mesh_y_up=_scene_mesh_y_up, + pointcloud_point_size=_env_float("DIMOS_POINTCLOUD_POINT_SIZE", 0.04), + ), + *_command_center_blueprints(), +).transports( + { + ("joint_state", JointState): LCMTransport("/mujoco/joint_state", JointState), + ("odom", PoseStamped): LCMTransport("/odom", PoseStamped), + ("tele_cmd_vel", Twist): LCMTransport("/tele_cmd_vel", Twist), + ("nav_cmd_vel", Twist): LCMTransport("/nav_cmd_vel", Twist), + ("cmd_vel", Twist): LCMTransport("/cmd_vel", Twist), + ("pointcloud", PointCloud2): LCMTransport("/lidar", PointCloud2), + ("lidar", PointCloud2): LCMTransport("/lidar", PointCloud2), + ("global_map", PointCloud2): LCMTransport("/global_map", PointCloud2), + ("pointcloud_overlay", PointCloud2): LCMTransport("/global_map", PointCloud2), + ("global_costmap", OccupancyGrid): LCMTransport("/global_costmap", OccupancyGrid), + ("path", PathMsg): LCMTransport("/nav_path", PathMsg), + ("clicked_point", PointStamped): LCMTransport("/clicked_point", PointStamped), + ("goal", PointStamped): LCMTransport("/goal", PointStamped), + ("goal_request", PoseStamped): LCMTransport("/goal_request", PoseStamped), + ("stop_movement", Bool): LCMTransport("/stop_movement", Bool), + ("point_goal", PointStamped): LCMTransport("/point_goal", PointStamped), + } +) + +__all__ = ["mujoco_scene_playground"] diff --git a/dimos/visualization/viser/camera.py b/dimos/visualization/viser/camera.py new file mode 100644 index 0000000000..296b7f3be3 --- /dev/null +++ b/dimos/visualization/viser/camera.py @@ -0,0 +1,207 @@ +# 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. + +"""Robot-mounted camera spec + frustum overlay helpers. + +A ``CameraSpec`` is a fixed-mount RGB camera attached to a body in the +robot MJCF. It carries everything a renderer (or a frustum overlay) +needs: the parent body name, a local mount transform in the body +frame, image-plane intrinsics, and an output resolution. + +Conventions: + * Mount quaternion is in **wxyz** order, expressing the camera's + optical frame in the body frame: image-x = right, image-y = down, + image-z = forward. This matches OpenCV / viser camera conventions. + * Robot body frame in the bundled G1 MJCF is the standard ROS one: + body-x = forward, body-y = left, body-z = up. + +The default ``g1_d435_default()`` mounts a RealSense D435i color +sensor on ``head_link`` looking forward — a sensible "robot's eye +view" for office walking. Override the spec to pitch down for +manipulation, mount on torso, swap to a different sensor, etc. +""" + +from __future__ import annotations + +from dataclasses import dataclass + +import mujoco +import numpy as np + + +@dataclass(frozen=True) +class CameraSpec: + """Fixed-mount RGB camera attached to a robot body.""" + + body_name: str + """MJCF body name to mount on (e.g. 'head_link', 'torso_link').""" + + mount_pos: tuple[float, float, float] + """Camera optical-center position in the parent body's local frame, meters.""" + + mount_wxyz: tuple[float, float, float, float] + """Quaternion (w, x, y, z) mapping body frame to camera optical frame.""" + + vfov_deg: float + """Vertical field of view, degrees. Horizontal FOV is derived from aspect.""" + + width: int + """Image width, pixels.""" + + height: int + """Image height, pixels.""" + + frustum_scale: float = 0.15 + """Frustum wireframe size in meters when overlaid in viser.""" + + frustum_color: tuple[int, int, int] = (50, 255, 100) + """RGB 0..255 for the frustum overlay. Lime by default.""" + + @property + def aspect(self) -> float: + return self.width / self.height + + def focal_pixels(self) -> float: + """Focal length in pixels, derived from VFOV. Square pixels assumed.""" + return 0.5 * self.height / float(np.tan(np.radians(self.vfov_deg) * 0.5)) + + def fx(self) -> float: + return self.focal_pixels() + + def fy(self) -> float: + return self.focal_pixels() + + def cx(self) -> float: + return 0.5 * self.width + + def cy(self) -> float: + return 0.5 * self.height + + +def _quat_from_matrix(R: np.ndarray) -> tuple[float, float, float, float]: + """3x3 rotation matrix -> (w, x, y, z) via mujoco. Stable, no scipy dep.""" + flat = np.asarray(R, dtype=np.float64).flatten() + out = np.zeros(4, dtype=np.float64) + mujoco.mju_mat2Quat(out, flat) + return (float(out[0]), float(out[1]), float(out[2]), float(out[3])) + + +def g1_d435_default() -> CameraSpec: + """RealSense D435i color sensor mounted on G1 torso, pitched down. + + Mount: on ``torso_link``. Offset + ``(0.0576, 0.0325, 0.4299)`` matches the URDF d435_joint position + (Intel-spec RGB sensor offset already baked in). Optical axis + pitched down by ~47.6° (0.831 rad) — same value Matrix uses on + real G1 deployments — so the camera sees the workspace in front + of the chest, not the horizon. This is what manipulation / + object registration consume; pick-and-place needs a downward + view of the table. + + Intrinsics are Intel datasheet for D435i color + (HFOV 69.4°, VFOV 42.5°), binned to 320x180. + """ + # Body frame : +x forward, +y left, +z up + # Image frame : +x right, +y down, +z forward + # body_R_image = horizontal_forward @ R_pitch_down(47.6°) + pitch_rad = 0.831 + c, s = np.cos(pitch_rad), np.sin(pitch_rad) + horizontal = np.array( + [ + [0.0, 0.0, 1.0], + [-1.0, 0.0, 0.0], + [0.0, -1.0, 0.0], + ], + dtype=np.float64, + ) + pitch_down = np.array( + [[1.0, 0.0, 0.0], [0.0, c, s], [0.0, -s, c]], + dtype=np.float64, + ) + body_R_image = horizontal @ pitch_down + return CameraSpec( + body_name="torso_link", + mount_pos=(0.0576, 0.0325, 0.4299), + mount_wxyz=_quat_from_matrix(body_R_image), + vfov_deg=42.5, + width=320, + height=180, + ) + + +def g1_d435_forward() -> CameraSpec: + """RealSense D435i mounted forward at G1 eye level (no pitch). + + Alternate to ``g1_d435_default`` for when the agent wants a + "robot's eye view" of the room — looking at the horizon, walls, + people — instead of the manipulation-oriented downward pitch. + Useful for navigation / exploration / scene understanding tasks + that don't care about the table workspace in front of the chest. + + Mount: on ``torso_link`` at ``(0.10, 0.0, 0.40)`` — 10 cm forward + of the torso origin and 40 cm up, roughly at eye level just past + the forehead mesh. Optical axis horizontal. + + Intrinsics are Intel datasheet for D435i color + (HFOV 69.4°, VFOV 42.5°), binned to 320x180. + """ + body_R_image = np.array( + [ + [0.0, 0.0, 1.0], + [-1.0, 0.0, 0.0], + [0.0, -1.0, 0.0], + ], + dtype=np.float64, + ) + return CameraSpec( + body_name="torso_link", + mount_pos=(0.10, 0.0, 0.40), + mount_wxyz=_quat_from_matrix(body_R_image), + vfov_deg=42.5, + width=320, + height=180, + ) + + +def world_pose( + body_world_pos: np.ndarray, + body_world_wxyz: np.ndarray, + spec: CameraSpec, +) -> tuple[np.ndarray, np.ndarray]: + """Compose the camera's world pose from its parent body's world pose. + + Returns ``(world_pos (3,), world_wxyz (4,))`` ready to feed straight + into viser's ``add_camera_frustum`` (which uses the same + +Z-forward / +Y-down convention the camera spec is in). + """ + # World rotation: q_world_image = q_world_body * q_body_image + out_quat = np.zeros(4, dtype=np.float64) + mujoco.mju_mulQuat( + out_quat, + np.asarray(body_world_wxyz, dtype=np.float64), + np.asarray(spec.mount_wxyz, dtype=np.float64), + ) + + # World translation: p_world_image = p_world_body + R_world_body @ mount_pos + body_R_world = np.zeros(9, dtype=np.float64) + mujoco.mju_quat2Mat(body_R_world, np.asarray(body_world_wxyz, dtype=np.float64)) + body_R_world = body_R_world.reshape(3, 3) + out_pos = np.asarray(body_world_pos, dtype=np.float64) + body_R_world @ np.asarray( + spec.mount_pos, dtype=np.float64 + ) + + return out_pos, out_quat + + +__all__ = ["CameraSpec", "g1_d435_default", "g1_d435_forward", "world_pose"] diff --git a/dimos/visualization/viser/robot_meshes.py b/dimos/visualization/viser/robot_meshes.py new file mode 100644 index 0000000000..1e02ce1cbe --- /dev/null +++ b/dimos/visualization/viser/robot_meshes.py @@ -0,0 +1,230 @@ +# 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. + +"""MuJoCo-based robot mesh extractor + FK helper for the Viser viewer. + +Loads an MJCF (the same one the sim subprocess loads), pulls out visual +mesh geoms with their parent-body indices and local poses, and runs FK +on demand to give world poses for every body in the model. + +Lets the Viser render module display the same robot the simulation is +stepping, without forcing a separate URDF or duplicating geometry. +""" + +from __future__ import annotations + +from dataclasses import dataclass +from pathlib import Path +import xml.etree.ElementTree as ET + +import mujoco +import numpy as np + + +# dimos joint names look like ``g1/left_hip_pitch`` (slash-separated +# hardware id + snake_case suffix — the canonical convention since +# Mustafa's #1954 G1 coordinator integration unified naming with the +# Unitree SDK). MJCF joint names look like ``left_hip_pitch_joint``. +# Strip the hardware prefix and append ``_joint``. +def dimos_joint_to_mjcf(name: str) -> str: + parts = name.split("/", 1) + suffix = parts[1] if len(parts) > 1 else parts[0] + return f"{suffix}_joint" + + +@dataclass +class GeomInstance: + """A single visual mesh geom, parented to a body.""" + + body_name: str + vertices: np.ndarray # (V, 3) + faces: np.ndarray # (F, 3) + local_pos: np.ndarray # (3,) + local_wxyz: np.ndarray # (4,) + rgba: tuple[float, float, float, float] + + +@dataclass +class RobotMeshes: + model: mujoco.MjModel + data: mujoco.MjData + geoms: list[GeomInstance] + # joint-name (in MJCF order) -> qpos address. Used to splice incoming + # joint_state values into the right slots of qpos. + qpos_addr_by_mjcf_name: dict[str, int] + # body_id -> body name (for viser entity paths). + body_names: list[str] + + +def load_robot_meshes( + mjcf_path: str | Path, + *, + visual_groups: tuple[int, ...] = (0, 1, 2), + meshdir: str | Path | None = None, + assets: dict[str, bytes] | None = None, +) -> RobotMeshes: + """Parse the MJCF, pull visual mesh geoms into Python arrays. + + ``visual_groups`` defaults to MuJoCo's convention where group 0-2 are + visual and group 3+ are collision. Most menagerie / dimos models + follow this; if a model uses different groups, override it. + + ``meshdir`` points MuJoCo at a local mesh directory when an MJCF + uses bare mesh filenames. + + ``assets`` is an optional ``{filename: bytes}`` map for embedded assets. + """ + path = Path(mjcf_path) + xml = path.read_text() + if meshdir is not None: + root = ET.fromstring(xml) + compiler = root.find("compiler") + if compiler is None: + compiler = ET.Element("compiler") + root.insert(0, compiler) + compiler.set("meshdir", str(Path(meshdir).expanduser().resolve())) + for include in root.iter("include"): + include_file = include.get("file") + if include_file and not Path(include_file).is_absolute(): + include.set("file", str((path.parent / include_file).resolve())) + xml = ET.tostring(root, encoding="unicode") + model = mujoco.MjModel.from_xml_string(xml, assets or {}) + data = mujoco.MjData(model) + + geoms: list[GeomInstance] = [] + for gid in range(model.ngeom): + if int(model.geom_group[gid]) not in visual_groups: + continue + gtype = int(model.geom_type[gid]) + body_id = int(model.geom_bodyid[gid]) + body_name = mujoco.mj_id2name(model, mujoco.mjtObj.mjOBJ_BODY, body_id) or f"body_{body_id}" + rgba = tuple(float(x) for x in model.geom_rgba[gid]) + local_pos = np.array(model.geom_pos[gid], dtype=np.float32).copy() + local_wxyz = np.array(model.geom_quat[gid], dtype=np.float32).copy() + size = model.geom_size[gid] + + # Mesh: pull vertices/faces from the model. + if gtype == mujoco.mjtGeom.mjGEOM_MESH: + mesh_id = int(model.geom_dataid[gid]) + if mesh_id < 0: + continue + v_start = int(model.mesh_vertadr[mesh_id]) + v_count = int(model.mesh_vertnum[mesh_id]) + f_start = int(model.mesh_faceadr[mesh_id]) + f_count = int(model.mesh_facenum[mesh_id]) + vertices = np.array( + model.mesh_vert[v_start : v_start + v_count], + dtype=np.float32, + ).copy() + faces = np.array( + model.mesh_face[f_start : f_start + f_count], + dtype=np.int32, + ).copy() + # Box: tessellate as 8 verts + 12 triangles, half-sizes from + # geom_size[0..2]. Lets us render primitives + # (manip_table, manip_cube, scene-editor exports) without a + # mesh asset. + elif gtype == mujoco.mjtGeom.mjGEOM_BOX: + hx, hy, hz = float(size[0]), float(size[1]), float(size[2]) + vertices = np.array( + [ + [-hx, -hy, -hz], + [hx, -hy, -hz], + [hx, hy, -hz], + [-hx, hy, -hz], + [-hx, -hy, hz], + [hx, -hy, hz], + [hx, hy, hz], + [-hx, hy, hz], + ], + dtype=np.float32, + ) + # Outward-facing CCW triangles (verified by cross-product). + faces = np.array( + [ + [0, 2, 1], + [0, 3, 2], # -Z (bottom) + [4, 5, 6], + [4, 6, 7], # +Z (top) + [0, 1, 5], + [0, 5, 4], # -Y + [1, 2, 6], + [1, 6, 5], # +X + [2, 3, 7], + [2, 7, 6], # +Y + [3, 0, 4], + [3, 4, 7], # -X + ], + dtype=np.int32, + ) + else: + # Sphere, cylinder, plane, etc. — skip for now. Only manip + # rigs and scene-editor exports use boxes; everything else + # the dimos sims care about is a mesh. + continue + + geoms.append( + GeomInstance( + body_name=body_name, + vertices=vertices, + faces=faces, + local_pos=local_pos, + local_wxyz=local_wxyz, + rgba=rgba, # type: ignore[arg-type] + ) + ) + + qpos_addr_by_mjcf_name: dict[str, int] = {} + for jid in range(model.njnt): + jname = mujoco.mj_id2name(model, mujoco.mjtObj.mjOBJ_JOINT, jid) + if jname is None: + continue + qpos_addr_by_mjcf_name[jname] = int(model.jnt_qposadr[jid]) + + body_names = [ + mujoco.mj_id2name(model, mujoco.mjtObj.mjOBJ_BODY, bid) or f"body_{bid}" + for bid in range(model.nbody) + ] + + return RobotMeshes( + model=model, + data=data, + geoms=geoms, + qpos_addr_by_mjcf_name=qpos_addr_by_mjcf_name, + body_names=body_names, + ) + + +def apply_state( + rm: RobotMeshes, + *, + base_pos: np.ndarray | None = None, + base_wxyz: np.ndarray | None = None, + joint_positions: dict[str, float] | None = None, +) -> None: + """Splice base + joint values into qpos and run FK in-place. + + After this returns, ``rm.data.xpos`` and ``rm.data.xquat`` hold each + body's world pose. Cheap (~50 us for G1). + """ + if base_pos is not None: + rm.data.qpos[0:3] = base_pos + if base_wxyz is not None: + rm.data.qpos[3:7] = base_wxyz + if joint_positions: + for name, q in joint_positions.items(): + adr = rm.qpos_addr_by_mjcf_name.get(name) + if adr is not None: + rm.data.qpos[adr] = q + mujoco.mj_kinematics(rm.model, rm.data) diff --git a/dimos/visualization/viser/splat.py b/dimos/visualization/viser/splat.py new file mode 100644 index 0000000000..87b94c50bb --- /dev/null +++ b/dimos/visualization/viser/splat.py @@ -0,0 +1,217 @@ +# 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. + +"""3DGS PLY loader for Viser. + +Reads a Gaussian splat PLY (3DGS-format), applies an alignment transform +(rotation + translation + uniform scale), and returns the +``(centers, covariances, rgbs, opacities)`` arrays Viser's +``add_gaussian_splats`` expects. + +The alignment transform is needed because 3DGS splats trained from +COLMAP come out in the COLMAP world frame, which is Y-up and in +arbitrary scale. Dimos uses Z-up metric. See +``data/scenes/.yaml`` for per-scene alignment values. +""" + +from __future__ import annotations + +from dataclasses import dataclass +from typing import TYPE_CHECKING + +import numpy as np + +if TYPE_CHECKING: + from pathlib import Path + +# 3DGS spherical harmonic DC coefficient. +_SH_C0 = 0.28209479177387814 + +# Y-up (3DGS / COLMAP) -> Z-up (dimos). (x, y, z) -> (x, z, -y). +_Y_UP_TO_Z_UP = np.array( + [[1, 0, 0], [0, 0, 1], [0, -1, 0]], + dtype=np.float32, +) + + +@dataclass +class SplatAlignment: + """Per-scene splat alignment. + + Loaded from a YAML next to the PLY: + + scale: 1.0 # multiplicative; COLMAP units -> meters + translation: [0, 0, 0] # post-rotation offset in world frame, meters + rotation_zyx: [0, 0, 0] # extra yaw/pitch/roll in degrees, applied after Y->Z + y_up: true # apply standard Y-up -> Z-up + """ + + scale: float = 1.0 + translation: tuple[float, float, float] = (0.0, 0.0, 0.0) + rotation_zyx_deg: tuple[float, float, float] = (0.0, 0.0, 0.0) + y_up: bool = True + + @classmethod + def from_yaml(cls, path: str | Path) -> SplatAlignment: + import yaml + + with open(path) as f: + d = yaml.safe_load(f) or {} + return cls( + scale=float(d.get("scale", 1.0)), + translation=tuple(d.get("translation", [0.0, 0.0, 0.0])), # type: ignore[arg-type] + rotation_zyx_deg=tuple(d.get("rotation_zyx", [0.0, 0.0, 0.0])), # type: ignore[arg-type] + y_up=bool(d.get("y_up", True)), + ) + + def world_from_splat(self) -> np.ndarray: + """3x3 rotation: scaled rotation that maps splat-frame -> world-frame.""" + R = _Y_UP_TO_Z_UP if self.y_up else np.eye(3, dtype=np.float32) + rz, ry, rx = (np.deg2rad(a) for a in self.rotation_zyx_deg) + cz, sz = np.cos(rz), np.sin(rz) + cy, sy = np.cos(ry), np.sin(ry) + cx, sx = np.cos(rx), np.sin(rx) + Rz = np.array([[cz, -sz, 0], [sz, cz, 0], [0, 0, 1]], dtype=np.float32) + Ry = np.array([[cy, 0, sy], [0, 1, 0], [-sy, 0, cy]], dtype=np.float32) + Rx = np.array([[1, 0, 0], [0, cx, -sx], [0, sx, cx]], dtype=np.float32) + return (Rz @ Ry @ Rx @ R).astype(np.float32) + + +@dataclass +class SplatData: + centers: np.ndarray # (N, 3) float32, world frame + covariances: np.ndarray # (N, 3, 3) float32, world frame. For viser. + rgbs: np.ndarray # (N, 3) float32, [0, 1] + opacities: np.ndarray # (N, 1) float32, [0, 1] + # Primitive form for renderers that prefer it (e.g. gsplat). + # All in the same world frame as ``centers``/``covariances``. + quats_wxyz: np.ndarray # (N, 4) float32 + scales: np.ndarray # (N, 3) float32, post-alignment uniform-scaled + + +def load_splat(ply_path: str | Path, alignment: SplatAlignment | None = None) -> SplatData: + """Load a 3DGS PLY and bake the alignment into centers + covariances. + + Returns arrays in dimos world frame, ready to feed straight into + ``viser.scene.add_gaussian_splats``. Heavy: ~1-2 GB for a 250 MB PLY, + so do this once at module start, not per frame. + """ + if alignment is None: + alignment = SplatAlignment() + from plyfile import PlyData + + ply = PlyData.read(str(ply_path)) + v = ply["vertex"] + props = {p.name for p in v.properties} + + pos = np.stack( + [v["x"], v["y"], v["z"]], + axis=-1, + ).astype(np.float32) + + if "rot_0" in props: + rw = v["rot_0"].astype(np.float32) + rx = v["rot_1"].astype(np.float32) + ry = v["rot_2"].astype(np.float32) + rz = v["rot_3"].astype(np.float32) + n = np.sqrt(rw * rw + rx * rx + ry * ry + rz * rz).clip(1e-12) + rw, rx, ry, rz = rw / n, rx / n, ry / n, rz / n + R = np.empty((len(rw), 3, 3), dtype=np.float32) + R[:, 0, 0] = 1 - 2 * (ry * ry + rz * rz) + R[:, 0, 1] = 2 * (rx * ry - rw * rz) + R[:, 0, 2] = 2 * (rx * rz + rw * ry) + R[:, 1, 0] = 2 * (rx * ry + rw * rz) + R[:, 1, 1] = 1 - 2 * (rx * rx + rz * rz) + R[:, 1, 2] = 2 * (ry * rz - rw * rx) + R[:, 2, 0] = 2 * (rx * rz - rw * ry) + R[:, 2, 1] = 2 * (ry * rz + rw * rx) + R[:, 2, 2] = 1 - 2 * (rx * rx + ry * ry) + else: + R = np.tile(np.eye(3, dtype=np.float32), (len(pos), 1, 1)) + + if "scale_0" in props: + s = np.exp(np.stack([v["scale_0"], v["scale_1"], v["scale_2"]], axis=-1).astype(np.float32)) + else: + s = np.ones((len(pos), 3), dtype=np.float32) + + if "opacity" in props: + op = (1.0 / (1.0 + np.exp(-v["opacity"].astype(np.float32)))).reshape(-1, 1) + else: + op = np.ones((len(pos), 1), dtype=np.float32) + + if all(f"f_dc_{i}" in props for i in range(3)): + sh_dc = np.stack( + [v["f_dc_0"], v["f_dc_1"], v["f_dc_2"]], + axis=-1, + ).astype(np.float32) + rgbs = (_SH_C0 * sh_dc + 0.5).clip(0.0, 1.0).astype(np.float32) + else: + rgbs = np.ones((len(pos), 3), dtype=np.float32) + + # Covariance in original splat frame: C = R diag(s^2) R^T. + cov_splat = np.einsum("nij,nj,nkj->nik", R, s * s, R) + + # Apply alignment. Centers: world = scale * (M @ splat) + t. Covariances: + # transform as bilinear forms: C' = scale^2 * M C M^T (translation drops). + M = alignment.world_from_splat() + centers = (alignment.scale * pos @ M.T) + np.asarray(alignment.translation, dtype=np.float32) + covariances = (alignment.scale * alignment.scale) * np.einsum("ij,njk,lk->nil", M, cov_splat, M) + + # Same alignment applied to the primitive (quat, scale) form. Renderers + # like gsplat operate directly on these instead of full covariances. + quats_splat = np.stack([rw, rx, ry, rz], axis=-1) if "rot_0" in props else None + if quats_splat is None: + quats_world = np.tile(np.array([1.0, 0.0, 0.0, 0.0], dtype=np.float32), (len(pos), 1)) + else: + # Rotate every Gaussian's local frame by M: q_world = q_M ⊗ q_splat. + qM = _mat3_to_wxyz(M) + quats_world = _quat_mul_left(qM, quats_splat).astype(np.float32) + scales_world = (alignment.scale * s).astype(np.float32) + + return SplatData( + centers=centers, + covariances=covariances, + rgbs=rgbs, + opacities=op, + quats_wxyz=quats_world, + scales=scales_world, + ) + + +def _mat3_to_wxyz(R: np.ndarray) -> np.ndarray: + """3x3 rotation matrix -> (w, x, y, z), via mujoco for numerical stability.""" + import mujoco + + out = np.zeros(4, dtype=np.float64) + mujoco.mju_mat2Quat(out, np.asarray(R, dtype=np.float64).flatten()) + return out.astype(np.float32) + + +def _quat_mul_left(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: + """Left-multiply ``q1 ⊗ q2`` for q1: (4,) wxyz and q2: (N, 4) wxyz. + + Vectorised — the per-Gaussian alternative through ``mujoco.mju_mulQuat`` + in a Python loop is ~50x slower for 1M Gaussians. + """ + aw, ax, ay, az = q1[0], q1[1], q1[2], q1[3] + bw, bx, by, bz = q2[:, 0], q2[:, 1], q2[:, 2], q2[:, 3] + return np.stack( + [ + aw * bw - ax * bx - ay * by - az * bz, + aw * bx + ax * bw + ay * bz - az * by, + aw * by - ax * bz + ay * bw + az * bx, + aw * bz + ax * by - ay * bx + az * bw, + ], + axis=-1, + ) diff --git a/dimos/visualization/viser/viser_render_module.py b/dimos/visualization/viser/viser_render_module.py new file mode 100644 index 0000000000..04e24454d8 --- /dev/null +++ b/dimos/visualization/viser/viser_render_module.py @@ -0,0 +1,765 @@ +# 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. + +"""Viser-based 3D viewer module for dimos. + +Streams a Gaussian splat scene + the robot (MJCF meshes, FK from +``/coordinator/joint_state`` + ``/odom``) into a browser at +http://localhost:/. + +This is render-only — the viewer subscribes to existing LCM topics and +does not feed back into the control path. Teleop continues to come +from the existing command-center dashboard. +""" + +from __future__ import annotations + +from pathlib import Path as FilePath +import threading +import time +from typing import Any + +import mujoco +import numpy as np +from reactivex.disposable import Disposable + +from dimos.core.core import rpc +from dimos.core.module import Module +from dimos.core.stream import In, Out +from dimos.msgs.geometry_msgs.PointStamped import PointStamped +from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped +from dimos.msgs.nav_msgs.Path import Path as PathMsg +from dimos.msgs.sensor_msgs.JointState import JointState +from dimos.msgs.sensor_msgs.PointCloud2 import PointCloud2 +from dimos.utils.logging_config import setup_logger +from dimos.visualization.viser.camera import CameraSpec, world_pose +from dimos.visualization.viser.robot_meshes import ( + RobotMeshes, + apply_state, + dimos_joint_to_mjcf, + load_robot_meshes, +) +from dimos.visualization.viser.splat import SplatAlignment, load_splat + +logger = setup_logger() + + +def _compose_scene_mesh_wxyz( + *, y_up: bool, rotation_zyx_deg: tuple[float, float, float] +) -> tuple[float, float, float, float]: + """Build the viser wxyz quaternion that applies (y_up swap then zyx euler) — + same convention as SceneMeshAlignment, just expressed as a parent-frame + transform so we don't have to bake it into vertices.""" + R = np.eye(3, dtype=np.float64) + if y_up: + R = np.array([[1, 0, 0], [0, 0, 1], [0, -1, 0]], dtype=np.float64) + rz, ry, rx = (np.deg2rad(a) for a in rotation_zyx_deg) + cz, sz = np.cos(rz), np.sin(rz) + cy, sy = np.cos(ry), np.sin(ry) + cx, sx = np.cos(rx), np.sin(rx) + Rz = np.array([[cz, -sz, 0], [sz, cz, 0], [0, 0, 1]], dtype=np.float64) + Ry = np.array([[cy, 0, sy], [0, 1, 0], [-sy, 0, cy]], dtype=np.float64) + Rx = np.array([[1, 0, 0], [0, cx, -sx], [0, sx, cx]], dtype=np.float64) + R = Rz @ Ry @ Rx @ R + import mujoco + + out = np.zeros(4, dtype=np.float64) + mujoco.mju_mat2Quat(out, R.flatten()) + return (float(out[0]), float(out[1]), float(out[2]), float(out[3])) + + +class ViserRenderModule(Module): + """Viser viewer that overlays the live robot on a Gaussian splat. + + Inputs: + joint_state: per-joint q values from the coordinator. + odom: base pose from the sim (or future real-hw) adapter. + """ + + joint_state: In[JointState] + odom: In[PoseStamped] + path: In[PathMsg] + # Optional pointcloud overlay. Named distinctly (not `lidar`) so the + # global transport map doesn't collide with VoxelGridMapper's `lidar` + # In port — the coordinator keys transports by (port_name, type) and + # the last-registered module wins, so a name clash silently overrides + # whichever transport was registered first. Blueprints typically + # wire this to /global_map (accumulated voxel cloud) for a persistent + # obstacle-memory overlay; /lidar (per-scan, transient) also works + # if the latest sweep is what you want. + pointcloud_overlay: In[PointCloud2] + clicked_point: Out[PointStamped] + # Interactive pointing-target publisher. Wired up by the "Set point + # goal" button: armed by the user pressing the button, the next + # scene click ray-casts against the scene mesh (if loaded) or + # intersects the eye-height plane, and the resulting world-frame + # point is published here. G1ManipulationModule subscribes and runs + # point_at on each value. Separate stream from clicked_point so a + # human's pointing click doesn't accidentally retarget the navigator. + point_goal: Out[PointStamped] + + def __init__( + self, + splat_path: str | FilePath | None, + mjcf_path: str | FilePath, + *, + port: int = 8082, + alignment_yaml: str | FilePath | None = None, + render_hz: float = 30.0, + camera_spec: CameraSpec | None = None, + mjcf_meshdir: str | FilePath | None = None, + scene_mesh_path: str | FilePath | None = None, + scene_mesh_scale: float = 1.0, + scene_mesh_translation: tuple[float, float, float] = (0.0, 0.0, 0.0), + scene_mesh_rotation_zyx_deg: tuple[float, float, float] = (0.0, 0.0, 0.0), + scene_mesh_y_up: bool = True, + pointcloud_point_size: float = 0.04, + **kwargs: Any, + ) -> None: + super().__init__(**kwargs) + # Empty / None splat_path means "no splat in the viewer" — useful when + # the world is provided as a mesh instead (DIMOS_SCENE_MESH_PATH). + self._splat_path = FilePath(splat_path) if splat_path else None + self._mjcf_path = FilePath(mjcf_path) + self._mjcf_meshdir = FilePath(mjcf_meshdir) if mjcf_meshdir else None + self._alignment_yaml = FilePath(alignment_yaml) if alignment_yaml else None + self._port = port + self._render_dt = 1.0 / float(render_hz) + self._camera_spec = camera_spec + self._scene_mesh_path = FilePath(scene_mesh_path) if scene_mesh_path else None + self._scene_mesh_scale = scene_mesh_scale + self._scene_mesh_translation = scene_mesh_translation + self._scene_mesh_rotation_zyx_deg = scene_mesh_rotation_zyx_deg + self._scene_mesh_y_up = scene_mesh_y_up + self._pointcloud_point_size = pointcloud_point_size + + # viser handles for view-mode toggle + self._splat_handle: Any = None + self._scene_mesh_handle: Any = None + # Open3D RaycastingScene built from the scene-mesh geometry. Used + # by the "Set point goal" button to resolve a 2D click into an + # exact 3D surface hit. None when no scene mesh is configured. + self._raycast_scene: Any = None + + # Mutable shared state — written from In subscribers, read from + # the render loop. Plain dict + lock; values are lightweight. + self._state_lock = threading.Lock() + self._latest_joints: dict[str, float] = {} + self._latest_base_pos: np.ndarray | None = None + self._latest_base_wxyz: np.ndarray | None = None + + self._server: Any = None # viser.ViserServer + self._body_frames: dict[int, Any] = {} # body_id -> viser frame handle + self._camera_body_id: int | None = None + self._camera_frustum: Any = None # viser frustum handle + self._robot: RobotMeshes | None = None + self._render_thread: threading.Thread | None = None + self._stop_event = threading.Event() + self._path_handle: Any = None + # Layer-visibility state. Three independent toggles in the + # viser GUI panel — Splat / Mesh / Lidar — each gating one + # backdrop so any subset can be shown. The current and + # previous designs (a Splat-vs-Mesh dropdown plus separate + # checkboxes) were redundant because they overlapped on mesh + # visibility and forced exclusivity the user didn't want. + # GaussianSplatHandle in viser 1.0.26 advertises `.visible` but + # the splat shader pipeline (still labeled "work-in-progress" + # in the docstring) ignores it — flipping the property does + # nothing in the browser. Keep a copy of the loaded splat so + # the toggle can re-add the handle on demand instead. + self._splat_visible: bool = True + self._splat_checkbox: Any = None + self._splat_data: Any = None # cached load_splat() result + self._scene_mesh_visible: bool = True + self._scene_mesh_checkbox: Any = None + # Lidar overlay handle is replaced (not appended) on every + # incoming /global_map message so we don't accumulate + # cloud-on-cloud. `_lidar_visible` gates the upload itself + # so toggling off costs nothing. + self._lidar_handle: Any = None + self._lidar_visible: bool = True + self._lidar_checkbox: Any = None + + @rpc + def start(self) -> None: + super().start() + + import viser + + alignment = ( + SplatAlignment.from_yaml(self._alignment_yaml) + if self._alignment_yaml and self._alignment_yaml.exists() + else SplatAlignment() + ) + + if self._splat_path is not None: + logger.info(f"Viser: loading splat from {self._splat_path}") + splat = load_splat(self._splat_path, alignment=alignment) + logger.info(f"Viser: loaded {len(splat.centers)} Gaussians") + else: + splat = None + logger.info("Viser: splat disabled (no splat_path provided)") + + logger.info(f"Viser: loading robot meshes from {self._mjcf_path}") + self._robot = load_robot_meshes(self._mjcf_path, meshdir=self._mjcf_meshdir) + logger.info( + f"Viser: {len(self._robot.geoms)} visual meshes across " + f"{len(self._robot.body_names)} bodies" + ) + + self._server = viser.ViserServer(host="0.0.0.0", port=self._port) + # Strip the floating control panel down to just a collapse button — + # the viewer is render-only, no GUI controls live in the panel, and + # viser exposes no API to hide the panel entirely. + self._server.gui.set_panel_label(None) + self._server.gui.configure_theme( + control_layout="collapsible", + show_logo=False, + show_share_button=False, + dark_mode=True, + ) + logger.info(f"Viser viewer: http://localhost:{self._port}/") + + if splat is not None: + self._splat_data = splat + self._splat_handle = self._server.scene.add_gaussian_splats( + "/splat", + centers=splat.centers, + covariances=splat.covariances, + rgbs=splat.rgbs, + opacities=splat.opacities, + ) + + # Optional scene mesh (.usdz / .glb / etc.) — drawn in the same + # world frame as the robot. ``MeshCameraModule`` ray-casts the + # same mesh to feed the head-camera RGB topic. + if self._scene_mesh_path is not None and self._scene_mesh_path.exists(): + try: + self._add_scene_mesh() + except Exception as e: + logger.warning(f"Viser: scene mesh load failed: {e}") + + # Three independent layer toggles: Splat / Mesh / Lidar. + # Each checkbox only appears when the corresponding backdrop + # actually exists in this run (no point in a "Show splat" toggle + # when no splat was loaded). Combined, they cover every subset + # — splat-only, mesh-only, lidar-only, splat+mesh, splat+lidar, + # mesh+lidar, all three. + if self._splat_handle is not None: + self._splat_checkbox = self._server.gui.add_checkbox( + "Show splat", initial_value=self._splat_visible + ) + + @self._splat_checkbox.on_update + def _on_splat_toggle(_: Any) -> None: + visible = bool(self._splat_checkbox.value) + self._splat_visible = visible + # `.visible = False` is silently ignored on + # GaussianSplatHandle in viser 1.0.26, so add/remove + # the handle outright. Re-add costs ~one frame from + # the cached splat data. + if visible: + if self._splat_handle is None and self._splat_data is not None: + d = self._splat_data + self._splat_handle = self._server.scene.add_gaussian_splats( + "/splat", + centers=d.centers, + covariances=d.covariances, + rgbs=d.rgbs, + opacities=d.opacities, + ) + else: + if self._splat_handle is not None: + try: + self._splat_handle.remove() + except Exception as e: + logger.debug(f"Viser splat remove failed: {e}") + self._splat_handle = None + + if self._scene_mesh_handle is not None: + self._scene_mesh_checkbox = self._server.gui.add_checkbox( + "Show mesh", initial_value=self._scene_mesh_visible + ) + + @self._scene_mesh_checkbox.on_update + def _on_scene_mesh_toggle(_: Any) -> None: + self._scene_mesh_visible = bool(self._scene_mesh_checkbox.value) + if self._scene_mesh_handle is not None: + self._scene_mesh_handle.visible = self._scene_mesh_visible + + # Lidar map overlay toggle is unconditional — when no publisher is + # connected the cloud stays empty, but having the checkbox + # always present makes the overlay discoverable. + self._lidar_checkbox = self._server.gui.add_checkbox( + "Show lidar map", initial_value=self._lidar_visible + ) + + @self._lidar_checkbox.on_update + def _on_lidar_toggle(_: Any) -> None: + self._lidar_visible = bool(self._lidar_checkbox.value) + if self._lidar_handle is not None: + self._lidar_handle.visible = self._lidar_visible + + # One frame per body; meshes are added as children so they + # follow when the body frame moves. + for body_id, body_name in enumerate(self._robot.body_names): + self._body_frames[body_id] = self._server.scene.add_frame( + f"/robot/{body_name}", + show_axes=False, + ) + for i, geom in enumerate(self._robot.geoms): + color_rgb = ( + int(geom.rgba[0] * 255), + int(geom.rgba[1] * 255), + int(geom.rgba[2] * 255), + ) + self._server.scene.add_mesh_simple( + f"/robot/{geom.body_name}/geom_{i}", + vertices=geom.vertices, + faces=geom.faces, + color=color_rgb, + opacity=float(geom.rgba[3]) if geom.rgba[3] > 0 else 1.0, + position=tuple(geom.local_pos), + wxyz=tuple(geom.local_wxyz), + ) + + # Camera frustum overlay — shows where a robot-mounted RGB sensor + # would look from. Stays None if the configured mount body + # isn't in this MJCF (e.g. swap to a robot without head_link). + if self._camera_spec is not None: + cam_body_id = mujoco.mj_name2id( + self._robot.model, mujoco.mjtObj.mjOBJ_BODY, self._camera_spec.body_name + ) + if cam_body_id < 0: + logger.warning( + f"Viser: camera mount body '{self._camera_spec.body_name}' not in MJCF; " + "frustum overlay disabled" + ) + else: + self._camera_body_id = cam_body_id + self._camera_frustum = self._server.scene.add_camera_frustum( + "/robot/_camera_frustum", + fov=float(np.radians(self._camera_spec.vfov_deg)), + aspect=float(self._camera_spec.aspect), + scale=float(self._camera_spec.frustum_scale), + color=self._camera_spec.frustum_color, + ) + + # Click-to-navigate. We arm a one-shot scene click callback when + # the user presses "Set nav goal", because viser disables camera + # orbit while the click callback is registered (App.tsx:514) — so + # leaving it always-on would break LMB orbit globally. + nav_goal_button = self._server.gui.add_button("Set nav goal") + + @nav_goal_button.on_click + def _arm_nav_goal_click(_event: Any) -> None: + nav_goal_button.disabled = True + nav_goal_button.label = "Click on floor..." + + @self._server.scene.on_pointer_event(event_type="click") + def _on_floor_click(event: Any) -> None: + try: + self._handle_floor_click(event) + finally: + self._server.scene.remove_pointer_callback() + + @self._server.scene.on_pointer_callback_removed + def _rearm_button() -> None: + nav_goal_button.disabled = False + nav_goal_button.label = "Set nav goal" + + # Click-to-point. Same one-shot-callback pattern; the click ray + # is intersected with the scene-mesh raycaster if one is loaded, + # else with an eye-height (z=1.0 m) horizontal plane so pointing + # works even when no scene mesh is configured. Published on + # /point_goal; G1ManipulationModule subscribes and runs point_at. + point_goal_button = self._server.gui.add_button("Set point goal") + + @point_goal_button.on_click + def _arm_point_goal_click(_event: Any) -> None: + point_goal_button.disabled = True + point_goal_button.label = "Click target..." + + @self._server.scene.on_pointer_event(event_type="click") + def _on_point_click(event: Any) -> None: + try: + self._handle_point_goal_click(event) + finally: + self._server.scene.remove_pointer_callback() + + @self._server.scene.on_pointer_callback_removed + def _rearm_point_button() -> None: + point_goal_button.disabled = False + point_goal_button.label = "Set point goal" + + try: + unsub = self.path.subscribe(self._on_path) + self.register_disposable(Disposable(unsub)) + except Exception as e: + logger.warning(f"Viser: path subscribe failed: {e}") + + try: + unsub = self.pointcloud_overlay.subscribe(self._on_lidar) + self.register_disposable(Disposable(unsub)) + except Exception as e: + logger.warning(f"Viser: lidar subscribe failed: {e}") + + try: + unsub = self.joint_state.subscribe(self._on_joint_state) + self.register_disposable(Disposable(unsub)) + except Exception as e: + logger.warning(f"Viser: joint_state subscribe failed: {e}") + + try: + unsub = self.odom.subscribe(self._on_odom) + self.register_disposable(Disposable(unsub)) + except Exception as e: + logger.warning(f"Viser: odom subscribe failed: {e}") + + self._render_thread = threading.Thread( + target=self._render_loop, name="viser-render", daemon=True + ) + self._render_thread.start() + + @rpc + def stop(self) -> None: + self._stop_event.set() + if self._render_thread and self._render_thread.is_alive(): + self._render_thread.join(timeout=2.0) + if self._server is not None: + try: + self._server.stop() + except Exception: + pass + super().stop() + + def _add_scene_mesh(self) -> None: + """Add the configured scene mesh to viser. + + For ``.glb``/``.gltf`` we hand the file's bytes straight to + ``server.scene.add_glb()`` — the browser renders the PBR materials + natively. This is critical: going through ``load_scene_mesh()`` calls + ``trimesh.load(force="mesh")`` which decompresses every embedded + texture to sample per-vertex colors, allocating ~10 GB peak for a + scene with many 4K PBR textures (e.g. the office mesh has 321 textures + totaling ~895 MP). For unknown extensions (USD, OBJ, etc.) we fall back + to the geometry path — those generally don't have the embedded-texture + problem. + """ + assert self._scene_mesh_path is not None + path = self._scene_mesh_path + suffix = path.suffix.lower() + + # Alignment for viser: handed to add_glb as scale + wxyz + position so + # we don't touch the geometry at all on this path. + wxyz = _compose_scene_mesh_wxyz( + y_up=self._scene_mesh_y_up, + rotation_zyx_deg=self._scene_mesh_rotation_zyx_deg, + ) + position = tuple(float(x) for x in self._scene_mesh_translation) + scale = float(self._scene_mesh_scale) + + # Always build a server-side raycaster from the geometry so the + # "Set point goal" button can resolve clicks to surface hits. + # Cheap now that GLBs are geometry-only (textures stripped at + # asset-prep time) — load_scene_mesh peaks at ~1 GB even for the + # 1.4M-vert office mesh. + from dimos.mapping.mesh_scene import ( + SceneMeshAlignment, + load_scene_mesh, + make_raycasting_scene, + ) + + mesh_alignment = SceneMeshAlignment( + scale=self._scene_mesh_scale, + rotation_zyx_deg=self._scene_mesh_rotation_zyx_deg, + translation=self._scene_mesh_translation, + y_up=self._scene_mesh_y_up, + ) + + if suffix in {".glb", ".gltf"}: + logger.info(f"Viser: loading scene mesh {path} (GLB native path)") + with open(path, "rb") as f: + glb_bytes = f.read() + self._scene_mesh_handle = self._server.scene.add_glb( + "/scene_mesh", + glb_data=glb_bytes, + scale=scale, + wxyz=wxyz, + position=position, + ) + logger.info(f"Viser: scene mesh added ({len(glb_bytes) / 1e6:.1f} MB GLB)") + # Build raycaster from geometry separately (browser already + # has the bytes for display; we need o3d structures here). + try: + scene_mesh = load_scene_mesh(path, alignment=mesh_alignment) + self._raycast_scene = make_raycasting_scene(scene_mesh) + logger.info("Viser: scene-mesh raycaster ready for click-to-point") + except Exception as e: + logger.warning( + f"Viser: raycaster build failed (point-goal will use plane fallback): {e}" + ) + return + + # Non-GLB path: USD, OBJ, PLY — geometry-only, no texture decode blowup. + logger.info(f"Viser: loading scene mesh {path}") + scene_mesh = load_scene_mesh(path, alignment=mesh_alignment) + vertices = np.asarray(scene_mesh.vertices, dtype=np.float32) + faces = np.asarray(scene_mesh.triangles, dtype=np.int32) + self._scene_mesh_handle = self._server.scene.add_mesh_simple( + "/scene_mesh", + vertices=vertices, + faces=faces, + color=(180, 180, 180), + opacity=1.0, + ) + logger.info(f"Viser: scene mesh added ({len(vertices)} verts, {len(faces)} tris)") + try: + self._raycast_scene = make_raycasting_scene(scene_mesh) + logger.info("Viser: scene-mesh raycaster ready for click-to-point") + except Exception as e: + logger.warning(f"Viser: raycaster build failed: {e}") + + def _handle_floor_click(self, event: Any) -> None: + """Project the click ray onto the z=0 floor and publish a goal.""" + ray_origin = event.ray_origin + ray_direction = event.ray_direction + if ray_origin is None or ray_direction is None: + return + + ox, oy, oz = ray_origin + dx, dy, dz = ray_direction + if abs(dz) < 1e-6: + logger.info("Viser nav-goal: click ray is parallel to floor, ignoring") + return + t = -oz / dz + if t <= 0: + logger.info("Viser nav-goal: click is above the horizon, ignoring") + return + x = ox + t * dx + y = oy + t * dy + + marker_color = (0, 200, 255) + try: + self._server.scene.add_icosphere( + "/nav_goal_marker", + radius=0.08, + position=(float(x), float(y), 0.05), + color=marker_color, + ) + except Exception as e: + logger.debug(f"Viser nav-goal marker failed: {e}") + + point = PointStamped(x=float(x), y=float(y), z=0.0, ts=time.time(), frame_id="map") + self.clicked_point.publish(point) + logger.info(f"Viser nav-goal: published clicked_point=({x:.3f}, {y:.3f})") + + def _handle_point_goal_click(self, event: Any) -> None: + """Click → 3D world point → publish to /point_goal. + + Resolution order: + 1. Cast against the loaded scene-mesh raycaster (exact surface hit). + 2. Fall back to intersecting an eye-height z=1.0 m plane — picking + a floor target makes no sense for pointing, and eye height is a + reasonable default for "the user clicked on empty space". + """ + ray_origin = event.ray_origin + ray_direction = event.ray_direction + if ray_origin is None or ray_direction is None: + return + + ox, oy, oz = (float(v) for v in ray_origin) + dx, dy, dz = (float(v) for v in ray_direction) + + hit_xyz: tuple[float, float, float] | None = None + + # 1. Scene-mesh ray-cast if we have one. + if self._raycast_scene is not None: + import open3d.core as o3c + + rays = o3c.Tensor( + np.array([[ox, oy, oz, dx, dy, dz]], dtype=np.float32), + dtype=o3c.Dtype.Float32, + ) + t_hit = float(self._raycast_scene.cast_rays(rays)["t_hit"].numpy()[0]) + if np.isfinite(t_hit) and t_hit > 0: + hit_xyz = (ox + t_hit * dx, oy + t_hit * dy, oz + t_hit * dz) + + # 2. Fallback: intersect z = 1.0 m plane. + if hit_xyz is None: + if abs(dz) < 1e-6: + logger.info("Viser point-goal: ray parallel to eye plane, ignoring") + return + t = (1.0 - oz) / dz + if t <= 0: + logger.info("Viser point-goal: target behind camera, ignoring") + return + hit_xyz = (ox + t * dx, oy + t * dy, 1.0) + + x, y, z = hit_xyz + try: + self._server.scene.add_icosphere( + "/point_goal_marker", + radius=0.06, + position=(float(x), float(y), float(z)), + color=(255, 80, 200), # magenta — distinct from nav-goal cyan + ) + except Exception as e: + logger.debug(f"Viser point-goal marker failed: {e}") + + point = PointStamped(x=float(x), y=float(y), z=float(z), ts=time.time(), frame_id="map") + self.point_goal.publish(point) + logger.info(f"Viser point-goal: published point_goal=({x:.3f}, {y:.3f}, {z:.3f})") + + def _on_path(self, msg: PathMsg) -> None: + """Draw the planner's path as a polyline floating above the floor.""" + poses = msg.poses + if len(poses) < 2: + handle = self._path_handle + if handle is not None: + try: + handle.remove() + except Exception: + pass + self._path_handle = None + return + + path_height = 0.10 # lift above floor so it doesn't z-fight with the splat + pts = np.array( + [[p.position.x, p.position.y, path_height] for p in poses], + dtype=np.float32, + ) + # add_line_segments wants (N, 2, 3): start/end of each segment. + segments = np.stack([pts[:-1], pts[1:]], axis=1) + + try: + self._path_handle = self._server.scene.add_line_segments( + "/nav_path", + points=segments, + colors=(255, 30, 30), + line_width=4.0, + ) + except Exception as e: + logger.debug(f"Viser nav-path render failed: {e}") + + def _on_lidar(self, msg: PointCloud2) -> None: + """Replace the lidar overlay in viser with the latest pointcloud. + + The publisher hands us an ``open3d`` PointCloud whose points are + already in the world frame (this is what ``VoxelGridMapper`` + consumes too — see its docstring). We pass the (N, 3) array to + viser's ``add_point_cloud``; the previous handle is overwritten + in-place so we don't accumulate cloud-on-cloud across frames. + """ + if not self._lidar_visible or self._server is None: + return + try: + pcd = msg.pointcloud + pts = np.asarray(pcd.points, dtype=np.float32) + if pts.size == 0: + return + # Per-point colors via height-mapped turbo colormap — same + # gradient + same z-normalization formula rerun's pointcloud + # path uses (PointCloud2.to_rerun) so the two viewers look + # identical when both are running. + from dimos.msgs.sensor_msgs.PointCloud2 import _get_colormap_lut + + lut = _get_colormap_lut("turbo") # (256, 3) uint8, lru-cached + z = pts[:, 2] + z_min, z_max = float(z.min()), float(z.max()) + class_ids = ((z - z_min) / (z_max - z_min + 1e-8) * 255).astype(np.uint8) + colors = lut[class_ids] # (N, 3) uint8 + self._lidar_handle = self._server.scene.add_point_cloud( + "/lidar_overlay", + points=pts, + colors=colors, + point_size=self._pointcloud_point_size, + ) + self._lidar_handle.visible = self._lidar_visible + except Exception as e: + logger.debug(f"Viser lidar overlay update failed: {e}") + + def _on_joint_state(self, msg: JointState) -> None: + names = list(msg.name) + positions = list(msg.position) + if not names or len(names) != len(positions): + return + with self._state_lock: + for n, q in zip(names, positions, strict=False): + self._latest_joints[dimos_joint_to_mjcf(n)] = float(q) + + def _on_odom(self, msg: PoseStamped) -> None: + with self._state_lock: + self._latest_base_pos = np.array( + [msg.position.x, msg.position.y, msg.position.z], + dtype=np.float64, + ) + # PoseStamped quaternion is (x, y, z, w); MuJoCo / Viser want (w, x, y, z). + self._latest_base_wxyz = np.array( + [msg.orientation.w, msg.orientation.x, msg.orientation.y, msg.orientation.z], + dtype=np.float64, + ) + + def _render_loop(self) -> None: + assert self._robot is not None + next_tick = time.monotonic() + while not self._stop_event.is_set(): + with self._state_lock: + joints = dict(self._latest_joints) + base_pos = None if self._latest_base_pos is None else self._latest_base_pos.copy() + base_wxyz = ( + None if self._latest_base_wxyz is None else self._latest_base_wxyz.copy() + ) + + try: + apply_state( + self._robot, + base_pos=base_pos, + base_wxyz=base_wxyz, + joint_positions=joints, + ) + self._update_camera_frustum() + xpos = self._robot.data.xpos + xquat = self._robot.data.xquat + for body_id, frame in self._body_frames.items(): + frame.position = tuple(float(x) for x in xpos[body_id]) + frame.wxyz = tuple(float(x) for x in xquat[body_id]) + except Exception as e: + logger.debug(f"Viser render tick failed: {e}") + + next_tick += self._render_dt + sleep_for = next_tick - time.monotonic() + if sleep_for > 0: + time.sleep(sleep_for) + else: + next_tick = time.monotonic() + + def _update_camera_frustum(self) -> None: + """Place the camera frustum at the current pose of its mount body.""" + if self._camera_frustum is None or self._camera_body_id is None: + return + if self._camera_spec is None: + return + assert self._robot is not None + body_pos = self._robot.data.xpos[self._camera_body_id] + body_wxyz = self._robot.data.xquat[self._camera_body_id] + cam_pos, cam_wxyz = world_pose(body_pos, body_wxyz, self._camera_spec) + self._camera_frustum.position = tuple(float(x) for x in cam_pos) + self._camera_frustum.wxyz = tuple(float(x) for x in cam_wxyz) + + +viser_render = ViserRenderModule.blueprint + + +__all__ = ["ViserRenderModule", "viser_render"] diff --git a/dimos/web/websocket_vis/websocket_vis_module.py b/dimos/web/websocket_vis/websocket_vis_module.py index ed319e52ca..a9bc69536f 100644 --- a/dimos/web/websocket_vis/websocket_vis_module.py +++ b/dimos/web/websocket_vis/websocket_vis_module.py @@ -205,13 +205,6 @@ def stop(self) -> None: if self._uvicorn_server: self._uvicorn_server.should_exit = True - if self.sio and self._broadcast_loop and not self._broadcast_loop.is_closed(): - - async def _disconnect_all() -> None: - await self.sio.disconnect() - - asyncio.run_coroutine_threadsafe(_disconnect_all(), self._broadcast_loop) - if self._broadcast_loop and not self._broadcast_loop.is_closed(): self._broadcast_loop.call_soon_threadsafe(self._broadcast_loop.stop) diff --git a/pyproject.toml b/pyproject.toml index 50403b2ac1..389b74b584 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -177,6 +177,7 @@ agents = [ web = [ "fastapi>=0.115.6", + "python-socketio>=5.11.0,<6", "sse-starlette>=2.2.1", "uvicorn>=0.34.0", "jinja2>=3.1.6", @@ -303,6 +304,13 @@ sim = [ "mujoco>=3.3.4", "playground>=0.0.5", "pygame>=2.6.1", + "usd-core>=24.0", +] + +viz = [ + "dimos[sim]", + "viser>=1.0.26", + "plyfile>=1.1.3", ] navigation = [ diff --git a/uv.lock b/uv.lock index 4106e93992..b88fe316ed 100644 --- a/uv.lock +++ b/uv.lock @@ -1970,6 +1970,7 @@ all = [ { name = "python-lsp-ruff" }, { name = "python-lsp-server", extra = ["all"] }, { name = "python-multipart" }, + { name = "python-socketio" }, { name = "pyturbojpeg" }, { name = "pyyaml" }, { name = "reactivex" }, @@ -2019,6 +2020,7 @@ all = [ { name = "types-tqdm" }, { name = "ultralytics" }, { name = "unitree-webrtc-connect-leshy" }, + { name = "usd-core" }, { name = "uvicorn" }, { name = "watchdog" }, { name = "xacro" }, @@ -2042,6 +2044,7 @@ base = [ { name = "langchain-text-splitters" }, { name = "ollama" }, { name = "openai" }, + { name = "python-socketio" }, { name = "rerun-sdk" }, { name = "sounddevice" }, { name = "soundfile" }, @@ -2188,6 +2191,7 @@ sim = [ { name = "mujoco" }, { name = "playground" }, { name = "pygame" }, + { name = "usd-core" }, ] unitree = [ { name = "anthropic" }, @@ -2205,6 +2209,7 @@ unitree = [ { name = "langchain-text-splitters" }, { name = "ollama" }, { name = "openai" }, + { name = "python-socketio" }, { name = "rerun-sdk" }, { name = "sounddevice" }, { name = "soundfile" }, @@ -2229,6 +2234,7 @@ unitree-dds = [ { name = "langchain-text-splitters" }, { name = "ollama" }, { name = "openai" }, + { name = "python-socketio" }, { name = "rerun-sdk" }, { name = "sounddevice" }, { name = "soundfile" }, @@ -2241,10 +2247,19 @@ visualization = [ { name = "dimos-viewer" }, { name = "rerun-sdk" }, ] +viz = [ + { name = "mujoco" }, + { name = "playground" }, + { name = "plyfile" }, + { name = "pygame" }, + { name = "usd-core" }, + { name = "viser" }, +] web = [ { name = "fastapi" }, { name = "ffmpeg-python" }, { name = "jinja2" }, + { name = "python-socketio" }, { name = "soundfile" }, { name = "sse-starlette" }, { name = "uvicorn" }, @@ -2268,6 +2283,7 @@ requires-dist = [ { name = "dimos", extras = ["agents", "base", "cpu", "cuda", "dev", "docker", "drone", "manipulation", "misc", "perception", "psql", "sim", "unitree", "visualization", "web"], marker = "extra == 'all'" }, { name = "dimos", extras = ["agents", "web", "visualization"], marker = "extra == 'base'" }, { name = "dimos", extras = ["base"], marker = "extra == 'unitree'" }, + { name = "dimos", extras = ["sim"], marker = "extra == 'viz'" }, { name = "dimos", extras = ["unitree"], marker = "extra == 'unitree-dds'" }, { name = "dimos-lcm" }, { name = "dimos-lcm", marker = "extra == 'docker'" }, @@ -2336,6 +2352,7 @@ requires-dist = [ { name = "plotly", marker = "extra == 'manipulation'", specifier = ">=5.9.0" }, { name = "plum-dispatch", specifier = "==2.5.7" }, { name = "plum-dispatch", marker = "extra == 'docker'", specifier = "==2.5.7" }, + { name = "plyfile", marker = "extra == 'viz'", specifier = ">=1.1.3" }, { name = "portal", marker = "extra == 'misc'" }, { name = "pre-commit", marker = "extra == 'dev'", specifier = "==4.2.0" }, { name = "protobuf", specifier = ">=6.33.5,<7" }, @@ -2359,6 +2376,7 @@ requires-dist = [ { name = "python-lsp-ruff", marker = "extra == 'dev'", specifier = "==2.3.0" }, { name = "python-lsp-server", extras = ["all"], marker = "extra == 'dev'", specifier = "==1.14.0" }, { name = "python-multipart", marker = "extra == 'misc'", specifier = ">=0.0.27" }, + { name = "python-socketio", marker = "extra == 'web'", specifier = ">=5.11.0,<6" }, { name = "pyturbojpeg", specifier = "==1.8.2" }, { name = "pyturbojpeg", marker = "extra == 'docker'" }, { name = "pyyaml", marker = "extra == 'manipulation'", specifier = ">=6.0" }, @@ -2420,7 +2438,9 @@ requires-dist = [ { name = "ultralytics", marker = "extra == 'perception'", specifier = ">=8.3.70" }, { name = "unitree-sdk2py-dimos", marker = "extra == 'unitree-dds'", specifier = ">=1.0.2" }, { name = "unitree-webrtc-connect-leshy", marker = "extra == 'unitree'", specifier = ">=2.0.7" }, + { name = "usd-core", marker = "extra == 'sim'", specifier = ">=24.0" }, { name = "uvicorn", marker = "extra == 'web'", specifier = ">=0.34.0" }, + { name = "viser", marker = "extra == 'viz'", specifier = ">=1.0.26" }, { name = "watchdog", marker = "extra == 'dev'", specifier = ">=3.0.0" }, { name = "xacro", marker = "extra == 'manipulation'" }, { name = "xarm-python-sdk", marker = "extra == 'manipulation'", specifier = ">=1.17.0" }, @@ -2428,7 +2448,7 @@ requires-dist = [ { name = "xformers", marker = "platform_machine == 'x86_64' and extra == 'cuda'", specifier = ">=0.0.20" }, { name = "yapf", marker = "extra == 'misc'", specifier = "==0.40.2" }, ] -provides-extras = ["misc", "visualization", "agents", "web", "perception", "unitree", "unitree-dds", "manipulation", "cpu", "cuda", "dev", "psql", "sim", "navigation", "drone", "dds", "docker", "base", "all"] +provides-extras = ["misc", "visualization", "agents", "web", "perception", "unitree", "unitree-dds", "manipulation", "cpu", "cuda", "dev", "psql", "sim", "viz", "navigation", "drone", "dds", "docker", "base", "all"] [[package]] name = "dimos-lcm" @@ -2672,6 +2692,35 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/87/62/9773de14fe6c45c23649e98b83231fffd7b9892b6cf863251dc2afa73643/einops-0.8.1-py3-none-any.whl", hash = "sha256:919387eb55330f5757c6bea9165c5ff5cfe63a642682ea788a6d472576d81737", size = 64359, upload-time = "2025-02-09T03:17:01.998Z" }, ] +[[package]] +name = "embreex" +version = "4.4.0" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11' and platform_machine == 'x86_64'" }, + { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11' and platform_machine == 'x86_64'" }, +] +wheels = [ + { url = "https://files.pythonhosted.org/packages/14/fe/cedef264696768248f8139c569e10796ffb76627383adb5a60e1eaf28a20/embreex-4.4.0-cp310-cp310-macosx_13_0_x86_64.whl", hash = "sha256:daf8b1848798523d7d71cc22f2610401ab02ec93ea063f9cbb90dcb9abda2ccf", size = 13215487, upload-time = "2026-04-22T19:46:32.769Z" }, + { url = "https://files.pythonhosted.org/packages/11/f5/460b7f79689ac5e6ceb3ec2a1194176a0a66d6c4e010dae68ba899a1c927/embreex-4.4.0-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:f548cbebc550624ef08530ed9dcd147eeddcd181fd8f32cf3378800b39b21034", size = 14438524, upload-time = "2026-04-22T19:46:35.533Z" }, + { url = "https://files.pythonhosted.org/packages/9f/c2/aef3606d7ca2b4d2d18e57c8f65762b94d253e678a05c946649bb1913f5e/embreex-4.4.0-cp310-cp310-win_amd64.whl", hash = "sha256:58921ef7ad488dbd514b3053e7c4a9fdcd2f7008426b3185b9f1bd394c608edd", size = 13119003, upload-time = "2026-04-22T19:46:38.442Z" }, + { url = "https://files.pythonhosted.org/packages/4c/0c/1bcdcb8cb09713d40c3cc6d303a4e456113df859dacb28a1b7af8a19a718/embreex-4.4.0-cp311-cp311-macosx_13_0_x86_64.whl", hash = "sha256:96a187753f578cb685051f8fd679dc7986f887fcb922bb81a9924f5b89e941d8", size = 13214875, upload-time = "2026-04-22T19:46:43.439Z" }, + { url = "https://files.pythonhosted.org/packages/7d/1d/bed6f27a57b89ad028c8ec5adf6f1877a1ef92d983d703abb7a70717f0d9/embreex-4.4.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:8415d14c8956afec7eb05749f1e0bf396bb51efd566054ca169e10e4089e7bb7", size = 14474358, upload-time = "2026-04-22T19:46:46.056Z" }, + { url = "https://files.pythonhosted.org/packages/21/f4/c3515fde7bacab245673988398ef40928ce0b9fb54e2b51e90a4a4535479/embreex-4.4.0-cp311-cp311-win_amd64.whl", hash = "sha256:bfa54fb71cbb3a41c2366cabd09bb2dbbc8700843872f2c8655a3215a73459a7", size = 13119132, upload-time = "2026-04-22T19:46:48.753Z" }, + { url = "https://files.pythonhosted.org/packages/6d/78/8cc0960cc0f2d60d581869a66c8013e1bf1c73bf5bf9609bd8aa79e0f721/embreex-4.4.0-cp312-cp312-macosx_13_0_x86_64.whl", hash = "sha256:8e93bce7cf905365117dea2d0726d19262c88a010044d00631db6bb7dc145612", size = 13214768, upload-time = "2026-04-22T19:46:54.088Z" }, + { url = "https://files.pythonhosted.org/packages/79/b0/05a5b4d49749602b12e13d1871f8e6d1fe6db806eda75f6f57bb4f1acf6f/embreex-4.4.0-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:cb0872f5bc231f465b840b122847acbaf468ac48f49bfaff127c5347ec0db94f", size = 14529899, upload-time = "2026-04-22T19:46:56.824Z" }, + { url = "https://files.pythonhosted.org/packages/b5/96/625e035f3433071c91de07e66265a261be7bb708367f785000f93d7a992a/embreex-4.4.0-cp312-cp312-win_amd64.whl", hash = "sha256:6c092ee1adf5c48b7430c7ae3902943863745e54b4aef4327ecb3473e0a299d7", size = 13119305, upload-time = "2026-04-22T19:46:59.329Z" }, + { url = "https://files.pythonhosted.org/packages/36/d2/9bbde8d9d520c2a7bcad892631165b9676d9dcbde381f25bfda06d0f6e42/embreex-4.4.0-cp313-cp313-macosx_13_0_x86_64.whl", hash = "sha256:078bae4dcebb2a64c8dde6b3c178f258f966c4514e265608620033a6c907e21b", size = 13212105, upload-time = "2026-04-22T19:47:04.511Z" }, + { url = "https://files.pythonhosted.org/packages/03/5d/3e5ca5dea1c2c5b4604f3bedb67ea4beaa465398d9c04d8124ca3d657b05/embreex-4.4.0-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:cd305875e2cd7c51004a423fe7da9881fa266fa4a50e61dd546978e10f020e66", size = 14486730, upload-time = "2026-04-22T19:47:07.229Z" }, + { url = "https://files.pythonhosted.org/packages/45/00/26741306e557129d398744601cd9bca4069d52cebe146ba99e535f9f2c65/embreex-4.4.0-cp313-cp313-win_amd64.whl", hash = "sha256:433de9063843804d70bb3c1680619bb28bc6403b79d3d94560ec9acc3df96eda", size = 13117246, upload-time = "2026-04-22T19:47:10.08Z" }, + { url = "https://files.pythonhosted.org/packages/f5/ac/638a6b4a6cb67125a3c2676a108fb73d75e67b3ce3813f25b6056d0b77cd/embreex-4.4.0-cp314-cp314-macosx_13_0_x86_64.whl", hash = "sha256:ab3c50ecd3aa6c39491928d975b00c9f5eeaa1b39b74bab87170c17e2df1bfde", size = 13212439, upload-time = "2026-04-22T19:47:15.009Z" }, + { url = "https://files.pythonhosted.org/packages/39/1c/567194e9f5bdbb5099144dae3202452821319ff348e328b50c0fbacc3828/embreex-4.4.0-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:3b0bd41b10dc2f1ad4995faef08d924d5f33a5d47afb97ba5801c820f305db6d", size = 14480771, upload-time = "2026-04-22T19:47:17.681Z" }, + { url = "https://files.pythonhosted.org/packages/d1/8d/a46fb6ca4cc898e8d06449a4b46a8c22a28971f1e6d9bb6c99459bbb96d1/embreex-4.4.0-cp314-cp314-win_amd64.whl", hash = "sha256:80f938291832ab11dc7a604d609bce2587d574b4fe862be91d117562629f1b94", size = 13373573, upload-time = "2026-04-22T19:47:21.487Z" }, + { url = "https://files.pythonhosted.org/packages/61/5e/da7c1448c209f406a5b43a8feb07489e8652a64c48450b5642d3f34cf9e7/embreex-4.4.0-cp314-cp314t-macosx_13_0_x86_64.whl", hash = "sha256:ea332cfe60f3b242ecb557ef7b5fcbffec5edd0f3127241bed343d090ac735e2", size = 13218445, upload-time = "2026-04-22T19:47:25.847Z" }, + { url = "https://files.pythonhosted.org/packages/a5/d4/8cb8a41b25138999a98286ae1562e5903c7579ec71becc05bfa1c10d571f/embreex-4.4.0-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:1e3481b76df80f23128173486ac0efe55e9199fc311bc74707452b4f19951eff", size = 14589303, upload-time = "2026-04-22T19:47:28.544Z" }, + { url = "https://files.pythonhosted.org/packages/93/3d/8b393b35016909143ecac7bf7bf418f79236e1f83faf3867b5c5cb50c97f/embreex-4.4.0-cp314-cp314t-win_amd64.whl", hash = "sha256:a2fedc756a36729da6803425398aa4987b27d1d89e9fad403d8ef371fad5ca01", size = 13389585, upload-time = "2026-04-22T19:47:31.398Z" }, +] + [[package]] name = "empy" version = "3.3.4" @@ -3585,6 +3634,20 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/9c/1f/19ebc343cc71a7ffa78f17018535adc5cbdd87afb31d7c34874680148b32/ifaddr-0.2.0-py3-none-any.whl", hash = "sha256:085e0305cfe6f16ab12d72e2024030f5d52674afad6911bb1eee207177b8a748", size = 12314, upload-time = "2022-06-15T21:40:25.756Z" }, ] +[[package]] +name = "imageio" +version = "2.37.3" +source = { registry = "https://pypi.org/simple" } +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 = "pillow" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/b1/84/93bcd1300216ea50811cee96873b84a1bebf8d0489ffaf7f2a3756bab866/imageio-2.37.3.tar.gz", hash = "sha256:bbb37efbfc4c400fcd534b367b91fcd66d5da639aaa138034431a1c5e0a41451", size = 389673, upload-time = "2026-03-09T11:31:12.573Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/49/fa/391e437a34e55095173dca5f24070d89cbc233ff85bf1c29c93248c6588d/imageio-2.37.3-py3-none-any.whl", hash = "sha256:46f5bb8522cd421c0f5ae104d8268f569d856b29eb1a13b92829d1970f32c9f0", size = 317646, upload-time = "2026-03-09T11:31:10.771Z" }, +] + [[package]] name = "importlib-metadata" version = "8.7.1" @@ -5004,6 +5067,118 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ca/28/2635a8141c9a4f4bc23f5135a92bbcf48d928d8ca094088c962df1879d64/lz4-4.4.5-cp314-cp314-win_arm64.whl", hash = "sha256:d994b87abaa7a88ceb7a37c90f547b8284ff9da694e6afcfaa8568d739faf3f7", size = 93812, upload-time = "2025-11-03T13:02:26.133Z" }, ] +[[package]] +name = "manifold3d" +version = "3.4.1" +source = { registry = "https://pypi.org/simple" } +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' and python_full_version < '3.14'" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/b0/fd/4dfc246e076e3912c45a821764f4de8b6c8117fa36fc67f8e44bf9dfe59b/manifold3d-3.4.1.tar.gz", hash = "sha256:b517927e2c15dc52169fff0cd12e1949eceb4ca49f3a5b8c0568b1116a561ab1", size = 269275, upload-time = "2026-03-24T06:22:40.062Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/5b/43/9ce593ad180d69f802e7b9837da95567c30e6af3cb1b66f3c254d0eb4445/manifold3d-3.4.1-cp310-cp310-macosx_10_14_universal2.whl", hash = "sha256:2ec55079d4c4ada4aaa3708559a473b41817ed9d226c61e1a6d43b0ef17390c5", size = 1739369, upload-time = "2026-03-24T06:21:35.762Z" }, + { url = "https://files.pythonhosted.org/packages/6a/7a/547b4098cffecedc5e4dc5d8eb753d8ede90bed5b325e75476ae5edb7340/manifold3d-3.4.1-cp310-cp310-macosx_10_14_x86_64.whl", hash = "sha256:6cf5abadc56c094fbaf135e2474db79ade3dba6210bb9b7aff90d48361c328b1", size = 942685, upload-time = "2026-03-24T06:21:37.512Z" }, + { url = "https://files.pythonhosted.org/packages/4e/94/f8baf4269dcd34d4d1a4ef42c4724231f5fc57a81f0ad65fcbade2cdf00d/manifold3d-3.4.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:274d87ead558f0e29eec874e588789200f578b6132b3bd8e4ce4e1da21fe10a8", size = 828147, upload-time = "2026-03-24T06:21:39.172Z" }, + { url = "https://files.pythonhosted.org/packages/94/c9/8a634c6304c0a9f4d0ca1c59cf798f90a3ad174d32d9390a7b938b0f7bf5/manifold3d-3.4.1-cp310-cp310-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0002baedc42cb1562cf723d0362ef99a9675bf5455dabd1d9ba893868a132ad0", size = 1238708, upload-time = "2026-03-24T06:21:40.623Z" }, + { url = "https://files.pythonhosted.org/packages/a9/62/3df433dce9f87e7a4d76bbdbb6339a70a674fd8e350055bf88b4085c1e80/manifold3d-3.4.1-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:308e3dda79236b9258dd0d13cfc56f932a372ca5f56677bb06ed65585a447045", size = 1340136, upload-time = "2026-03-24T06:21:42.013Z" }, + { url = "https://files.pythonhosted.org/packages/cc/65/462e5422e39f7e57a28281bb5c5c55b7a1a50f71bcbbc34730ade5f3fb33/manifold3d-3.4.1-cp310-cp310-win_amd64.whl", hash = "sha256:ef8d5bb14f827738179d472f9deeb43323e82b92afe9ee359c175120ce5194d0", size = 970295, upload-time = "2026-03-24T06:21:43.654Z" }, + { url = "https://files.pythonhosted.org/packages/af/14/42f1d0fbe0dbbaf7abd9ffb83596a84cea7b3d84c40f0c20a3474a23e397/manifold3d-3.4.1-cp311-cp311-macosx_10_14_universal2.whl", hash = "sha256:5b4ba7b71ffd6bf16682acff89cb72ade3eba54ea05d58d956c3a95d982ed8e4", size = 1753383, upload-time = "2026-03-24T06:21:45.602Z" }, + { url = "https://files.pythonhosted.org/packages/35/47/3d5369c2485c48c2510eab4e803b29296edecbce78c9069995731bff9635/manifold3d-3.4.1-cp311-cp311-macosx_10_14_x86_64.whl", hash = "sha256:095b072e89485f00af8aeed0a88e72c19f9740467824d6653b329851c3928c14", size = 956296, upload-time = "2026-03-24T06:21:47.257Z" }, + { url = "https://files.pythonhosted.org/packages/75/d4/d01a5579b636e49a106071365f82d0c7a695226cbc6dc077304e51bfc86f/manifold3d-3.4.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:539c2467abc58754b74dc9bb3422ddd4e73a5b11b006f27c0ba6302bab6ecfe9", size = 841995, upload-time = "2026-03-24T06:21:48.529Z" }, + { url = "https://files.pythonhosted.org/packages/d8/63/32c64efc0a34f23776dc339f8b1cdbcc61b12a80ade261f2e7a358af52d9/manifold3d-3.4.1-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:42c0c8ab2495acd514e8f46e5acd9465937c46c8c06e45e2f02da983b849bcea", size = 1252454, upload-time = "2026-03-24T06:21:50.317Z" }, + { url = "https://files.pythonhosted.org/packages/d7/f2/6c7ec5986bc3cfc9251878ade6e65354538a8bc569c5e51c483aa4310063/manifold3d-3.4.1-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:aa75de877ccda5482493f65659de240d4bb7c96e3cc4ce96509ecd6ef9f91fbc", size = 1353505, upload-time = "2026-03-24T06:21:52.428Z" }, + { url = "https://files.pythonhosted.org/packages/94/61/9e8ab3a9ce6e7e6099794afd25abe1e4e7934f31529c55331bf8019bc736/manifold3d-3.4.1-cp311-cp311-win_amd64.whl", hash = "sha256:2aff8707558e2fa5ff241185fe71da18ac8bd4156fb2811401df3366e461c562", size = 983641, upload-time = "2026-03-24T06:21:53.876Z" }, + { url = "https://files.pythonhosted.org/packages/d9/59/def4c589dd55aa32026a720f8a31d71aa2162fef8e3963b6241a7945ef4e/manifold3d-3.4.1-cp312-cp312-macosx_10_14_universal2.whl", hash = "sha256:967c89daf24ec9ff863323d593cce98e4c130abbaaa9504df6789f9d8c780d0d", size = 1752517, upload-time = "2026-03-24T06:21:55.203Z" }, + { url = "https://files.pythonhosted.org/packages/b1/a9/377800999cc8421ce8bfa40787d09570bb635e0099f44959170fee751dd7/manifold3d-3.4.1-cp312-cp312-macosx_10_14_x86_64.whl", hash = "sha256:c29db9a1bda414ecaa56dd2cd274f06bbbe740e463133c5b69943d82c3dcfb96", size = 956343, upload-time = "2026-03-24T06:21:57.134Z" }, + { url = "https://files.pythonhosted.org/packages/6a/72/7f988a0deae9b3fbed3a6b2e9285e96fd9105e95f6755f5457e3a80e103e/manifold3d-3.4.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2ae6855a6f652acd89e228f1981e5b710d4b10e06d7c06e5bada3b3fb31904a3", size = 840924, upload-time = "2026-03-24T06:21:58.462Z" }, + { url = "https://files.pythonhosted.org/packages/bf/46/787ad4b53a35ccf1d31fbd3d2ffe0653dab67057b1f561db51d2edc494ba/manifold3d-3.4.1-cp312-cp312-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:a8068f85416034e290d23b424f2bea15d2f1da1c5ccb79b442bdb50ed4e1a4b6", size = 1253014, upload-time = "2026-03-24T06:21:59.734Z" }, + { url = "https://files.pythonhosted.org/packages/e2/45/29d2380ac477b11629a72483b21dd544861caccaedbc87043bf315a15a50/manifold3d-3.4.1-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:fe9ff5ce3d949c72b21120318121eb926ddba4299eab0e8bab2c6784a9843ffb", size = 1355512, upload-time = "2026-03-24T06:22:01.518Z" }, + { url = "https://files.pythonhosted.org/packages/7f/7f/310688a725a5a23d00e9f29e614a2b7906b399df27731b1aa6e153e4f465/manifold3d-3.4.1-cp312-cp312-win_amd64.whl", hash = "sha256:1bd6fa1b20238603ec3df7f6060ddba1181cf9464104e82b746747b487d12092", size = 983293, upload-time = "2026-03-24T06:22:03.273Z" }, + { url = "https://files.pythonhosted.org/packages/e3/d0/b066b476242dddfad98db51425a28ac41ab008a4e7697f6d6bca21a24881/manifold3d-3.4.1-cp313-cp313-macosx_10_14_universal2.whl", hash = "sha256:210ec6918870611d9e3f888c00657aad842cfa89a7967e94546a568bf8dfc2f1", size = 1752343, upload-time = "2026-03-24T06:22:04.731Z" }, + { url = "https://files.pythonhosted.org/packages/11/2c/10b5cb142b00bb7b14bb5698c584ce7722c68c3ed58ae4173693a35d2108/manifold3d-3.4.1-cp313-cp313-macosx_10_14_x86_64.whl", hash = "sha256:d4e1dd76a3c5fe935bc14eb62f98ce2361e0e505fcfca08abb2f9d8a1d01e0db", size = 956241, upload-time = "2026-03-24T06:22:06.404Z" }, + { url = "https://files.pythonhosted.org/packages/05/a7/af84e5f6e6af2d07d800355345ffb303c4e8de96dbf3194633322f3d8335/manifold3d-3.4.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:7e1bf4857f64311fb5113ff286898c47efc0f199e4d860cfc663b5f69ce90ede", size = 840900, upload-time = "2026-03-24T06:22:07.974Z" }, + { url = "https://files.pythonhosted.org/packages/80/1c/f274d6e35652c3fb72b54c5fcafc5fc474e1a93d3fd17fb8df3c9c765873/manifold3d-3.4.1-cp313-cp313-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:9b23435456d5ed64e48a34a281869c3b626da8ccd8872e54637b77f420716f9a", size = 1252521, upload-time = "2026-03-24T06:22:09.259Z" }, + { url = "https://files.pythonhosted.org/packages/97/90/82081bcbffc68e36f9f34c36f041d6e0176cbb462e9041683d82ff17b626/manifold3d-3.4.1-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6871adaf9e5081303d2c9446de5a76a9af84bcf938949fa198cc5f0ae9cad19f", size = 1355366, upload-time = "2026-03-24T06:22:10.892Z" }, + { url = "https://files.pythonhosted.org/packages/0d/db/26df1d96a2c61a4d79aeb0ca2f8bfbfd4af94fdb944469dda38ced240f2f/manifold3d-3.4.1-cp313-cp313-win_amd64.whl", hash = "sha256:0a93e8202cccea16c76a6c3a7d02300755cccea6536874ccfc160f8c4d8948c4", size = 983317, upload-time = "2026-03-24T06:22:12.257Z" }, + { url = "https://files.pythonhosted.org/packages/26/50/d62f9fed01bdeaea50d3dd821498573c0bf1c286e54e5a632f47cef8fffa/manifold3d-3.4.1-cp314-cp314-macosx_10_15_universal2.whl", hash = "sha256:632525867f23a5d34ab4a7b9129dc440a6ed2b4a0444d9feddb6069361107555", size = 1752191, upload-time = "2026-03-24T06:22:13.521Z" }, + { url = "https://files.pythonhosted.org/packages/1c/2e/464f3898f8f1b727a248d4b2bedc310d60efed1a0f43f9977f95f122fcf4/manifold3d-3.4.1-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:c4e755c0a1d808603185fb5a562c045c71918b4e64a498c489eba658df49692b", size = 956239, upload-time = "2026-03-24T06:22:14.864Z" }, + { url = "https://files.pythonhosted.org/packages/0e/ec/da4bdba9ae1fe9049be9e2f42336ebf700dfd839795b561fb0cee9cb03f6/manifold3d-3.4.1-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:2c9c20b479e15ec5f0710951d3ae4f95635d0bbf6502f03e43ed87e310e69230", size = 840646, upload-time = "2026-03-24T06:22:16.471Z" }, + { url = "https://files.pythonhosted.org/packages/eb/e0/c476d79d5940da31cf6d0aa9353e56d70fe709fefbadd3c99804594aeb4d/manifold3d-3.4.1-cp314-cp314-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:145b94b7bb73b425fa42bb795d5c8eaea5de5e45cba9731f2542c7311f3a73c3", size = 1253522, upload-time = "2026-03-24T06:22:17.734Z" }, + { url = "https://files.pythonhosted.org/packages/89/fa/2d5838248950b8cb41ba22496dfc7e95222582761ec83e473a210a0be059/manifold3d-3.4.1-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:1093c002a5f5c012219208bfb0b49f4821974f887cbd357316b9dbab74b7fa5b", size = 1356044, upload-time = "2026-03-24T06:22:19.375Z" }, + { url = "https://files.pythonhosted.org/packages/95/a7/2b8e4b88a613b0057b871ca71342d7237289c5eccf2f75ce10afa04e080e/manifold3d-3.4.1-cp314-cp314-win_amd64.whl", hash = "sha256:04c99b94fbb92572051288d3c6163baf9c81a647dab33d1fdce418457b0a1a44", size = 1014216, upload-time = "2026-03-24T06:22:20.977Z" }, + { url = "https://files.pythonhosted.org/packages/4f/06/c8c5e38b5f93ce2268aa0fc2e4e995a04c8722045868dc75021a7c2a5bc9/manifold3d-3.4.1-cp314-cp314t-macosx_10_15_universal2.whl", hash = "sha256:22bb8c202c88072fd5cd3fb24243715e7b200151a8aa3da78661b3611e07924f", size = 1760559, upload-time = "2026-03-24T06:22:22.701Z" }, + { url = "https://files.pythonhosted.org/packages/7e/93/5defaadef6a57bb864a51f68c824435929a7c7de1205f95e166325cba55e/manifold3d-3.4.1-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:9ade2f14cf906271604ccfa5c49bb5704f0c14b08367e6d3aa0c4ed6ed56f919", size = 961249, upload-time = "2026-03-24T06:22:24.364Z" }, + { url = "https://files.pythonhosted.org/packages/fd/fa/5705986493097e268f26d87b3cfce8e966f6c62a1b8f38fa4086b704cf4d/manifold3d-3.4.1-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:b4b24047cf423b024f477c09e2c44fed5991cbca4906abf34bf6ced62f37ef93", size = 846070, upload-time = "2026-03-24T06:22:25.946Z" }, + { url = "https://files.pythonhosted.org/packages/2a/84/925d96698fbd90e9990a7a4fdd9a7a8b038e166de696673cfd141bf54e85/manifold3d-3.4.1-cp314-cp314t-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:2e02108ee43c6dcf1f40b208569ad49dcf1a6ceed21fd6d5fd6e8f09c02a8b60", size = 1260343, upload-time = "2026-03-24T06:22:27.266Z" }, + { url = "https://files.pythonhosted.org/packages/07/0a/f2d1c6390ebd565fa44357cddc9e6aa783fbccb0cc952996217bcbc69699/manifold3d-3.4.1-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:b1ac2b29c6ca1412f63a1ac2c240ae067fe03f666bb12a21729012275fbbde85", size = 1361860, upload-time = "2026-03-24T06:22:28.945Z" }, + { url = "https://files.pythonhosted.org/packages/8b/9b/5d0cf29530e31c2ef66cc9b2780031a82955002ad924b0eb23ac5e3dd90f/manifold3d-3.4.1-cp314-cp314t-win_amd64.whl", hash = "sha256:4d3f795cfcaa857f4bd9bf62bd3f15061bae502fb4cea87e820f4bba67045ff8", size = 1022928, upload-time = "2026-03-24T06:22:30.285Z" }, +] + +[[package]] +name = "mapbox-earcut" +version = "2.0.0" +source = { registry = "https://pypi.org/simple" } +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'" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/bc/7b/bbf6b00488662be5d2eb7a188222c264b6f713bac10dc4a77bf37a4cb4b6/mapbox_earcut-2.0.0.tar.gz", hash = "sha256:81eab6b86cf99551deb698b98e3f7502c57900e5c479df15e1bdaf1a57f0f9d6", size = 39934, upload-time = "2025-11-16T18:41:27.251Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/a8/d3/5222339a8fad091bf64f2e3041e48606d69d69f0609a7632ca17a8a05d5a/mapbox_earcut-2.0.0-cp310-cp310-macosx_10_13_x86_64.whl", hash = "sha256:c9a1dab7529f8e54bdb377f908e56f1e2b9a7e27ed168c64d3c7c38ed04ac201", size = 55920, upload-time = "2025-11-16T18:40:09.254Z" }, + { url = "https://files.pythonhosted.org/packages/19/e4/88d06e83ab75db2f4ae140a1e03ad8f84b02ac8af585dd61108aba73b8ed/mapbox_earcut-2.0.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:5e5953098ea198253c8a40e2f282ca5b04d50ec2b9661e20c4cd2b2be39f0bb0", size = 52557, upload-time = "2025-11-16T18:40:10.536Z" }, + { url = "https://files.pythonhosted.org/packages/22/88/abefd244ea049e42334c5f7a9e3b58f4ec3c84d063119ba3c8d27ff31932/mapbox_earcut-2.0.0-cp310-cp310-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:efe5fd5de409e3b6d13907e73f295c8f1d63bdb6b8ca155dde4c93865796eafe", size = 56950, upload-time = "2025-11-16T18:40:11.905Z" }, + { url = "https://files.pythonhosted.org/packages/3c/e2/11122fddd086b930502eb4a954735da0f75e9d658fdab2d9e5914b9ebd2a/mapbox_earcut-2.0.0-cp310-cp310-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:cd04da6edbca1dd68ddbfac2398a95c763f35d7317fed227fde5b3aff1253b18", size = 59618, upload-time = "2025-11-16T18:40:13.017Z" }, + { url = "https://files.pythonhosted.org/packages/e8/fd/e62195729daa3111fe95404a99c7a6b3aa174800373d10111b7e7278a789/mapbox_earcut-2.0.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:8bdb8881e857d6d9277df696e9cfb8749c00d6162021d9359cba9da58dfdd4f5", size = 153021, upload-time = "2025-11-16T18:40:14.294Z" }, + { url = "https://files.pythonhosted.org/packages/2c/6a/d39ebaaa9010ea6c9f4d468f8812b1a1b31a40fba4f02ff29bc1bf321c30/mapbox_earcut-2.0.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:6e2d1bf5af90d5857955775b4d8ea15b02e172f2a8f194bba50ff95f8ff3e80e", size = 157736, upload-time = "2025-11-16T18:40:16.344Z" }, + { url = "https://files.pythonhosted.org/packages/20/00/6a59cdb8d8c1bf7e3cc92f0404f68fdb1a3cb0bbb0837af0dbb93d6290a6/mapbox_earcut-2.0.0-cp310-cp310-win32.whl", hash = "sha256:5b0aa63dd890d712343095b05eb7b60e071912ad3ced1fc4187d6a6a739677bc", size = 51564, upload-time = "2025-11-16T18:40:17.852Z" }, + { url = "https://files.pythonhosted.org/packages/bc/7b/af69669c959d8f7fd1bd49c15deace2360bf6a79dad7bf9f7a7f1c137da6/mapbox_earcut-2.0.0-cp310-cp310-win_amd64.whl", hash = "sha256:b1355f13af89ea815b32f59a5455db295c965d51ab501bde0459cddc010a7149", size = 56793, upload-time = "2025-11-16T18:40:18.953Z" }, + { url = "https://files.pythonhosted.org/packages/07/9f/fbd15d9e348e75e986d6912c4eab99888106b7e5fb0a01e765422f7cd464/mapbox_earcut-2.0.0-cp311-cp311-macosx_10_13_x86_64.whl", hash = "sha256:9b5040e79e3783295e99c90277f31c1cbaddd3335297275331995ba5680e3649", size = 55773, upload-time = "2025-11-16T18:40:20.045Z" }, + { url = "https://files.pythonhosted.org/packages/72/40/be761298704fbbaa81c5618bb306f1510fb068e482f6a1c8b3b6c1b31479/mapbox_earcut-2.0.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:1cf43baafec3ef1e967319d9b5da96bc6ddf3dbb204b6f3535275eda4b519a72", size = 52444, upload-time = "2025-11-16T18:40:21.501Z" }, + { url = "https://files.pythonhosted.org/packages/5a/0b/0c0c08db9663238ffb82c48259582dc0047a3255d98c0ac83c48026b7544/mapbox_earcut-2.0.0-cp311-cp311-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:3a283531847f603dd9d69afb75b21bd009d385ca9485fcd3e5a7fa5db1ccd913", size = 56803, upload-time = "2025-11-16T18:40:22.891Z" }, + { url = "https://files.pythonhosted.org/packages/f0/4a/86796859383d7d11fa5d4bcf1983f94c6cbb9eeb60fb3bab527fec4b32fa/mapbox_earcut-2.0.0-cp311-cp311-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:ab697676f4cec4572d4e941b7a3429a6687bf2ac6e8db3f3781024e3239ae3a0", size = 59403, upload-time = "2025-11-16T18:40:24.021Z" }, + { url = "https://files.pythonhosted.org/packages/6c/db/adaf981ab3bcfcf993ef317636b1f27210d6834bb1e8d63db6ad7c08214a/mapbox_earcut-2.0.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:f1bdac76e048f4299accf4eaf797079ddfc330442e7231c15535ed198100d6c5", size = 152876, upload-time = "2025-11-16T18:40:25.588Z" }, + { url = "https://files.pythonhosted.org/packages/d2/83/86417974039e7554c9e1e55c852a7e9c2a1390d64675eb85d70e5fa7eb37/mapbox_earcut-2.0.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:4a6945b23f859bef11ce3194303d17bd371c86b637e7029f81b1feaff3db3758", size = 157548, upload-time = "2025-11-16T18:40:27.202Z" }, + { url = "https://files.pythonhosted.org/packages/aa/4c/c82a292bb21e5c651d81334123db2d654c5c9d19b2197080d3429dc1e49a/mapbox_earcut-2.0.0-cp311-cp311-win32.whl", hash = "sha256:8e119524c29406afb5eaa15e933f297d35679293a3ca62ced22f97a14c484cb5", size = 51424, upload-time = "2025-11-16T18:40:28.415Z" }, + { url = "https://files.pythonhosted.org/packages/30/57/6c39d7db81f72a3e4814ef152c8fb8dfe275dc4b03c9bfa073d251e3755f/mapbox_earcut-2.0.0-cp311-cp311-win_amd64.whl", hash = "sha256:378bbbb3304e446023752db8f44ecd6e7ef965bcbda36541d2ae64442ba94254", size = 56662, upload-time = "2025-11-16T18:40:29.863Z" }, + { url = "https://files.pythonhosted.org/packages/f4/d6/a1ef6e196b3d6968bf6546d4f7e54c559f9cff8991fdb880df0ba1618f52/mapbox_earcut-2.0.0-cp311-cp311-win_arm64.whl", hash = "sha256:6d249a431abd6bbff36f1fd0493247a86de962244cc4081b4d5050b02ed48fb1", size = 50505, upload-time = "2025-11-16T18:40:30.992Z" }, + { url = "https://files.pythonhosted.org/packages/8d/93/846804029d955c3c841d8efff77c2b0e8d9aab057d3a077dc8e3f88b5ea4/mapbox_earcut-2.0.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:db55ce18e698bc9d90914ee7d4f8c3e4d23827456ece7c5d7a1ec91e90c7122b", size = 55623, upload-time = "2025-11-16T18:40:32.113Z" }, + { url = "https://files.pythonhosted.org/packages/d3/f6/cc9ece104bc3876b350dba6fef7f34fb7b20ecc028d2cdbdbecb436b1ed1/mapbox_earcut-2.0.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:01dd6099d16123baf582a11b2bd1d59ce848498cf0cdca3812fd1f8b20ff33b7", size = 52028, upload-time = "2025-11-16T18:40:33.516Z" }, + { url = "https://files.pythonhosted.org/packages/88/6e/230da4aabcc56c99e9bddb4c43ce7d4ba3609c0caf2d316fb26535d7c60c/mapbox_earcut-2.0.0-cp312-cp312-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:2d5a098aae26a52282bc981a38e7bf6b889d2ea7442f2cd1903d2ba842f4ff07", size = 56351, upload-time = "2025-11-16T18:40:35.217Z" }, + { url = "https://files.pythonhosted.org/packages/1a/f7/5cdd3752526e91d91336c7263af7767b291d21e63c89d7190a60051f0f87/mapbox_earcut-2.0.0-cp312-cp312-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:de35f241d0b9110ad9260f295acedd9d7cc0d7acfe30d36b1b3ee8419c2caba1", size = 59209, upload-time = "2025-11-16T18:40:36.634Z" }, + { url = "https://files.pythonhosted.org/packages/7b/a2/b7781416cb93b37b95d0444e03f87184de8815e57ff202ce4105fa921325/mapbox_earcut-2.0.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:6cb63ab85e2e430c350f93e75c13f8b91cb8c8a045f3cd714c390b69a720368a", size = 152316, upload-time = "2025-11-16T18:40:38.147Z" }, + { url = "https://files.pythonhosted.org/packages/c1/74/396338e3d345e4e36fb23a0380921098b6a95ce7fb19c4777f4185a5974e/mapbox_earcut-2.0.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:fb3c9f069fc3795306db87f8139f70c4f047532f897a3de05f54dc1faebc97f6", size = 157268, upload-time = "2025-11-16T18:40:39.753Z" }, + { url = "https://files.pythonhosted.org/packages/56/2c/66fd137ea86c508f6cd7247f7f6e2d1dabffc9f0e9ccf14c71406b197af1/mapbox_earcut-2.0.0-cp312-cp312-win32.whl", hash = "sha256:eb290e6676217707ed238dd55e07b0a8ca3ab928f6a27c4afefb2ff3af08d7cb", size = 51226, upload-time = "2025-11-16T18:40:41.018Z" }, + { url = "https://files.pythonhosted.org/packages/b8/84/7b78e37b0c2109243c0dad7d9ba9774b02fcee228bf61cf727a5aa1702e2/mapbox_earcut-2.0.0-cp312-cp312-win_amd64.whl", hash = "sha256:5ef5b3319a43375272ad2cad9333ed16e569b5102e32a4241451358897e6f6ee", size = 56417, upload-time = "2025-11-16T18:40:42.173Z" }, + { url = "https://files.pythonhosted.org/packages/75/7f/cd7195aa27c1c8f2b9d38025a5a8663f32cd01c07b648a54b1308ab26c15/mapbox_earcut-2.0.0-cp312-cp312-win_arm64.whl", hash = "sha256:a4a3706feb5cc8c782d8f68bb0110c8d551304043f680a87a54b0651a2c208c3", size = 50111, upload-time = "2025-11-16T18:40:43.334Z" }, + { url = "https://files.pythonhosted.org/packages/8b/7c/c5dd5b255b9828ba5df729e62fdd470a322c938f07ef392ca03c0592bb3a/mapbox_earcut-2.0.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:582329a81bd36cf0f82e443c395bcb8cfdb10caddafec76acaebac7c20bf1c31", size = 55619, upload-time = "2025-11-16T18:40:44.44Z" }, + { url = "https://files.pythonhosted.org/packages/1a/3f/03f23eac9831e7d0d8da3d6993695a9a3724659c94e9997f6b7aaccc199d/mapbox_earcut-2.0.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:d2ac5f610b3e44a3a0c4df06b5552d503b4f1c2c409eeca20dbe05112bd60955", size = 52023, upload-time = "2025-11-16T18:40:45.857Z" }, + { url = "https://files.pythonhosted.org/packages/39/f3/a92ccee494b3e437e4bd81ecd358e39d231dc90af010d6c43930506c10ad/mapbox_earcut-2.0.0-cp313-cp313-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:58cc88513b87734b243d86f0d3fb87e96e0a78d9abd8fd615c55f766dd63f949", size = 56357, upload-time = "2025-11-16T18:40:47.27Z" }, + { url = "https://files.pythonhosted.org/packages/03/30/e54ececd0403a5495c340b693075abec92a6d17dc44283b6cb059534f7ed/mapbox_earcut-2.0.0-cp313-cp313-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:40218d887798451932f3c335992834aa807c35cd497c6e0733470fdbd77f9521", size = 59215, upload-time = "2025-11-16T18:40:48.682Z" }, + { url = "https://files.pythonhosted.org/packages/6e/e1/8fbff13a074c1fbf702b30ce7ec4d878bc664d659c1c2b1697831f4ea3a8/mapbox_earcut-2.0.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:39fa5cfa0e855b028ec9b0200c88ebfa252448f343ce2f67b6fc07fe1f22a3ae", size = 152304, upload-time = "2025-11-16T18:40:49.85Z" }, + { url = "https://files.pythonhosted.org/packages/b9/d5/c757030b3cb3a9f2278ded6f7312d2b9d3761db6f3da8d395f7f7303dd66/mapbox_earcut-2.0.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:476b558473b8a43f238d46e819bc0f830c427842ec5feb19e23b4dcac8ad2455", size = 157270, upload-time = "2025-11-16T18:40:51.093Z" }, + { url = "https://files.pythonhosted.org/packages/96/63/589c6decb1f032d8811f1066da552f0a718830f592e6d6539fa4c3c766b8/mapbox_earcut-2.0.0-cp313-cp313-win32.whl", hash = "sha256:8c2d125c182acbc490b39503c0dec4f937bae180d0849a26bcea0ee4a76024bd", size = 51207, upload-time = "2025-11-16T18:40:52.285Z" }, + { url = "https://files.pythonhosted.org/packages/76/75/a79a6020c46d4f07731e88ec5cc9324f6b43343aba835def1dc0bf59fecf/mapbox_earcut-2.0.0-cp313-cp313-win_amd64.whl", hash = "sha256:e049e6a37c228d7a9cb2f54ae405aa21d35c5175d849530fb32064ddb38ad5ab", size = 56416, upload-time = "2025-11-16T18:40:53.474Z" }, + { url = "https://files.pythonhosted.org/packages/ce/5f/83e878c2b3e9e6db1f60b598a2cc5ed4c2b5bc8d281575c964869414a159/mapbox_earcut-2.0.0-cp313-cp313-win_arm64.whl", hash = "sha256:8a833d73d63d4b6291bbd8b4d2f551e87f663282cdc547ecbbd9b423849ee996", size = 50103, upload-time = "2025-11-16T18:40:54.954Z" }, + { url = "https://files.pythonhosted.org/packages/96/fc/f1b74324c83f510213ff91eb8b1d2697ad5a12418c5fba966e80f1104a5f/mapbox_earcut-2.0.0-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:ad1dc141797037b7d4c9d8d2e52b9665b36294913a8ec31008b282d1a95b9bdc", size = 55728, upload-time = "2025-11-16T18:40:56.098Z" }, + { url = "https://files.pythonhosted.org/packages/7b/59/053c04e29c4bd22157d3b6255f1e5c19c46cb7a594c4314298bdcbca723f/mapbox_earcut-2.0.0-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:0f0f5c6f5ed8ffdce8efe6a003ba598089d0ee07eabd41868db183be50484f9f", size = 52063, upload-time = "2025-11-16T18:40:57.227Z" }, + { url = "https://files.pythonhosted.org/packages/a6/77/acc2d553c3bb8c769535a280545bb7d9608141e90511a2e6215a54611776/mapbox_earcut-2.0.0-cp314-cp314-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:82cd92775f37fd1e4b8464c5e74a00e87130eecc55ee3df2492b8ca2bdf6ef3e", size = 56522, upload-time = "2025-11-16T18:40:58.349Z" }, + { url = "https://files.pythonhosted.org/packages/1a/f5/627dd6defd3c1a2b3069e9e27482aa04d268c841735e576c1e22848a34f6/mapbox_earcut-2.0.0-cp314-cp314-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:626ffc1310e0cc8910283e4ac3139e5fb0458f18f2c4874162f66159951933ff", size = 59204, upload-time = "2025-11-16T18:41:00.095Z" }, + { url = "https://files.pythonhosted.org/packages/4a/3e/819185542ab095ba1244ad65ececb3edcde6fd0111248a0f9318d695bfcf/mapbox_earcut-2.0.0-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:ea951d764a356cad95b23fef950d8aa3b44b933795ad09d977fea7d4dbe377c3", size = 152550, upload-time = "2025-11-16T18:41:01.233Z" }, + { url = "https://files.pythonhosted.org/packages/a9/ad/85e0f815e4774b90ad6761bce55c80d13ee21b2a24014b0be0d5010b0049/mapbox_earcut-2.0.0-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:df1f217624abb5e02ecabcbd84369de970b8d8bc1e4e7c164c1cfcaddad76ca3", size = 157322, upload-time = "2025-11-16T18:41:02.866Z" }, + { url = "https://files.pythonhosted.org/packages/27/4c/0f56369e7a000d2f3177d17baf34263559b206ae524fcd0c4c5d1d960dab/mapbox_earcut-2.0.0-cp314-cp314-win32.whl", hash = "sha256:6fa61307d38b50fc9bd5449c00dbae46d270a32b372c6fc3b8af4b85c85746e4", size = 52916, upload-time = "2025-11-16T18:41:04.122Z" }, + { url = "https://files.pythonhosted.org/packages/c2/9d/8c557dd9b3d9fe2344f5bd5ff3bb0b2a42ed6addb7e43ca4358051743b04/mapbox_earcut-2.0.0-cp314-cp314-win_amd64.whl", hash = "sha256:0da20ed3c81b240450118773bcedfac34e70a56998f66147222c46f4356fff67", size = 57713, upload-time = "2025-11-16T18:41:05.204Z" }, + { url = "https://files.pythonhosted.org/packages/3b/ec/678c5553938d3a29d02dd41dd898672267f054afc4e2821958dee6ec86ce/mapbox_earcut-2.0.0-cp314-cp314-win_arm64.whl", hash = "sha256:847e74bd5878e4c64793dc100f9288f5443f87c55c3fe391fd90509029136ff6", size = 51872, upload-time = "2025-11-16T18:41:06.323Z" }, + { url = "https://files.pythonhosted.org/packages/18/37/94f2d973669cbfef811e536713fe56ec012ba74e5f8795a832337b1866a3/mapbox_earcut-2.0.0-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:ddc9e7175fc903185c64afbbf91febee56b50787dd0962fce2bfb4f20cf80d27", size = 56447, upload-time = "2025-11-16T18:41:07.443Z" }, + { url = "https://files.pythonhosted.org/packages/c9/1c/e0afcc82659cc1727a7e59c4f9e9880bbc3f048a4a5325772b44d4a91dfd/mapbox_earcut-2.0.0-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:6dc8a7568066af9a858018d6d92b7e77e164578f9fcd79093f1cbe4ec203461b", size = 53154, upload-time = "2025-11-16T18:41:08.618Z" }, + { url = "https://files.pythonhosted.org/packages/6c/2d/9845281c8c35da2bea733b8c2df5b9fe694e73e7b05fe8a1d4c3c439a1bc/mapbox_earcut-2.0.0-cp314-cp314t-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:6abc5340edd9b433ab2dab2ee033082a199d5c51cce445124626c0040ec0d81b", size = 56285, upload-time = "2025-11-16T18:41:09.728Z" }, + { url = "https://files.pythonhosted.org/packages/97/8e/eeea762a519490662b8f480e2b35bf03701b0bcc5a446b62a4c5a1500b06/mapbox_earcut-2.0.0-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:df7afdd8078a9aa28f469d9242531d304e09a4b14e514f048e021a949f3777b4", size = 58601, upload-time = "2025-11-16T18:41:10.872Z" }, + { url = "https://files.pythonhosted.org/packages/b9/67/932f80aa6af9bc1a317b6119052c74f327d81e00b457003a049e324b810c/mapbox_earcut-2.0.0-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:1a286f73e612a46cafd6d6c843365265090517af16823e2f37277c13cd8b6f09", size = 154924, upload-time = "2025-11-16T18:41:12.104Z" }, + { url = "https://files.pythonhosted.org/packages/87/38/5db4a91f9f90cbb447be61da5468a2955fad3a840ae4c7dbde789b09d45a/mapbox_earcut-2.0.0-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:8d081fe1d00dc553e3e68c02fc395324aad0d8ed955f3ff59289264c9b21ace4", size = 159194, upload-time = "2025-11-16T18:41:13.364Z" }, + { url = "https://files.pythonhosted.org/packages/6b/03/de3843b13fe854a010fb2f8b25551d4d5fe1c879ff2e7c8d7d8d7d735a8e/mapbox_earcut-2.0.0-cp314-cp314t-win32.whl", hash = "sha256:13049ca96431bbc7ef7fd7780dd1872209ca11a5c1977f7aa91a1b574a8af863", size = 54143, upload-time = "2025-11-16T18:41:14.564Z" }, + { url = "https://files.pythonhosted.org/packages/9a/89/fbdee5a56ba51df9be6098b5428636ad75aa994e98d8bec6113d5cba401e/mapbox_earcut-2.0.0-cp314-cp314t-win_amd64.whl", hash = "sha256:6ace78e4fdba3b8cbb7768d44d77a981698305862a07f94bbb6f5cc16659adb4", size = 60833, upload-time = "2025-11-16T18:41:15.694Z" }, +] + [[package]] name = "markdown" version = "3.10.2" @@ -5595,6 +5770,62 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/81/f2/08ace4142eb281c12701fc3b93a10795e4d4dc7f753911d836675050f886/msgpack-1.1.2-cp314-cp314t-win_arm64.whl", hash = "sha256:d99ef64f349d5ec3293688e91486c5fdb925ed03807f64d98d205d2713c60b46", size = 70868, upload-time = "2025-10-08T09:15:44.959Z" }, ] +[[package]] +name = "msgspec" +version = "0.21.1" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/e3/60/f79b9b013a16fa3a58350c9295ddc6789f2e335f36ea61ed10a21b215364/msgspec-0.21.1.tar.gz", hash = "sha256:2313508e394b0d208f8f56892ca9b2799e2561329de9763b19619595a6c0f72c", size = 319193, upload-time = "2026-04-12T21:44:50.394Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/96/38/d591d9f66d43d897ecbd249f2833665823d19c8b043f16619bc8343e23df/msgspec-0.21.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:72d9cd03241b8b2edb2e12dcc66c500fa480d8cbd71a8bac105809d468882064", size = 195172, upload-time = "2026-04-12T21:43:45.062Z" }, + { url = "https://files.pythonhosted.org/packages/69/1a/6899188b5982ec1324e0c629b7801eed2db987f6634fab58abd9fc82d317/msgspec-0.21.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:ed2ab278200e743a1d2610a4e0c8fc74f6cecb8548544cdec43f927bd9265238", size = 188316, upload-time = "2026-04-12T21:43:46.641Z" }, + { url = "https://files.pythonhosted.org/packages/9e/95/7e591b4fa11fdbbf9891164473c23420a8c781ef553295abe416bf335f42/msgspec-0.21.1-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:dd677e3001fdfed9186de72eab434da2976303cd5eb9550921d3d0c3e3e168ce", size = 216565, upload-time = "2026-04-12T21:43:48.081Z" }, + { url = "https://files.pythonhosted.org/packages/19/86/714feeaf3b84cf2027235681725593840153dedd2868578f9f2715e296bb/msgspec-0.21.1-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:f667b90b37fad734a91671abd68e0d7f4d066862771b87e91c53996dcb7a9027", size = 222689, upload-time = "2026-04-12T21:43:49.385Z" }, + { url = "https://files.pythonhosted.org/packages/7d/b9/4384243e814f2579e5205e17d170b9c1a30121afd1393298d904817a7fa7/msgspec-0.21.1-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:49880fd20fdbcfe1b793f07dd83f12572bab679c9800352c8b2240289aa46a06", size = 222343, upload-time = "2026-04-12T21:43:50.612Z" }, + { url = "https://files.pythonhosted.org/packages/04/01/4b227d9c4057346271043632bad41979cf8c3dca372e41bb1f7d546395b2/msgspec-0.21.1-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:ae0162e22849a5e91eaad907766525107523b0daea3df267a9fcb5ba4e0936ae", size = 225607, upload-time = "2026-04-12T21:43:52.129Z" }, + { url = "https://files.pythonhosted.org/packages/c1/ce/27021d1c3e5da837743092a7b7a5e8818397e1f4c05ee8b068bd7d1fd78a/msgspec-0.21.1-cp310-cp310-win_amd64.whl", hash = "sha256:f041a2279f31e3a53319005e4d60ba77c085cfcbe394cdc7ce803c2d01fe9449", size = 188392, upload-time = "2026-04-12T21:43:53.384Z" }, + { url = "https://files.pythonhosted.org/packages/80/2b/daf7a8d6d7cf00e0dcd0439178b284ade701234abdcadf3385601da04fbd/msgspec-0.21.1-cp310-cp310-win_arm64.whl", hash = "sha256:1bf17cbd7b28a5dffc7e764c654eed8ccde5e0f1de7970628608304640d4ce4e", size = 174191, upload-time = "2026-04-12T21:43:54.6Z" }, + { url = "https://files.pythonhosted.org/packages/ba/7f/bbc4e74cd33d316b75541149e4d35b163b63bce066530ae185a2ec3b5bfc/msgspec-0.21.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:b504b6e7f7a22a24b27232b73034421692147865162daaec9f3bf62439007c87", size = 193131, upload-time = "2026-04-12T21:43:56.094Z" }, + { url = "https://files.pythonhosted.org/packages/c1/60/504886af1aaf854112663b842d5eea9a15d9588f9bf7d0d2df736424b84d/msgspec-0.21.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:4692b7c1609155708c4418f88e92f63c13fdf08aa095c84bae82bad75b53389b", size = 186597, upload-time = "2026-04-12T21:43:57.242Z" }, + { url = "https://files.pythonhosted.org/packages/fa/54/d24ddeaa65b5278c9e67f48ce3c17a9831e8f3722f3c8322ee120aca22ef/msgspec-0.21.1-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:d3124010b3815451494c85ff345e693cb9fe5889cfcbbef39ed8622e0e72319c", size = 215158, upload-time = "2026-04-12T21:43:58.442Z" }, + { url = "https://files.pythonhosted.org/packages/9f/75/bb79c8b89a93ae23cd33c0d802373f16feaf9633f05d8af77091350dda0a/msgspec-0.21.1-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6badc03b9725352219cca017bfe71c61f2fbd0fb5982b410ac17c97c213deb30", size = 219856, upload-time = "2026-04-12T21:44:00.015Z" }, + { url = "https://files.pythonhosted.org/packages/b4/9c/c5ca26b46f0ebbd3a6683695ef89396712cb9e4199fd1f0bc1dd968216b1/msgspec-0.21.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:5d2d4116ebe3035a78d9ec76e99a9d64e5fa6d44fe61a9c5de7fd1acf54bcc69", size = 220314, upload-time = "2026-04-12T21:44:01.548Z" }, + { url = "https://files.pythonhosted.org/packages/c8/31/645a351c4285dce40ed6755c3dcc0aa648e26dacb20a98018fe2cce5e87b/msgspec-0.21.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:0d1009f6715f5bff3b54d4ff5c7428ad96197e0534e1645b8e9b955890c84664", size = 223215, upload-time = "2026-04-12T21:44:02.884Z" }, + { url = "https://files.pythonhosted.org/packages/09/af/8bf15736a6dd3cb4f90c5467f6dc39197d2daaf10754490cdc0aa17b7312/msgspec-0.21.1-cp311-cp311-win_amd64.whl", hash = "sha256:c6faffe5bb644ec884052679af4dfd776d4b5ca90e4a7ec7e7e319e4e6b93a6e", size = 188554, upload-time = "2026-04-12T21:44:04.151Z" }, + { url = "https://files.pythonhosted.org/packages/ef/29/cc7db3a165b62d16e64a83f82eccb79655055cb5bc1f60459a6f9d7c82f2/msgspec-0.21.1-cp311-cp311-win_arm64.whl", hash = "sha256:ee9e3f11fa94603f7d673bf795cfa31b549c4a2c723bc39b45beb1e7f5a3fb99", size = 174517, upload-time = "2026-04-12T21:44:05.66Z" }, + { url = "https://files.pythonhosted.org/packages/6e/cf/317224852c00248c620a9bcf4b26e2e4ab8afd752f18d2a6ef73ebd423b6/msgspec-0.21.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:d4248cf0b6129b7d230eacd493c17cc2d4f3989f3bb7f633a928a85b7dcfa251", size = 196188, upload-time = "2026-04-12T21:44:07.181Z" }, + { url = "https://files.pythonhosted.org/packages/6d/81/074612945c0666078f7366f40000013de9f6ba687491d450df699bceebc9/msgspec-0.21.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:5102c7e9b3acff82178449b85006d96310e690291bb1ea0142f1b24bcb8aabcb", size = 188473, upload-time = "2026-04-12T21:44:08.736Z" }, + { url = "https://files.pythonhosted.org/packages/8a/37/655101799590bcc5fddb2bd3fe0e6194e816c2d1da7c361725f5eb89a910/msgspec-0.21.1-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:846758412e9518252b2ac9bffd6f0e54d9ff614f5f9488df7749f81ff5c80920", size = 218871, upload-time = "2026-04-12T21:44:09.917Z" }, + { url = "https://files.pythonhosted.org/packages/b5/d1/d4cd9fe89c7d400d7a18f86ccc94daa3f0927f53558846fcb60791dce5d6/msgspec-0.21.1-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:21995e74b5c598c2e004110ad66ec7f1b8c20bf2bcf3b2de8fd9a3094422d3ff", size = 225025, upload-time = "2026-04-12T21:44:11.191Z" }, + { url = "https://files.pythonhosted.org/packages/24/bf/e20549e602b9edccadeeff98760345a416f9cce846a657e8b18e3396b212/msgspec-0.21.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:6129f0cca52992e898fd5344187f7c8127b63d810b2fd73e36fca73b4c6475ee", size = 222672, upload-time = "2026-04-12T21:44:12.481Z" }, + { url = "https://files.pythonhosted.org/packages/b4/68/04d7a8f0f786545cf9b8c280c57aa6befb5977af6e884b8b54191cbe44b3/msgspec-0.21.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:ef3ec2296248d1f8b9231acb051b6d471dfde8f21819e86c9adaaa9f42918521", size = 227303, upload-time = "2026-04-12T21:44:13.709Z" }, + { url = "https://files.pythonhosted.org/packages/cc/4d/619866af2840875be408047bf9e70ceafbae6ab50660de7134ed1b25eb86/msgspec-0.21.1-cp312-cp312-win_amd64.whl", hash = "sha256:d4ab834a054c6f0cbeef6df9e7e1b33d5f1bc7b86dea1d2fd7cad003873e783d", size = 190017, upload-time = "2026-04-12T21:44:14.977Z" }, + { url = "https://files.pythonhosted.org/packages/5e/2e/a8f9eca8fd00e097d7a9e99ba8a4685db994494448e3d4f0b7f6e9a3c0f7/msgspec-0.21.1-cp312-cp312-win_arm64.whl", hash = "sha256:628aaa35c74950a8c59da330d7e98917e1c7188f983745782027748ee4ca573e", size = 175345, upload-time = "2026-04-12T21:44:16.431Z" }, + { url = "https://files.pythonhosted.org/packages/7e/74/f11ede02839b19ff459f88e3145df5d711626ca84da4e23520cebf819367/msgspec-0.21.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:764173717a01743f007e9f74520ed281f24672c604514f7d76c1c3a10e8edb66", size = 196176, upload-time = "2026-04-12T21:44:17.613Z" }, + { url = "https://files.pythonhosted.org/packages/bb/40/4476c1bd341418a046c4955aff632ec769315d1e3cb94e6acf86d461f9ed/msgspec-0.21.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:344c7cd0eaed1fb81d7959f99100ef71ec9b536881a376f11b9a6c4803365697", size = 188524, upload-time = "2026-04-12T21:44:18.815Z" }, + { url = "https://files.pythonhosted.org/packages/ca/d9/9e9d7d7e5061b47540d03d640fab9b3965ba7ae49c1b2154861c8f007518/msgspec-0.21.1-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:48943e278b3854c2f89f955ddc6f9f430d3f0784b16e47d10604ee0463cd21f5", size = 218880, upload-time = "2026-04-12T21:44:20.028Z" }, + { url = "https://files.pythonhosted.org/packages/74/66/2bb344f34abb4b57e60c7c9c761994e0417b9718ec1460bf00c296f2a7ea/msgspec-0.21.1-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a9aa659ebb0101b1cbc31461212b87e341d961f0ab0772aaf068a99e001ec4aa", size = 225050, upload-time = "2026-04-12T21:44:21.577Z" }, + { url = "https://files.pythonhosted.org/packages/1a/84/7c1e412f76092277bf760cef12b7979d03314d259ab5b5cafde5d0c1722d/msgspec-0.21.1-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:f7b27d1a8ead2b6f5b0c4f2d07b8be1ccfcc041c8a0e704781edebe3ae13c484", size = 222713, upload-time = "2026-04-12T21:44:22.83Z" }, + { url = "https://files.pythonhosted.org/packages/4e/27/0bba04b2b4ef05f3d068429410bc71d2cea925f1596a8f41152cccd5edb8/msgspec-0.21.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:38fe93e86b61328fe544cb7fd871fad5a27c8734bfda90f65e5dbe288ae50f61", size = 227259, upload-time = "2026-04-12T21:44:24.11Z" }, + { url = "https://files.pythonhosted.org/packages/b0/2d/09574b0eea02fed2c2c1383dbaae2c7f79dc16dcd6487a886000afb5d7c4/msgspec-0.21.1-cp313-cp313-win_amd64.whl", hash = "sha256:8bc666331c35fcce05a7cd2d6221adbe0f6058f8e750711413d22793c080ac6a", size = 189857, upload-time = "2026-04-12T21:44:25.359Z" }, + { url = "https://files.pythonhosted.org/packages/46/34/105b1576ad182879914f0c821f17ee1d13abb165cb060448f96fe2aff078/msgspec-0.21.1-cp313-cp313-win_arm64.whl", hash = "sha256:42bb1241e0750c1a4346f2aa84db26c5ffd99a4eb3a954927d9f149ff2f42898", size = 175403, upload-time = "2026-04-12T21:44:26.608Z" }, + { url = "https://files.pythonhosted.org/packages/5a/ad/86954e987d1d6a5c579e2c2e7832b65e0fff194179fdac4f581536086024/msgspec-0.21.1-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:fab48eb45fdbfbdb2c0edfec00ffc53b6b6085beefc6b50b61e01659f9f8757f", size = 196261, upload-time = "2026-04-12T21:44:27.807Z" }, + { url = "https://files.pythonhosted.org/packages/d1/a1/c5e46c3e42b866199365e35d11dddfd1fbd8bba4fdb3c52f965b1607ce94/msgspec-0.21.1-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:3cb779ea0c35bc807ff941d415875c1f69ca0be91a2e907ab99a171811d86a9a", size = 188729, upload-time = "2026-04-12T21:44:28.99Z" }, + { url = "https://files.pythonhosted.org/packages/85/7d/1e29a319d678d6cb962ae5bdf32a6858ebdf38f73bc654c0e9c742a0c2c8/msgspec-0.21.1-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:68604db36b3b4dd9bf160e436e12798a4738848144cea1aca1cb984011eb160f", size = 219866, upload-time = "2026-04-12T21:44:31.104Z" }, + { url = "https://files.pythonhosted.org/packages/25/1f/cca084ca2572810fff12ea9dbdcbe39eac048f40daf4a9077b49fcbe8cee/msgspec-0.21.1-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:3d6b9dc50948eaf65df54d2fd0ff66e6d8c32f116037209ee861810eb9b676cb", size = 224993, upload-time = "2026-04-12T21:44:32.649Z" }, + { url = "https://files.pythonhosted.org/packages/71/94/d2120fc9d419a89a3a7c13e5b7078798c4b392a96a02a6e2b3ce43a8766c/msgspec-0.21.1-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:52c5e21930942302394429c5a582ce7e6b62c7f983b3760834c2ce107e0dd6df", size = 223535, upload-time = "2026-04-12T21:44:33.839Z" }, + { url = "https://files.pythonhosted.org/packages/75/17/42418b66a3ad972a89bab73dd78b79cc6282bb488a25e73c853cee7443b9/msgspec-0.21.1-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:abbb39d65681fa24ed394e01af3d59d869068324f900c61d06062b7fb9980f2f", size = 227222, upload-time = "2026-04-12T21:44:35.093Z" }, + { url = "https://files.pythonhosted.org/packages/c4/33/265c894268cca88ff67b144ca2b4c522fc8b9a6f1966a3640c70516e78e1/msgspec-0.21.1-cp314-cp314-win_amd64.whl", hash = "sha256:5666b1b560b97b6ec2eb3fca8a502298ebac56e13bbca1f88523538ce83d01ea", size = 193810, upload-time = "2026-04-12T21:44:36.612Z" }, + { url = "https://files.pythonhosted.org/packages/3b/8f/a6d35f25bf1fc63c492fdd88fdce01ba0875ead48c2b91f90f33653b4131/msgspec-0.21.1-cp314-cp314-win_arm64.whl", hash = "sha256:d8b8578e4c83b14ceea4cef0d0b747e31d9330fe4b03b2b2ad4063866a178f93", size = 179125, upload-time = "2026-04-12T21:44:38.198Z" }, + { url = "https://files.pythonhosted.org/packages/c6/39/74839641e64b99d87da55af0fc472854d42b46e2183b9e2a67fe1bb2a512/msgspec-0.21.1-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:15f523d51c00ebad412213bfe9f06f0a50ec2b93e0c19e824a2d267cabb48ea2", size = 200171, upload-time = "2026-04-12T21:44:39.414Z" }, + { url = "https://files.pythonhosted.org/packages/70/9b/ce0cca6d2d87fcd4b6ff97600790494e64f26a2c55d61507cd2755c16193/msgspec-0.21.1-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:4e47390360583ba3d5c6cb44cf0a9f61b0a06a899d3c2c00627cedebb2e2884b", size = 192879, upload-time = "2026-04-12T21:44:40.882Z" }, + { url = "https://files.pythonhosted.org/packages/a7/08/673a7bb05e5702dc787ddd3011195b509f9867927970da59052211929987/msgspec-0.21.1-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f60800e6299b798142dc40b0644da77ceac5ea0568be58228417eae14135c847", size = 226281, upload-time = "2026-04-12T21:44:42.181Z" }, + { url = "https://files.pythonhosted.org/packages/7d/45/86508cf57283e9070b3c447e3ab25b792a7a0855a3ea4e0c6d111ac34c97/msgspec-0.21.1-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:5f8e9dfcd98419cf7568808470c4317a3fb30bef0e3715b568730a2b272a20d7", size = 229863, upload-time = "2026-04-12T21:44:43.442Z" }, + { url = "https://files.pythonhosted.org/packages/2c/62/e7c9367cd08d590559faacd711edbae36840342843e669440363f33c7d36/msgspec-0.21.1-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:92d89dfad13bd1ea640dc3e37e724ed380da1030b272bdf5ecafb983c3ad7c75", size = 230445, upload-time = "2026-04-12T21:44:44.806Z" }, + { url = "https://files.pythonhosted.org/packages/42/b4/c0f54632103846b658a10930025f4de41c8724b5e4805a5f3b395586cb7e/msgspec-0.21.1-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:0d03867786e5d7ba25d666df4b11320c27170f4aeafcb8e3a8b0a50a4fb742ca", size = 231822, upload-time = "2026-04-12T21:44:46.343Z" }, + { url = "https://files.pythonhosted.org/packages/ea/1d/0d85cc79d0ccf5508e9c846cc66552a6a16bf92abd1dbd8362617f7b35cd/msgspec-0.21.1-cp314-cp314t-win_amd64.whl", hash = "sha256:740fbf1c9d59992ca3537d6fbe9ebbf9eaf726a65fbf31448e0ecbc710697a63", size = 206650, upload-time = "2026-04-12T21:44:47.601Z" }, + { url = "https://files.pythonhosted.org/packages/90/91/56c5d560f20e6c20e9e4f55bd0e458f7f162aa689ee350346c04c48eac0b/msgspec-0.21.1-cp314-cp314t-win_arm64.whl", hash = "sha256:0d2cc73df6058d811a126ac3a8ad63a4dfa210c82f9cf5a004802eaf4712de90", size = 183149, upload-time = "2026-04-12T21:44:48.833Z" }, +] + [[package]] name = "mujoco" version = "3.5.0" @@ -7417,6 +7648,19 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/79/ad/45312df6b63ba64ea35b8d8f5f0c577aac16e6b416eafe8e1cb34e03f9a7/plumbum-1.10.0-py3-none-any.whl", hash = "sha256:9583d737ac901c474d99d030e4d5eec4c4e6d2d7417b1cf49728cf3be34f6dc8", size = 127383, upload-time = "2025-10-31T05:02:47.002Z" }, ] +[[package]] +name = "plyfile" +version = "1.1.3" +source = { registry = "https://pypi.org/simple" } +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'" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/78/d8/f68ec9a54568236ba4c00fc0b002f74d2a559841c1fce86ab356599da032/plyfile-1.1.3.tar.gz", hash = "sha256:1c37720cb0470b762cec2dfef573ee7996a616c359c0ec34fdd766ace3ea0634", size = 36163, upload-time = "2025-10-22T01:58:40.06Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/22/22/1755bb4c7db15bb1ed63b4eb7a7fc133bf42a3f9cc806c0d5941e107ba90/plyfile-1.1.3-py3-none-any.whl", hash = "sha256:581302f07b1c298431dcaa9038bba2ae80f3f7868b29ccb826a07bc4488ff38a", size = 36455, upload-time = "2025-10-22T01:58:38.614Z" }, +] + [[package]] name = "polars" version = "1.38.1" @@ -8488,7 +8732,7 @@ wheels = [ [[package]] name = "pytest" -version = "9.0.3" +version = "8.3.5" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "colorama", marker = "sys_platform == 'win32'" }, @@ -8496,12 +8740,11 @@ dependencies = [ { name = "iniconfig" }, { name = "packaging" }, { name = "pluggy" }, - { name = "pygments" }, { name = "tomli", marker = "python_full_version < '3.11'" }, ] -sdist = { url = "https://files.pythonhosted.org/packages/7d/0d/549bd94f1a0a402dc8cf64563a117c0f3765662e2e668477624baeec44d5/pytest-9.0.3.tar.gz", hash = "sha256:b86ada508af81d19edeb213c681b1d48246c1a91d304c6c81a427674c17eb91c", size = 1572165, upload-time = "2026-04-07T17:16:18.027Z" } +sdist = { url = "https://files.pythonhosted.org/packages/ae/3c/c9d525a414d506893f0cd8a8d0de7706446213181570cdbd766691164e40/pytest-8.3.5.tar.gz", hash = "sha256:f4efe70cc14e511565ac476b57c279e12a855b11f48f212af1080ef2263d3845", size = 1450891, upload-time = "2025-03-02T12:54:54.503Z" } wheels = [ - { url = "https://files.pythonhosted.org/packages/d4/24/a372aaf5c9b7208e7112038812994107bc65a84cd00e0354a88c2c77a617/pytest-9.0.3-py3-none-any.whl", hash = "sha256:2c5efc453d45394fdd706ade797c0a81091eccd1d6e4bccfcd476e2b8e0ab5d9", size = 375249, upload-time = "2026-04-07T17:16:16.13Z" }, + { url = "https://files.pythonhosted.org/packages/30/3d/64ad57c803f1fa1e963a7946b6e0fea4a70df53c1a7fed304586539c2bac/pytest-8.3.5-py3-none-any.whl", hash = "sha256:c69214aa47deac29fad6c2a4f590b9c4a9fdb16a403176fe154b79c0b4d4d820", size = 343634, upload-time = "2025-03-02T12:54:52.069Z" }, ] [[package]] @@ -9325,6 +9568,22 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/3f/99/2e119d541d596daea39643eb9312b47c7847383951300f889166938035b1/rpyc-6.0.2-py3-none-any.whl", hash = "sha256:8072308ad30725bc281c42c011fc8c922be15f3eeda6eafb2917cafe1b6f00ec", size = 74768, upload-time = "2025-04-18T16:33:20.147Z" }, ] +[[package]] +name = "rtree" +version = "1.4.1" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/95/09/7302695875a019514de9a5dd17b8320e7a19d6e7bc8f85dcfb79a4ce2da3/rtree-1.4.1.tar.gz", hash = "sha256:c6b1b3550881e57ebe530cc6cffefc87cd9bf49c30b37b894065a9f810875e46", size = 52425, upload-time = "2025-08-13T19:32:01.413Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/04/d9/108cd989a4c0954e60b3cdc86fd2826407702b5375f6dfdab2802e5fed98/rtree-1.4.1-py3-none-macosx_10_9_x86_64.whl", hash = "sha256:d672184298527522d4914d8ae53bf76982b86ca420b0acde9298a7a87d81d4a4", size = 468484, upload-time = "2025-08-13T19:31:50.593Z" }, + { url = "https://files.pythonhosted.org/packages/f3/cf/2710b6fd6b07ea0aef317b29f335790ba6adf06a28ac236078ed9bd8a91d/rtree-1.4.1-py3-none-macosx_11_0_arm64.whl", hash = "sha256:a7e48d805e12011c2cf739a29d6a60ae852fb1de9fc84220bbcef67e6e595d7d", size = 436325, upload-time = "2025-08-13T19:31:52.367Z" }, + { url = "https://files.pythonhosted.org/packages/55/e1/4d075268a46e68db3cac51846eb6a3ab96ed481c585c5a1ad411b3c23aad/rtree-1.4.1-py3-none-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:efa8c4496e31e9ad58ff6c7df89abceac7022d906cb64a3e18e4fceae6b77f65", size = 459789, upload-time = "2025-08-13T19:31:53.926Z" }, + { url = "https://files.pythonhosted.org/packages/d1/75/e5d44be90525cd28503e7f836d077ae6663ec0687a13ba7810b4114b3668/rtree-1.4.1-py3-none-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:12de4578f1b3381a93a655846900be4e3d5f4cd5e306b8b00aa77c1121dc7e8c", size = 507644, upload-time = "2025-08-13T19:31:55.164Z" }, + { url = "https://files.pythonhosted.org/packages/fd/85/b8684f769a142163b52859a38a486493b05bafb4f2fb71d4f945de28ebf9/rtree-1.4.1-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:b558edda52eca3e6d1ee629042192c65e6b7f2c150d6d6cd207ce82f85be3967", size = 1454478, upload-time = "2025-08-13T19:31:56.808Z" }, + { url = "https://files.pythonhosted.org/packages/e9/a4/c2292b95246b9165cc43a0c3757e80995d58bc9b43da5cb47ad6e3535213/rtree-1.4.1-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:f155bc8d6bac9dcd383481dee8c130947a4866db1d16cb6dff442329a038a0dc", size = 1555140, upload-time = "2025-08-13T19:31:58.031Z" }, + { url = "https://files.pythonhosted.org/packages/74/25/5282c8270bfcd620d3e73beb35b40ac4ab00f0a898d98ebeb41ef0989ec8/rtree-1.4.1-py3-none-win_amd64.whl", hash = "sha256:efe125f416fd27150197ab8521158662943a40f87acab8028a1aac4ad667a489", size = 389358, upload-time = "2025-08-13T19:31:59.247Z" }, + { url = "https://files.pythonhosted.org/packages/3f/50/0a9e7e7afe7339bd5e36911f0ceb15fed51945836ed803ae5afd661057fd/rtree-1.4.1-py3-none-win_arm64.whl", hash = "sha256:3d46f55729b28138e897ffef32f7ce93ac335cb67f9120125ad3742a220800f0", size = 355253, upload-time = "2025-08-13T19:32:00.296Z" }, +] + [[package]] name = "ruff" version = "0.14.3" @@ -9770,6 +10029,74 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e1/e3/c164c88b2e5ce7b24d667b9bd83589cf4f3520d97cad01534cd3c4f55fdb/setuptools-81.0.0-py3-none-any.whl", hash = "sha256:fdd925d5c5d9f62e4b74b30d6dd7828ce236fd6ed998a08d81de62ce5a6310d6", size = 1062021, upload-time = "2026-02-06T21:10:37.175Z" }, ] +[[package]] +name = "shapely" +version = "2.1.2" +source = { registry = "https://pypi.org/simple" } +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'" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/4d/bc/0989043118a27cccb4e906a46b7565ce36ca7b57f5a18b78f4f1b0f72d9d/shapely-2.1.2.tar.gz", hash = "sha256:2ed4ecb28320a433db18a5bf029986aa8afcfd740745e78847e330d5d94922a9", size = 315489, upload-time = "2025-09-24T13:51:41.432Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/05/89/c3548aa9b9812a5d143986764dededfa48d817714e947398bdda87c77a72/shapely-2.1.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:7ae48c236c0324b4e139bea88a306a04ca630f49be66741b340729d380d8f52f", size = 1825959, upload-time = "2025-09-24T13:50:00.682Z" }, + { url = "https://files.pythonhosted.org/packages/ce/8a/7ebc947080442edd614ceebe0ce2cdbd00c25e832c240e1d1de61d0e6b38/shapely-2.1.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:eba6710407f1daa8e7602c347dfc94adc02205ec27ed956346190d66579eb9ea", size = 1629196, upload-time = "2025-09-24T13:50:03.447Z" }, + { url = "https://files.pythonhosted.org/packages/c8/86/c9c27881c20d00fc409e7e059de569d5ed0abfcec9c49548b124ebddea51/shapely-2.1.2-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:ef4a456cc8b7b3d50ccec29642aa4aeda959e9da2fe9540a92754770d5f0cf1f", size = 2951065, upload-time = "2025-09-24T13:50:05.266Z" }, + { url = "https://files.pythonhosted.org/packages/50/8a/0ab1f7433a2a85d9e9aea5b1fbb333f3b09b309e7817309250b4b7b2cc7a/shapely-2.1.2-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:e38a190442aacc67ff9f75ce60aec04893041f16f97d242209106d502486a142", size = 3058666, upload-time = "2025-09-24T13:50:06.872Z" }, + { url = "https://files.pythonhosted.org/packages/bb/c6/5a30ffac9c4f3ffd5b7113a7f5299ccec4713acd5ee44039778a7698224e/shapely-2.1.2-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:40d784101f5d06a1fd30b55fc11ea58a61be23f930d934d86f19a180909908a4", size = 3966905, upload-time = "2025-09-24T13:50:09.417Z" }, + { url = "https://files.pythonhosted.org/packages/9c/72/e92f3035ba43e53959007f928315a68fbcf2eeb4e5ededb6f0dc7ff1ecc3/shapely-2.1.2-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:f6f6cd5819c50d9bcf921882784586aab34a4bd53e7553e175dece6db513a6f0", size = 4129260, upload-time = "2025-09-24T13:50:11.183Z" }, + { url = "https://files.pythonhosted.org/packages/42/24/605901b73a3d9f65fa958e63c9211f4be23d584da8a1a7487382fac7fdc5/shapely-2.1.2-cp310-cp310-win32.whl", hash = "sha256:fe9627c39c59e553c90f5bc3128252cb85dc3b3be8189710666d2f8bc3a5503e", size = 1544301, upload-time = "2025-09-24T13:50:12.521Z" }, + { url = "https://files.pythonhosted.org/packages/e1/89/6db795b8dd3919851856bd2ddd13ce434a748072f6fdee42ff30cbd3afa3/shapely-2.1.2-cp310-cp310-win_amd64.whl", hash = "sha256:1d0bfb4b8f661b3b4ec3565fa36c340bfb1cda82087199711f86a88647d26b2f", size = 1722074, upload-time = "2025-09-24T13:50:13.909Z" }, + { url = "https://files.pythonhosted.org/packages/8f/8d/1ff672dea9ec6a7b5d422eb6d095ed886e2e523733329f75fdcb14ee1149/shapely-2.1.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:91121757b0a36c9aac3427a651a7e6567110a4a67c97edf04f8d55d4765f6618", size = 1820038, upload-time = "2025-09-24T13:50:15.628Z" }, + { url = "https://files.pythonhosted.org/packages/4f/ce/28fab8c772ce5db23a0d86bf0adaee0c4c79d5ad1db766055fa3dab442e2/shapely-2.1.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:16a9c722ba774cf50b5d4541242b4cce05aafd44a015290c82ba8a16931ff63d", size = 1626039, upload-time = "2025-09-24T13:50:16.881Z" }, + { url = "https://files.pythonhosted.org/packages/70/8b/868b7e3f4982f5006e9395c1e12343c66a8155c0374fdc07c0e6a1ab547d/shapely-2.1.2-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:cc4f7397459b12c0b196c9efe1f9d7e92463cbba142632b4cc6d8bbbbd3e2b09", size = 3001519, upload-time = "2025-09-24T13:50:18.606Z" }, + { url = "https://files.pythonhosted.org/packages/13/02/58b0b8d9c17c93ab6340edd8b7308c0c5a5b81f94ce65705819b7416dba5/shapely-2.1.2-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:136ab87b17e733e22f0961504d05e77e7be8c9b5a8184f685b4a91a84efe3c26", size = 3110842, upload-time = "2025-09-24T13:50:21.77Z" }, + { url = "https://files.pythonhosted.org/packages/af/61/8e389c97994d5f331dcffb25e2fa761aeedfb52b3ad9bcdd7b8671f4810a/shapely-2.1.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:16c5d0fc45d3aa0a69074979f4f1928ca2734fb2e0dde8af9611e134e46774e7", size = 4021316, upload-time = "2025-09-24T13:50:23.626Z" }, + { url = "https://files.pythonhosted.org/packages/d3/d4/9b2a9fe6039f9e42ccf2cb3e84f219fd8364b0c3b8e7bbc857b5fbe9c14c/shapely-2.1.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:6ddc759f72b5b2b0f54a7e7cde44acef680a55019eb52ac63a7af2cf17cb9cd2", size = 4178586, upload-time = "2025-09-24T13:50:25.443Z" }, + { url = "https://files.pythonhosted.org/packages/16/f6/9840f6963ed4decf76b08fd6d7fed14f8779fb7a62cb45c5617fa8ac6eab/shapely-2.1.2-cp311-cp311-win32.whl", hash = "sha256:2fa78b49485391224755a856ed3b3bd91c8455f6121fee0db0e71cefb07d0ef6", size = 1543961, upload-time = "2025-09-24T13:50:26.968Z" }, + { url = "https://files.pythonhosted.org/packages/38/1e/3f8ea46353c2a33c1669eb7327f9665103aa3a8dfe7f2e4ef714c210b2c2/shapely-2.1.2-cp311-cp311-win_amd64.whl", hash = "sha256:c64d5c97b2f47e3cd9b712eaced3b061f2b71234b3fc263e0fcf7d889c6559dc", size = 1722856, upload-time = "2025-09-24T13:50:28.497Z" }, + { url = "https://files.pythonhosted.org/packages/24/c0/f3b6453cf2dfa99adc0ba6675f9aaff9e526d2224cbd7ff9c1a879238693/shapely-2.1.2-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:fe2533caae6a91a543dec62e8360fe86ffcdc42a7c55f9dfd0128a977a896b94", size = 1833550, upload-time = "2025-09-24T13:50:30.019Z" }, + { url = "https://files.pythonhosted.org/packages/86/07/59dee0bc4b913b7ab59ab1086225baca5b8f19865e6101db9ebb7243e132/shapely-2.1.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:ba4d1333cc0bc94381d6d4308d2e4e008e0bd128bdcff5573199742ee3634359", size = 1643556, upload-time = "2025-09-24T13:50:32.291Z" }, + { url = "https://files.pythonhosted.org/packages/26/29/a5397e75b435b9895cd53e165083faed5d12fd9626eadec15a83a2411f0f/shapely-2.1.2-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:0bd308103340030feef6c111d3eb98d50dc13feea33affc8a6f9fa549e9458a3", size = 2988308, upload-time = "2025-09-24T13:50:33.862Z" }, + { url = "https://files.pythonhosted.org/packages/b9/37/e781683abac55dde9771e086b790e554811a71ed0b2b8a1e789b7430dd44/shapely-2.1.2-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:1e7d4d7ad262a48bb44277ca12c7c78cb1b0f56b32c10734ec9a1d30c0b0c54b", size = 3099844, upload-time = "2025-09-24T13:50:35.459Z" }, + { url = "https://files.pythonhosted.org/packages/d8/f3/9876b64d4a5a321b9dc482c92bb6f061f2fa42131cba643c699f39317cb9/shapely-2.1.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:e9eddfe513096a71896441a7c37db72da0687b34752c4e193577a145c71736fc", size = 3988842, upload-time = "2025-09-24T13:50:37.478Z" }, + { url = "https://files.pythonhosted.org/packages/d1/a0/704c7292f7014c7e74ec84eddb7b109e1fbae74a16deae9c1504b1d15565/shapely-2.1.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:980c777c612514c0cf99bc8a9de6d286f5e186dcaf9091252fcd444e5638193d", size = 4152714, upload-time = "2025-09-24T13:50:39.9Z" }, + { url = "https://files.pythonhosted.org/packages/53/46/319c9dc788884ad0785242543cdffac0e6530e4d0deb6c4862bc4143dcf3/shapely-2.1.2-cp312-cp312-win32.whl", hash = "sha256:9111274b88e4d7b54a95218e243282709b330ef52b7b86bc6aaf4f805306f454", size = 1542745, upload-time = "2025-09-24T13:50:41.414Z" }, + { url = "https://files.pythonhosted.org/packages/ec/bf/cb6c1c505cb31e818e900b9312d514f381fbfa5c4363edfce0fcc4f8c1a4/shapely-2.1.2-cp312-cp312-win_amd64.whl", hash = "sha256:743044b4cfb34f9a67205cee9279feaf60ba7d02e69febc2afc609047cb49179", size = 1722861, upload-time = "2025-09-24T13:50:43.35Z" }, + { url = "https://files.pythonhosted.org/packages/c3/90/98ef257c23c46425dc4d1d31005ad7c8d649fe423a38b917db02c30f1f5a/shapely-2.1.2-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:b510dda1a3672d6879beb319bc7c5fd302c6c354584690973c838f46ec3e0fa8", size = 1832644, upload-time = "2025-09-24T13:50:44.886Z" }, + { url = "https://files.pythonhosted.org/packages/6d/ab/0bee5a830d209adcd3a01f2d4b70e587cdd9fd7380d5198c064091005af8/shapely-2.1.2-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:8cff473e81017594d20ec55d86b54bc635544897e13a7cfc12e36909c5309a2a", size = 1642887, upload-time = "2025-09-24T13:50:46.735Z" }, + { url = "https://files.pythonhosted.org/packages/2d/5e/7d7f54ba960c13302584c73704d8c4d15404a51024631adb60b126a4ae88/shapely-2.1.2-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:fe7b77dc63d707c09726b7908f575fc04ff1d1ad0f3fb92aec212396bc6cfe5e", size = 2970931, upload-time = "2025-09-24T13:50:48.374Z" }, + { url = "https://files.pythonhosted.org/packages/f2/a2/83fc37e2a58090e3d2ff79175a95493c664bcd0b653dd75cb9134645a4e5/shapely-2.1.2-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:7ed1a5bbfb386ee8332713bf7508bc24e32d24b74fc9a7b9f8529a55db9f4ee6", size = 3082855, upload-time = "2025-09-24T13:50:50.037Z" }, + { url = "https://files.pythonhosted.org/packages/44/2b/578faf235a5b09f16b5f02833c53822294d7f21b242f8e2d0cf03fb64321/shapely-2.1.2-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:a84e0582858d841d54355246ddfcbd1fce3179f185da7470f41ce39d001ee1af", size = 3979960, upload-time = "2025-09-24T13:50:51.74Z" }, + { url = "https://files.pythonhosted.org/packages/4d/04/167f096386120f692cc4ca02f75a17b961858997a95e67a3cb6a7bbd6b53/shapely-2.1.2-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:dc3487447a43d42adcdf52d7ac73804f2312cbfa5d433a7d2c506dcab0033dfd", size = 4142851, upload-time = "2025-09-24T13:50:53.49Z" }, + { url = "https://files.pythonhosted.org/packages/48/74/fb402c5a6235d1c65a97348b48cdedb75fb19eca2b1d66d04969fc1c6091/shapely-2.1.2-cp313-cp313-win32.whl", hash = "sha256:9c3a3c648aedc9f99c09263b39f2d8252f199cb3ac154fadc173283d7d111350", size = 1541890, upload-time = "2025-09-24T13:50:55.337Z" }, + { url = "https://files.pythonhosted.org/packages/41/47/3647fe7ad990af60ad98b889657a976042c9988c2807cf322a9d6685f462/shapely-2.1.2-cp313-cp313-win_amd64.whl", hash = "sha256:ca2591bff6645c216695bdf1614fca9c82ea1144d4a7591a466fef64f28f0715", size = 1722151, upload-time = "2025-09-24T13:50:57.153Z" }, + { url = "https://files.pythonhosted.org/packages/3c/49/63953754faa51ffe7d8189bfbe9ca34def29f8c0e34c67cbe2a2795f269d/shapely-2.1.2-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:2d93d23bdd2ed9dc157b46bc2f19b7da143ca8714464249bef6771c679d5ff40", size = 1834130, upload-time = "2025-09-24T13:50:58.49Z" }, + { url = "https://files.pythonhosted.org/packages/7f/ee/dce001c1984052970ff60eb4727164892fb2d08052c575042a47f5a9e88f/shapely-2.1.2-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:01d0d304b25634d60bd7cf291828119ab55a3bab87dc4af1e44b07fb225f188b", size = 1642802, upload-time = "2025-09-24T13:50:59.871Z" }, + { url = "https://files.pythonhosted.org/packages/da/e7/fc4e9a19929522877fa602f705706b96e78376afb7fad09cad5b9af1553c/shapely-2.1.2-cp313-cp313t-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:8d8382dd120d64b03698b7298b89611a6ea6f55ada9d39942838b79c9bc89801", size = 3018460, upload-time = "2025-09-24T13:51:02.08Z" }, + { url = "https://files.pythonhosted.org/packages/a1/18/7519a25db21847b525696883ddc8e6a0ecaa36159ea88e0fef11466384d0/shapely-2.1.2-cp313-cp313t-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:19efa3611eef966e776183e338b2d7ea43569ae99ab34f8d17c2c054d3205cc0", size = 3095223, upload-time = "2025-09-24T13:51:04.472Z" }, + { url = "https://files.pythonhosted.org/packages/48/de/b59a620b1f3a129c3fecc2737104a0a7e04e79335bd3b0a1f1609744cf17/shapely-2.1.2-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:346ec0c1a0fcd32f57f00e4134d1200e14bf3f5ae12af87ba83ca275c502498c", size = 4030760, upload-time = "2025-09-24T13:51:06.455Z" }, + { url = "https://files.pythonhosted.org/packages/96/b3/c6655ee7232b417562bae192ae0d3ceaadb1cc0ffc2088a2ddf415456cc2/shapely-2.1.2-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:6305993a35989391bd3476ee538a5c9a845861462327efe00dd11a5c8c709a99", size = 4170078, upload-time = "2025-09-24T13:51:08.584Z" }, + { url = "https://files.pythonhosted.org/packages/a0/8e/605c76808d73503c9333af8f6cbe7e1354d2d238bda5f88eea36bfe0f42a/shapely-2.1.2-cp313-cp313t-win32.whl", hash = "sha256:c8876673449f3401f278c86eb33224c5764582f72b653a415d0e6672fde887bf", size = 1559178, upload-time = "2025-09-24T13:51:10.73Z" }, + { url = "https://files.pythonhosted.org/packages/36/f7/d317eb232352a1f1444d11002d477e54514a4a6045536d49d0c59783c0da/shapely-2.1.2-cp313-cp313t-win_amd64.whl", hash = "sha256:4a44bc62a10d84c11a7a3d7c1c4fe857f7477c3506e24c9062da0db0ae0c449c", size = 1739756, upload-time = "2025-09-24T13:51:12.105Z" }, + { url = "https://files.pythonhosted.org/packages/fc/c4/3ce4c2d9b6aabd27d26ec988f08cb877ba9e6e96086eff81bfea93e688c7/shapely-2.1.2-cp314-cp314-macosx_10_13_x86_64.whl", hash = "sha256:9a522f460d28e2bf4e12396240a5fc1518788b2fcd73535166d748399ef0c223", size = 1831290, upload-time = "2025-09-24T13:51:13.56Z" }, + { url = "https://files.pythonhosted.org/packages/17/b9/f6ab8918fc15429f79cb04afa9f9913546212d7fb5e5196132a2af46676b/shapely-2.1.2-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:1ff629e00818033b8d71139565527ced7d776c269a49bd78c9df84e8f852190c", size = 1641463, upload-time = "2025-09-24T13:51:14.972Z" }, + { url = "https://files.pythonhosted.org/packages/a5/57/91d59ae525ca641e7ac5551c04c9503aee6f29b92b392f31790fcb1a4358/shapely-2.1.2-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:f67b34271dedc3c653eba4e3d7111aa421d5be9b4c4c7d38d30907f796cb30df", size = 2970145, upload-time = "2025-09-24T13:51:16.961Z" }, + { url = "https://files.pythonhosted.org/packages/8a/cb/4948be52ee1da6927831ab59e10d4c29baa2a714f599f1f0d1bc747f5777/shapely-2.1.2-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:21952dc00df38a2c28375659b07a3979d22641aeb104751e769c3ee825aadecf", size = 3073806, upload-time = "2025-09-24T13:51:18.712Z" }, + { url = "https://files.pythonhosted.org/packages/03/83/f768a54af775eb41ef2e7bec8a0a0dbe7d2431c3e78c0a8bdba7ab17e446/shapely-2.1.2-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:1f2f33f486777456586948e333a56ae21f35ae273be99255a191f5c1fa302eb4", size = 3980803, upload-time = "2025-09-24T13:51:20.37Z" }, + { url = "https://files.pythonhosted.org/packages/9f/cb/559c7c195807c91c79d38a1f6901384a2878a76fbdf3f1048893a9b7534d/shapely-2.1.2-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:cf831a13e0d5a7eb519e96f58ec26e049b1fad411fc6fc23b162a7ce04d9cffc", size = 4133301, upload-time = "2025-09-24T13:51:21.887Z" }, + { url = "https://files.pythonhosted.org/packages/80/cd/60d5ae203241c53ef3abd2ef27c6800e21afd6c94e39db5315ea0cbafb4a/shapely-2.1.2-cp314-cp314-win32.whl", hash = "sha256:61edcd8d0d17dd99075d320a1dd39c0cb9616f7572f10ef91b4b5b00c4aeb566", size = 1583247, upload-time = "2025-09-24T13:51:23.401Z" }, + { url = "https://files.pythonhosted.org/packages/74/d4/135684f342e909330e50d31d441ace06bf83c7dc0777e11043f99167b123/shapely-2.1.2-cp314-cp314-win_amd64.whl", hash = "sha256:a444e7afccdb0999e203b976adb37ea633725333e5b119ad40b1ca291ecf311c", size = 1773019, upload-time = "2025-09-24T13:51:24.873Z" }, + { url = "https://files.pythonhosted.org/packages/a3/05/a44f3f9f695fa3ada22786dc9da33c933da1cbc4bfe876fe3a100bafe263/shapely-2.1.2-cp314-cp314t-macosx_10_13_x86_64.whl", hash = "sha256:5ebe3f84c6112ad3d4632b1fd2290665aa75d4cef5f6c5d77c4c95b324527c6a", size = 1834137, upload-time = "2025-09-24T13:51:26.665Z" }, + { url = "https://files.pythonhosted.org/packages/52/7e/4d57db45bf314573427b0a70dfca15d912d108e6023f623947fa69f39b72/shapely-2.1.2-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:5860eb9f00a1d49ebb14e881f5caf6c2cf472c7fd38bd7f253bbd34f934eb076", size = 1642884, upload-time = "2025-09-24T13:51:28.029Z" }, + { url = "https://files.pythonhosted.org/packages/5a/27/4e29c0a55d6d14ad7422bf86995d7ff3f54af0eba59617eb95caf84b9680/shapely-2.1.2-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:b705c99c76695702656327b819c9660768ec33f5ce01fa32b2af62b56ba400a1", size = 3018320, upload-time = "2025-09-24T13:51:29.903Z" }, + { url = "https://files.pythonhosted.org/packages/9f/bb/992e6a3c463f4d29d4cd6ab8963b75b1b1040199edbd72beada4af46bde5/shapely-2.1.2-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:a1fd0ea855b2cf7c9cddaf25543e914dd75af9de08785f20ca3085f2c9ca60b0", size = 3094931, upload-time = "2025-09-24T13:51:32.699Z" }, + { url = "https://files.pythonhosted.org/packages/9c/16/82e65e21070e473f0ed6451224ed9fa0be85033d17e0c6e7213a12f59d12/shapely-2.1.2-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:df90e2db118c3671a0754f38e36802db75fe0920d211a27481daf50a711fdf26", size = 4030406, upload-time = "2025-09-24T13:51:34.189Z" }, + { url = "https://files.pythonhosted.org/packages/7c/75/c24ed871c576d7e2b64b04b1fe3d075157f6eb54e59670d3f5ffb36e25c7/shapely-2.1.2-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:361b6d45030b4ac64ddd0a26046906c8202eb60d0f9f53085f5179f1d23021a0", size = 4169511, upload-time = "2025-09-24T13:51:36.297Z" }, + { url = "https://files.pythonhosted.org/packages/b1/f7/b3d1d6d18ebf55236eec1c681ce5e665742aab3c0b7b232720a7d43df7b6/shapely-2.1.2-cp314-cp314t-win32.whl", hash = "sha256:b54df60f1fbdecc8ebc2c5b11870461a6417b3d617f555e5033f1505d36e5735", size = 1602607, upload-time = "2025-09-24T13:51:37.757Z" }, + { url = "https://files.pythonhosted.org/packages/9a/f6/f09272a71976dfc138129b8faf435d064a811ae2f708cb147dccdf7aacdb/shapely-2.1.2-cp314-cp314t-win_amd64.whl", hash = "sha256:0036ac886e0923417932c2e6369b6c52e38e0ff5d9120b90eef5cd9a5fc5cae9", size = 1796682, upload-time = "2025-09-24T13:51:39.233Z" }, +] + [[package]] name = "shellingham" version = "1.5.4" @@ -9997,6 +10324,15 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/a8/45/a132b9074aa18e799b891b91ad72133c98d8042c70f6240e4c5f9dabee2f/structlog-25.5.0-py3-none-any.whl", hash = "sha256:a8453e9b9e636ec59bd9e79bbd4a72f025981b3ba0f5837aebf48f02f37a7f9f", size = 72510, upload-time = "2025-10-27T08:28:21.535Z" }, ] +[[package]] +name = "svg-path" +version = "7.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/66/b9/649abbe870842c185b12920e937e9b95d4c2b18de50af98d2c140df3e179/svg_path-7.0.tar.gz", hash = "sha256:9037486957cb1dcf4375ef42206499a47c111b8ffcbac6e3e55f9d079d875bb0", size = 23552, upload-time = "2025-07-06T15:20:40.823Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/3a/83/4f5b250220e1a5acd31345a5ec1c95a7769725d0d8135276f399f44062f8/svg_path-7.0-py2.py3-none-any.whl", hash = "sha256:447cb1e16a95acea2dd867fe737fa99cb75d587b4fc64dbee709a8dd6891ad9c", size = 18208, upload-time = "2025-07-06T15:20:39.59Z" }, +] + [[package]] name = "sympy" version = "1.14.0" @@ -10610,6 +10946,29 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/3c/b9/da09903ea53b677a58ba770112de6fe8b2acb8b4cd9bffae4ff6cfe7c072/trimesh-4.11.2-py3-none-any.whl", hash = "sha256:25e3ab2620f9eca5c9376168c67aabdd32205dad1c4eea09cd45cd4a3edf775a", size = 740328, upload-time = "2026-02-10T16:00:25.246Z" }, ] +[package.optional-dependencies] +easy = [ + { name = "charset-normalizer" }, + { name = "colorlog" }, + { name = "embreex", marker = "platform_machine == 'x86_64'" }, + { name = "httpx" }, + { name = "jsonschema" }, + { name = "lxml" }, + { name = "manifold3d", marker = "python_full_version < '3.14'" }, + { name = "mapbox-earcut" }, + { name = "networkx", version = "3.4.2", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, + { name = "networkx", version = "3.6.1", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, + { name = "pillow" }, + { name = "pycollada" }, + { name = "rtree" }, + { 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 = "shapely" }, + { name = "svg-path" }, + { name = "vhacdx" }, + { name = "xxhash" }, +] + [[package]] name = "triton" version = "3.6.0" @@ -11055,6 +11414,28 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/39/08/aaaad47bc4e9dc8c725e68f9d04865dbcb2052843ff09c97b08904852d84/urllib3-2.6.3-py3-none-any.whl", hash = "sha256:bf272323e553dfb2e87d9bfd225ca7b0f467b919d7bbd355436d3fd37cb0acd4", size = 131584, upload-time = "2026-01-07T16:24:42.685Z" }, ] +[[package]] +name = "usd-core" +version = "26.5" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/9b/a0/639e148c16a0ec201cc4848aa3da4aba8805e17a2d9e2398eec399fd3051/usd_core-26.5-cp310-none-macosx_10_15_universal2.whl", hash = "sha256:d6a3a567e313841b7390ea7a930bf5aef08bdb912974c725becd725d83edb0f9", size = 39723088, upload-time = "2026-04-24T20:17:23.663Z" }, + { url = "https://files.pythonhosted.org/packages/d7/26/6cb620a64f3fafa38b84008d916eee47c70e5313c5d88c9087edf4d57522/usd_core-26.5-cp310-none-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:85a1484024cdcefd77aac32a3b98e698f655e01951d62cc4d3fb3826e232400c", size = 28820064, upload-time = "2026-04-24T20:17:27.161Z" }, + { url = "https://files.pythonhosted.org/packages/00/d7/7814c95ca0b13a26313e5256472f90cfa2ab7f7cf3103b0d3611d41156e6/usd_core-26.5-cp310-none-win_amd64.whl", hash = "sha256:dff985cbfe24870a5dfe1c578acd918a358cd1680a17777d83b55d50f5560c18", size = 13450099, upload-time = "2026-04-24T20:17:29.994Z" }, + { url = "https://files.pythonhosted.org/packages/39/3a/adf7a4043e70974b84d3a572f928ffdd1176a070595cd17f028062622ade/usd_core-26.5-cp311-none-macosx_10_15_universal2.whl", hash = "sha256:b5416a108080311632b975da71b4ea480757ac6e7ea19b30bcd0eed6a3b6081f", size = 39723550, upload-time = "2026-04-24T20:17:32.975Z" }, + { url = "https://files.pythonhosted.org/packages/e2/7f/575b0ddc2a3effa1dc1f50ed67ae0def8f9ed961c69bfbb89a0a1c9ceaf8/usd_core-26.5-cp311-none-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:60076c97f0de2611dc39d2d25826e3b22a2b0e391c73806b4a072d69929f329e", size = 28825210, upload-time = "2026-04-24T20:17:37.136Z" }, + { url = "https://files.pythonhosted.org/packages/9f/51/9fb7c817f1ee7aff02adde8ec4805ff4add06482e036fe0914ab8e9cdbc5/usd_core-26.5-cp311-none-win_amd64.whl", hash = "sha256:1ff2031095ecdc2f9ff4e245114e6ab7001f7dec8fe75436b5beb72e1a280f57", size = 13450734, upload-time = "2026-04-24T20:17:39.641Z" }, + { url = "https://files.pythonhosted.org/packages/8d/cc/04870cc3ae8e1b3a4e168efea47e389cfab6ab4f619005da2443a10390d4/usd_core-26.5-cp312-none-macosx_10_15_universal2.whl", hash = "sha256:a9df2864e84b83ffc9cc0f2777a49170180f84f2b679bcd014d72036a51d057c", size = 39775789, upload-time = "2026-04-24T20:17:43.025Z" }, + { url = "https://files.pythonhosted.org/packages/77/62/963d3aba966539917d01e4a2169a1c07f7b3df087fc16ee39fc764214969/usd_core-26.5-cp312-none-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:caa2447252aeada8c158faacd4d448f29cf1617aeccef5bb954734b93c8f3f62", size = 28743527, upload-time = "2026-04-24T20:17:46.631Z" }, + { url = "https://files.pythonhosted.org/packages/3b/b0/645ae6e27a9768e570c1044efd6d2369c10c5c2412669314b3d6cd914803/usd_core-26.5-cp312-none-win_amd64.whl", hash = "sha256:6d887b010c756508d2e1f770626201f1f4ba5227c052c1135ba9c19932c4da8e", size = 13494028, upload-time = "2026-04-24T20:17:49.599Z" }, + { url = "https://files.pythonhosted.org/packages/2e/cd/128de2e16d597eb0868dde7cc837a908b28ec2a0d90d4697714b6770449b/usd_core-26.5-cp313-none-macosx_10_15_universal2.whl", hash = "sha256:ce5e90a6795b93d7e744694e5209ea2f1754f9d596e67a89f0cc3590e9fff578", size = 39776038, upload-time = "2026-04-24T20:17:52.535Z" }, + { url = "https://files.pythonhosted.org/packages/f1/10/88838fd371592cfc3d972547ab4361e2deef5891d89c22a509de0e6696ce/usd_core-26.5-cp313-none-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:dd4d3de388e6dfec91fa5ee9fa29800d43ebe86cbf7a10380ec02b15386fca67", size = 28743992, upload-time = "2026-04-24T20:17:55.995Z" }, + { url = "https://files.pythonhosted.org/packages/62/05/da8f44024e0f947c13da3bdae0d4ac6c04cb86de92a6f1b9bf03e6bb8ae8/usd_core-26.5-cp313-none-win_amd64.whl", hash = "sha256:b077ea37dfeb15ca6b24ca33b65c2fe9b1656138e1fda74e4eae9793a149a7d5", size = 13494201, upload-time = "2026-04-24T20:17:59.015Z" }, + { url = "https://files.pythonhosted.org/packages/3d/57/01cc4e412feaad5aaee09d09ead2afbd5b4022e3d3b5461adcbf726ca3f8/usd_core-26.5-cp314-none-macosx_10_15_universal2.whl", hash = "sha256:5b0acd9a1d804cb73d58815365ccb141727f635f4e6764609fade3bf4ef5cbba", size = 39927684, upload-time = "2026-04-24T20:18:01.828Z" }, + { url = "https://files.pythonhosted.org/packages/fd/0d/5b87f5d7c3501bd5296b0bba7ba8a3eaf639ded53b9a17e910ee3363dfc0/usd_core-26.5-cp314-none-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:755c469ec762f3b69d87f5e8af8f8098e4c107bf4c15ce570a042ac2fc2dbb76", size = 28776483, upload-time = "2026-04-24T20:18:05.082Z" }, + { url = "https://files.pythonhosted.org/packages/5a/48/d29a4649df00455174a5979fc8291021199bb2115d623378364b58055bb5/usd_core-26.5-cp314-none-win_amd64.whl", hash = "sha256:7654b5dfef6e7177849aa7e69962feb82a5312ad08469983214aae5821601296", size = 14043860, upload-time = "2026-04-24T20:18:07.896Z" }, +] + [[package]] name = "uuid-utils" version = "0.14.0" @@ -11153,6 +11534,60 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e4/16/c1fd27e9549f3c4baf1dc9c20c456cd2f822dbf8de9f463824b0c0357e06/uvloop-0.22.1-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:6cde23eeda1a25c75b2e07d39970f3374105d5eafbaab2a4482be82f272d5a5e", size = 4296730, upload-time = "2025-10-16T22:17:00.744Z" }, ] +[[package]] +name = "vhacdx" +version = "0.0.10" +source = { registry = "https://pypi.org/simple" } +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'" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/15/e3/d2abc3dc4c1cb216c2efdc70b36f80efeb1bdbd7d420a676ddc9d9d980e1/vhacdx-0.0.10.tar.gz", hash = "sha256:fcc23201e319d79fe25e064847efc254bd39ac30af28cc761409e1f9142dd033", size = 58125, upload-time = "2025-12-02T20:58:45.358Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/c4/f4/da308d86daaa9c636851357cbd928715d47963beecd525b3749d2d5c9537/vhacdx-0.0.10-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:4bc7be82fab608cb7231e95a0a10700be1e9422a36b21e7d49c782a598c8d37c", size = 222760, upload-time = "2025-12-02T20:57:30.778Z" }, + { url = "https://files.pythonhosted.org/packages/e0/8a/e3462a43ec6712b74d921e4af9d5a2998752378c5554bde9a594dbb0cf0c/vhacdx-0.0.10-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:4b63d1c5ad0e64c300a3a9d9404f4778df367b8c545639dfb932db4b76704ff3", size = 208812, upload-time = "2025-12-02T20:57:33.486Z" }, + { url = "https://files.pythonhosted.org/packages/fb/d1/b717275adb108431f1404193542fab7ecf4c5bae221f1552bbd570fe0e5d/vhacdx-0.0.10-cp310-cp310-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f9bcf3fe1c555598e41348108b55a0fc67534e7fef2367452c301014518c1476", size = 236999, upload-time = "2025-12-02T20:57:34.971Z" }, + { url = "https://files.pythonhosted.org/packages/bf/84/97e2305f6bd4a4de3d40bb234c38282cbcf2fa30653ff5ae4f7df9d8f3ec/vhacdx-0.0.10-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9506ca89289da63e5a3d1ac97aa7413aece47d65cbaa4b0c409469555add0e06", size = 250035, upload-time = "2025-12-02T20:57:36.037Z" }, + { url = "https://files.pythonhosted.org/packages/9d/66/eb1d8d64742b9e73557e075cea6ee7e4976dd89b84c7d3197ca3621d5a85/vhacdx-0.0.10-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:06faf9caa0abceddd5fa505e4299e2ebf14bc26c58a1e521013717cbf37bea61", size = 1224134, upload-time = "2025-12-02T20:57:37.217Z" }, + { url = "https://files.pythonhosted.org/packages/47/db/e829b21b071db94f45079c4ace2f967c684f08b10ea285919a95e9d5fe21/vhacdx-0.0.10-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:3a6b43b42290697e2bd04087977d1e3841d287c528e414c765581ecec62e66f6", size = 1284300, upload-time = "2025-12-02T20:57:38.78Z" }, + { url = "https://files.pythonhosted.org/packages/ff/aa/b401565542b927ce3e0a6d5e72acef79343a449ee1a7ad94a5c7266bab26/vhacdx-0.0.10-cp310-cp310-win_amd64.whl", hash = "sha256:27eb3b293ccef1332d477346d564bb4c474bb451e9b753e3ce9cac01cbb90a0c", size = 193069, upload-time = "2025-12-02T20:57:40.318Z" }, + { url = "https://files.pythonhosted.org/packages/b7/2c/d49df6fec3294cef3c8c88c54784162bd8350c427fecd9b16335772b760f/vhacdx-0.0.10-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:8584f33ed020b6cce678b8febcf84af22bced617ef31c85bf31fd7e2b4bba9fe", size = 224113, upload-time = "2025-12-02T20:57:41.59Z" }, + { url = "https://files.pythonhosted.org/packages/68/1d/bd2456baa6b16977c106adc2386b6e7a34c3e57ade6aeeab68bb61ceb16f/vhacdx-0.0.10-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:a9b63cdb5f34dfee386b64a01f7e1571ef0c2555244ea3d83a09d78273123bce", size = 210118, upload-time = "2025-12-02T20:57:42.749Z" }, + { url = "https://files.pythonhosted.org/packages/49/ab/15adb78489b51c2a898642755be727ecd7c3de37cac6e434ce420b8ce27c/vhacdx-0.0.10-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:915eab6c19fdf63ab256855331db546575284786a480aa2d67437db0e86b0d17", size = 238276, upload-time = "2025-12-02T20:57:43.95Z" }, + { url = "https://files.pythonhosted.org/packages/a6/f1/464c761dbe24f58d6fc354bf51729342981fb7a621e170e0d3512fadbec8/vhacdx-0.0.10-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6e335bb9af540e6867ff051166a399075823fdd8fc1fc27e9530995cc1bda1eb", size = 251383, upload-time = "2025-12-02T20:57:45.246Z" }, + { url = "https://files.pythonhosted.org/packages/b2/22/c7b4117c5431189a6a019e8fc2cf590df3ab196c38b4b7c3622292205d9b/vhacdx-0.0.10-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:c3ddbaa38eb65c3aec9b0e39a822223474c931c0e18d3e93a3a499870ffa45ad", size = 1225200, upload-time = "2025-12-02T20:57:46.639Z" }, + { url = "https://files.pythonhosted.org/packages/6c/62/c679ad28ce7854771913255e1abc588b3643c2147fb5c51a8553224aa1dd/vhacdx-0.0.10-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:d398fcc13e330ed1fd2540a7d572aeca0be9621411def78e10c7ea4132f959ee", size = 1285935, upload-time = "2025-12-02T20:57:48.51Z" }, + { url = "https://files.pythonhosted.org/packages/de/c8/a8260b780e4578d7ef19b70343f9717f74ff48f9950138c96c78f209ec01/vhacdx-0.0.10-cp311-cp311-win_amd64.whl", hash = "sha256:c9665a3ef887babcac8b5822f01288e8f06b4a949fadbbe1861670b358f111ee", size = 194137, upload-time = "2025-12-02T20:57:50.207Z" }, + { url = "https://files.pythonhosted.org/packages/cf/9c/66375e65634c80f6efb46e81915126bf3e55dc9d6615217590cbc8316d2e/vhacdx-0.0.10-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:7dd17d697d6d4d7cf66f1e947e0530041913981e05f7025236bec28a350b1a33", size = 224998, upload-time = "2025-12-02T20:57:51.639Z" }, + { url = "https://files.pythonhosted.org/packages/4e/e3/fc2644d3e7d0b2b52e2f681eb2878c0e1b9cafc53946f66736d0f01e237c/vhacdx-0.0.10-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:189ded39b709436cb732cdf694d4cf22e877aefb97e2ab2b55bf7ada9c030f93", size = 211130, upload-time = "2025-12-02T20:57:53.018Z" }, + { url = "https://files.pythonhosted.org/packages/e3/93/0b0f1977f5b3c2e1bbea5ef85e37a808ff73f1b7daf42950c57090e90dc7/vhacdx-0.0.10-cp312-cp312-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f3b03d35ab56a93beee338175dbe0b87552353e5dfb3ff37467e88f56cedf7cc", size = 239661, upload-time = "2025-12-02T20:57:54.144Z" }, + { url = "https://files.pythonhosted.org/packages/94/98/d2a6aeb1c6570a1fc1be29ee03db795f643ab03c6df7635522f23796b39d/vhacdx-0.0.10-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:ea8c54ed193fa0db0248928fbf5d438b3872d615a506889d5b89fc6467d6411a", size = 252938, upload-time = "2025-12-02T20:57:55.275Z" }, + { url = "https://files.pythonhosted.org/packages/94/2e/1e678efc161a0d7fe1806f5e037ce11cc5964db7e08ccfc220ef63951863/vhacdx-0.0.10-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:a5c898104140c72e4dc789e6125812671eee5e412916e83eff24a6148248ff5e", size = 1226696, upload-time = "2025-12-02T20:57:56.438Z" }, + { url = "https://files.pythonhosted.org/packages/90/5b/b302a0420a241c4910f4870eb9f39e6ada59858db441cc35bda511c17982/vhacdx-0.0.10-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:abdd0ba17786e578206594731df15c90e2751b6884220c8673124f47fd7ac620", size = 1287794, upload-time = "2025-12-02T20:57:57.694Z" }, + { url = "https://files.pythonhosted.org/packages/73/e9/f9729603ac75047a257f1b4ddac60cbde72b0abfd49ffed305751ba630a2/vhacdx-0.0.10-cp312-cp312-win_amd64.whl", hash = "sha256:79e7db59b4042295b21b79d55ba486a9a480550f696d466f158a30ed920dd0ec", size = 195033, upload-time = "2025-12-02T20:57:58.95Z" }, + { url = "https://files.pythonhosted.org/packages/0e/54/c2fc08d9324bbd92735caf9207cbabada3a8dd9d270d6e46ca69eb7f883d/vhacdx-0.0.10-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:0599bc2a96de8fc9aeff460b3e88b8572e84ae95b8fc6c9888ef4b92023c22d5", size = 225014, upload-time = "2025-12-02T20:58:00.938Z" }, + { url = "https://files.pythonhosted.org/packages/3b/9e/42adb642a12915acc9cb2bfab21710a6aabf045c26967ba0ff0e08a872d0/vhacdx-0.0.10-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:dc648829a1e973f34ee11393a4f334ab55e3e0e9c4b9f6d6349af966fdf1895a", size = 211127, upload-time = "2025-12-02T20:58:02.107Z" }, + { url = "https://files.pythonhosted.org/packages/51/3d/63e090cd966817b89643d7e52e13df45043b22a42c7fbf702866bdd75bc0/vhacdx-0.0.10-cp313-cp313-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:74c03f7315a434ec83cd0bff1e6bce6af4c01df61d677f48f3ffb36800606ee7", size = 239471, upload-time = "2025-12-02T20:58:03.173Z" }, + { url = "https://files.pythonhosted.org/packages/b8/b4/07ab1c828bae0eb5c72cd9a4cbe8b0376d374509be3c7055e1a399bf85c3/vhacdx-0.0.10-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:1fcd02acc3733ec3a0a0d28ca7f526d4c56f14a3ceb4b12fce45acf72c09054a", size = 253019, upload-time = "2025-12-02T20:58:04.318Z" }, + { url = "https://files.pythonhosted.org/packages/05/cb/bc8a8858b300d2c092da11096ae0586ece446b4c41cb26620bf00d1d8232/vhacdx-0.0.10-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:4b9f8a80ca4c54d7fa76419a2ebd9e9386cd177dc4d2b97f2208ac57c9a7e8aa", size = 1226933, upload-time = "2025-12-02T20:58:05.907Z" }, + { url = "https://files.pythonhosted.org/packages/15/52/213230883874615f1661903bce1ace5013d03b34696efce8d53c662a3358/vhacdx-0.0.10-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:847bd43e82afb439dd3fa972618d786d0b98d8ef04a8e8a6381f6945204d2505", size = 1288871, upload-time = "2025-12-02T20:58:07.432Z" }, + { url = "https://files.pythonhosted.org/packages/32/25/f0e6806824f88d47ab8bc1c9bf6f11634fd7b382d635d0696825f3b5672f/vhacdx-0.0.10-cp313-cp313-win_amd64.whl", hash = "sha256:ab300c5f3fe4e54f99af92f9ea27c977b09df5f59190b0a3e025161110f71ce7", size = 195091, upload-time = "2025-12-02T20:58:08.783Z" }, + { url = "https://files.pythonhosted.org/packages/b7/b8/5137c048728fddd3315a79c94ba8663f3707f9268af9af15b15e1ef3cd85/vhacdx-0.0.10-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:147030c7683be4f21a3cdfb202b121c01716694b61ddad794345fcd9fa43d0ec", size = 225247, upload-time = "2025-12-02T20:58:09.918Z" }, + { url = "https://files.pythonhosted.org/packages/1b/08/5c731863db402e9878380f68be8722fabbcaf8cfe8d06237aaf15f116d95/vhacdx-0.0.10-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:069eb4381917b790921a33d4cc6ed07f7ed5362474232110baf8dd3dadcd768d", size = 211339, upload-time = "2025-12-02T20:58:10.951Z" }, + { url = "https://files.pythonhosted.org/packages/04/3a/e93ce9b653a9f435c530df8d5ad68a80b8bdc2b8518abc225fef9e7f349a/vhacdx-0.0.10-cp314-cp314-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:7702892008b1150619c1f66a62ef88d1cb8f92b09d9c39a0bfb87d147f1c5ae2", size = 239974, upload-time = "2025-12-02T20:58:12.101Z" }, + { url = "https://files.pythonhosted.org/packages/77/dc/ef34f97a65385bc1f8ed4718fa5f7d96313e299e76761f1b69efaf597797/vhacdx-0.0.10-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:b4d550dfc377471b36f11065fc12cfbbd1750d63b10a336644bfdcbf27aa8382", size = 253245, upload-time = "2025-12-02T20:58:13.303Z" }, + { url = "https://files.pythonhosted.org/packages/f4/6c/57051066bd0589b7fe68c32061821180f520b6a7ef4efa072b755dde63d3/vhacdx-0.0.10-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:edce8f0ff516a111b6f1d644782a1d496b3e9e34ff4ce09849c9b8071627bca5", size = 1227432, upload-time = "2025-12-02T20:58:14.73Z" }, + { url = "https://files.pythonhosted.org/packages/1d/49/3488f2bd991027bd86f072cf776935c80b4e630bd3bc43c3289bc6eeeba0/vhacdx-0.0.10-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:4c463abbdce73d5d0b94eab2c9f43f2b55a4d0e788d87af659cc78029b960bf9", size = 1289126, upload-time = "2025-12-02T20:58:16.009Z" }, + { url = "https://files.pythonhosted.org/packages/77/56/2f4506382a1133bf441cba2010017064e8f7af940d100141799d7e867e58/vhacdx-0.0.10-cp314-cp314-win_amd64.whl", hash = "sha256:b93c834f2bf1fa6630da5d3f77e94ea8e542fca31e385244a7ec905a32155549", size = 198706, upload-time = "2025-12-02T20:58:17.378Z" }, + { url = "https://files.pythonhosted.org/packages/db/f6/4fabfe65f3123abda09adc416a396caf8c2ad1b29c34a5178ec71754a163/vhacdx-0.0.10-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:4c0f1bafc53e156472b0367533c2d3ec7a96b676b6d57aa92dd3e37519331b07", size = 228276, upload-time = "2025-12-02T20:58:18.545Z" }, + { url = "https://files.pythonhosted.org/packages/dc/70/bdc742628adcf9966cea81be7a651300bc399b492d10a763781af6d27041/vhacdx-0.0.10-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:b0f8643dcb1f0774320fc1389ead0d0da4536e4c0fecfd4c8133baec0b6fa556", size = 214287, upload-time = "2025-12-02T20:58:19.696Z" }, + { url = "https://files.pythonhosted.org/packages/84/6a/f2e37ad333d3f671e1d59ba76bb61edc5520146539d52ee29e555becb4ac/vhacdx-0.0.10-cp314-cp314t-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:4547f3e55eb935d163d89c10ffdcadf8797c3b435a9dc82be4e0e27b1e3abff0", size = 240923, upload-time = "2025-12-02T20:58:21.105Z" }, + { url = "https://files.pythonhosted.org/packages/5b/7a/f0325cd7ece95dbbc10d0c3f6d241d47beb3b99ae4dafe2e450082cd7bd9/vhacdx-0.0.10-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:ee09c4f2b6385546001b5e8609f428417fac147cfd3ea020fbc7dec0f11c489b", size = 254257, upload-time = "2025-12-02T20:58:22.176Z" }, + { url = "https://files.pythonhosted.org/packages/ac/56/53347b910351eb4cf32a797e177f18b8d82b1ef4e4325607254cfe88ad2a/vhacdx-0.0.10-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:8b94d198e4716f9220985523f374617432ef5530910f3730051f3e7fcba71798", size = 1228434, upload-time = "2025-12-02T20:58:23.302Z" }, + { url = "https://files.pythonhosted.org/packages/be/f5/f86c63da38b0446ef6652e8e72b84451e440418eaac0f554737e159ae36e/vhacdx-0.0.10-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:39c6d31ed27e3f33e9411927e1567ba37a18ba7ce9295efd1b24414b7313b503", size = 1288854, upload-time = "2025-12-02T20:58:24.46Z" }, + { url = "https://files.pythonhosted.org/packages/0c/d1/b30dec954a24b41358297a3fbe7c30d8e2e818831f552cb34c904baa04e4/vhacdx-0.0.10-cp314-cp314t-win_amd64.whl", hash = "sha256:fc6a613082ec522a020e4f6a09f39ed42546de9aebe99548aa84938b1440871c", size = 204896, upload-time = "2025-12-02T20:58:25.825Z" }, +] + [[package]] name = "virtualenv" version = "20.36.1" @@ -11168,6 +11603,29 @@ 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" }, ] +[[package]] +name = "viser" +version = "1.0.27" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "imageio" }, + { name = "msgspec" }, + { 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 = "requests" }, + { name = "rich" }, + { name = "tqdm" }, + { name = "trimesh" }, + { name = "typing-extensions" }, + { name = "websockets" }, + { name = "yourdfpy" }, + { name = "zstandard" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/fd/f5/48adb4e5e4234f48e96a1e7fc50cca6731280df0c279833e333963f9ea5c/viser-1.0.27.tar.gz", hash = "sha256:87e3239d6c1c2c003db93ac4072430ec790e336ffe7214781f035e54faebc0af", size = 4897986, upload-time = "2026-05-06T10:30:47.556Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/7c/ad/8ae712579e294b4395fb39f7d65524b51fc7b731eacce26af096b7e59b61/viser-1.0.27-py3-none-any.whl", hash = "sha256:8da5b7934416e6e2d3a7ebcf39fc840f21030b51eb63231e8cfef457bfb49031", size = 4998748, upload-time = "2026-05-06T10:30:49.965Z" }, +] + [[package]] name = "wadler-lindig" version = "0.1.7" @@ -11936,6 +12394,22 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/66/c9/d4b03b2490107f13ebd68fe9496d41ae41a7de6275ead56d0d4621b11ffd/yapf-0.40.2-py3-none-any.whl", hash = "sha256:adc8b5dd02c0143108878c499284205adb258aad6db6634e5b869e7ee2bd548b", size = 254707, upload-time = "2023-09-22T18:40:43.297Z" }, ] +[[package]] +name = "yourdfpy" +version = "0.0.60" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "lxml" }, + { 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 = "six" }, + { name = "trimesh", extra = ["easy"] }, +] +sdist = { url = "https://files.pythonhosted.org/packages/ff/19/20c50861f30aff7720f9a601f386d73760c2df9961de1f98d0dbf3b85e69/yourdfpy-0.0.60.tar.gz", hash = "sha256:2af2d8bdeea1b85b642590a3b4236fdb35746d7b3e38ce460a169c18d9c4f868", size = 538238, upload-time = "2026-01-23T07:32:47.856Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/c8/60/4ea0d6df0b497d51bf2ef87eaab0eb26f8bc3b3313c012da5df3383cced9/yourdfpy-0.0.60-py3-none-any.whl", hash = "sha256:8a187a8b18c98db87c76e9a950581b3c875b761e00df83942526c17ea693166c", size = 22194, upload-time = "2026-01-23T07:32:46.481Z" }, +] + [[package]] name = "zipp" version = "3.23.0" From e76cb63a944f47c33d9f72bc4ab8b07c5792fb73 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 02:56:33 +0200 Subject: [PATCH 02/30] Clean up MuJoCo scene playground --- dimos/mapping/mesh_scene.py | 28 -- ...{usdz_to_mjcf.py => scene_mesh_to_mjcf.py} | 251 ++++++++++-------- dimos/robot/all_blueprints.py | 2 + dimos/simulation/engines/mujoco_sim_module.py | 182 +++++++------ dimos/simulation/mujoco_scene_playground.py | 7 +- .../viser/viser_render_module.py | 101 +++---- pyproject.toml | 1 + uv.lock | 3 + 8 files changed, 304 insertions(+), 271 deletions(-) rename dimos/mapping/{usdz_to_mjcf.py => scene_mesh_to_mjcf.py} (58%) diff --git a/dimos/mapping/mesh_scene.py b/dimos/mapping/mesh_scene.py index 9036813365..d85e0b5001 100644 --- a/dimos/mapping/mesh_scene.py +++ b/dimos/mapping/mesh_scene.py @@ -556,34 +556,6 @@ def load_scene_prims( return prims -def floor_z_under_origin( - scene_mesh_path: str | Path, - alignment: SceneMeshAlignment | None = None, -) -> float: - """Return the z of the first surface ``(x=0, y=0)`` falls onto. - - Casts one ray straight down from a high z; the first hit defines - the local floor at origin. Falls back to the mesh's bbox min-z - when origin is over a hole (or outside the bbox xy footprint). - Used by the GR00T sim blueprint to align the loaded scene with - the robot's default spawn pose so all three downstream views - (viser, mesh camera, MuJoCo physics) share one world frame. - """ - import open3d.core as o3c - - mesh = load_scene_mesh(scene_mesh_path, alignment=alignment) - scene = make_raycasting_scene(mesh) - rays = o3c.Tensor( - np.array([[0.0, 0.0, 1000.0, 0.0, 0.0, -1.0]], dtype=np.float32), - dtype=o3c.Dtype.Float32, - ) - t = float(scene.cast_rays(rays)["t_hit"].numpy()[0]) - if np.isfinite(t): - return 1000.0 - t - bb = mesh.get_axis_aligned_bounding_box() - return float(bb.min_bound[2]) - - __all__ = [ "SceneMeshAlignment", "load_scene_mesh", diff --git a/dimos/mapping/usdz_to_mjcf.py b/dimos/mapping/scene_mesh_to_mjcf.py similarity index 58% rename from dimos/mapping/usdz_to_mjcf.py rename to dimos/mapping/scene_mesh_to_mjcf.py index 2566126fd3..b989fdd59b 100644 --- a/dimos/mapping/usdz_to_mjcf.py +++ b/dimos/mapping/scene_mesh_to_mjcf.py @@ -12,35 +12,14 @@ # See the License for the specific language governing permissions and # limitations under the License. -"""Bake a USDZ/GLB/OBJ scene mesh into an MJCF wrapper around a robot MJCF. - -MuJoCo only reads ``.stl`` / ``.obj`` / ``.msh`` meshes — not USD. This -module loads a scene mesh through the existing ``mesh_scene`` loader, -writes the welded geometry out as OBJ, and emits a tiny MJCF that -````s the robot MJCF and adds the scene mesh as a single -static collidable body. - -Pipeline: - - 1. ``load_scene_mesh()`` → ``open3d.geometry.TriangleMesh`` in dimos - world frame (Z-up, meters), with all per-prim transforms baked in. - 2. ``open3d.io.write_triangle_mesh()`` → OBJ on disk. - 3. Wrapper MJCF references both the robot MJCF (via absolute-path - ````) and the scene OBJ, declares one body with one mesh - geom (``contype=1 conaffinity=1`` — collides with anything that's - also enabled). ``meshdir`` / ``texturedir`` in the wrapper's - ```` are pinned to the robot MJCF's directory so the - robot's STLs still resolve through the include. - -Output is cached at ``~/.cache/dimos/scene_meshes//`` keyed on -the source mesh, robot MJCF, alignment params, and mesh directory. -""" +"""Bake a scene mesh into an MJCF wrapper around a robot MJCF.""" from __future__ import annotations -from dataclasses import asdict +from dataclasses import asdict, dataclass import hashlib from pathlib import Path +from typing import Any import numpy as np import open3d as o3d # type: ignore[import-untyped] @@ -74,6 +53,18 @@ ' ' ) +_DEGENERATE_EPS = 1e-3 +_SHELL_VOLUME_M3 = 2.0 + + +@dataclass +class _BakeArtifacts: + asset_lines: list[str] + geom_lines: list[str] + total_tris: int + skipped_degenerate: int + n_hulls: int + n_decomposed: int def bake_scene_mjcf( @@ -86,13 +77,13 @@ def bake_scene_mjcf( """Convert ``scene_mesh_path`` to OBJ and emit a wrapped MJCF. Args: - scene_mesh_path: ``.usdz`` / ``.glb`` / ``.obj`` etc. — anything + scene_mesh_path: ``.usdz`` / ``.glb`` / ``.obj`` etc.; anything ``mesh_scene.load_scene_mesh`` accepts. robot_mjcf_path: the base robot MJCF the wrapper will ````. alignment: scale / translation / rotation / y-up swap to bake into the OBJ before MuJoCo sees it. Authoritative for all - three views (MuJoCo physics, viser, mesh camera) — the + three views (MuJoCo physics, viser, mesh camera); the blueprint passes the same ``SceneMeshAlignment`` to each so the world frames agree to the millimeter. meshdir: directory MuJoCo should resolve unqualified mesh @@ -117,20 +108,12 @@ def bake_scene_mjcf( meshdir = Path(meshdir).expanduser().resolve() if meshdir else robot_mjcf_path.parent - # Cache key — invalidates when any input changes. - h = hashlib.sha256() - h.update(scene_mesh_path.read_bytes()) - h.update(robot_mjcf_path.read_bytes()) - h.update(repr(sorted(asdict(align).items())).encode()) - h.update(str(meshdir).encode()) - cache_key = h.hexdigest()[:12] - + cache_key = _cache_key(scene_mesh_path, robot_mjcf_path, align, meshdir) root = (cache_root or CACHE_DIR).expanduser() cache_dir = root / cache_key wrapper_path = cache_dir / "wrapper.xml" - # Cache hit: wrapper exists + at least one prim OBJ next to it. - if wrapper_path.exists() and any(cache_dir.glob("*.obj")): + if _cache_hit(wrapper_path, cache_dir): logger.info(f"bake_scene_mjcf: cache hit at {cache_dir}") return wrapper_path @@ -142,6 +125,47 @@ def bake_scene_mjcf( prims = load_scene_prims(scene_mesh_path, alignment=align) logger.info(f"bake_scene_mjcf: {len(prims)} prims to bake") + artifacts = _bake_collision_hulls(prims, cache_dir) + if not artifacts.asset_lines: + raise RuntimeError( + "bake_scene_mjcf: every hull came out degenerate; nothing left to collide against" + ) + logger.info( + f"bake_scene_mjcf: baked {artifacts.n_hulls} convex hulls from {len(prims)} prims " + f"({artifacts.total_tris} tris total), VHACD-decomposed {artifacts.n_decomposed} " + f"shell prims, skipped {artifacts.skipped_degenerate} degenerate hulls" + ) + + _write_wrapper( + wrapper_path=wrapper_path, + cache_key=cache_key, + meshdir=meshdir, + robot_mjcf_path=robot_mjcf_path, + asset_lines=artifacts.asset_lines, + geom_lines=artifacts.geom_lines, + ) + return wrapper_path + + +def _cache_key( + scene_mesh_path: Path, + robot_mjcf_path: Path, + alignment: SceneMeshAlignment, + meshdir: Path, +) -> str: + h = hashlib.sha256() + h.update(scene_mesh_path.read_bytes()) + h.update(robot_mjcf_path.read_bytes()) + h.update(repr(sorted(asdict(alignment).items())).encode()) + h.update(str(meshdir).encode()) + return h.hexdigest()[:12] + + +def _cache_hit(wrapper_path: Path, cache_dir: Path) -> bool: + return wrapper_path.exists() and any(cache_dir.glob("*.obj")) + + +def _bake_collision_hulls(prims: list[Any], cache_dir: Path) -> _BakeArtifacts: import trimesh asset_lines: list[str] = [] @@ -149,12 +173,8 @@ def bake_scene_mjcf( total_tris = 0 skipped_degenerate = 0 n_hulls = 0 - _DEGENERATE_EPS = 1e-3 - # Furniture-scale prims are fine as one hull. Large shell-like prims - # need decomposition or MuJoCo sees the room as a solid block. - _SHELL_VOLUME_M3 = 2.0 n_decomposed = 0 - logger.info(f"bake_scene_mjcf: per-prim convex-hulling {len(prims)} prims (one-time)…") + logger.info(f"bake_scene_mjcf: per-prim convex-hulling {len(prims)} prims (one-time)") for prim in prims: tm = trimesh.Trimesh( vertices=prim.vertices.astype(np.float64), @@ -167,81 +187,99 @@ def bake_scene_mjcf( logger.warning(f" convex_hull failed for {prim.name}: {e}; skipping") continue - if float(single_hull.volume) > _SHELL_VOLUME_M3: - try: - parts = tm.convex_decomposition(maxConvexHulls=64, resolution=200_000) - if not isinstance(parts, list): - parts = [parts] - hulls = parts - n_decomposed += 1 - logger.info( - f" {prim.name}: VHACD decomposed " - f"({single_hull.volume:.1f} m³ shell → {len(parts)} sub-hulls)" - ) - except Exception as e: - logger.warning( - f" VHACD failed for {prim.name}: {e}; " - f"using single hull (will swallow robot spawn area)" - ) - hulls = [single_hull] - else: - hulls = [single_hull] + hulls, decomposed = _collision_hulls(tm, single_hull, prim.name) + if decomposed: + n_decomposed += 1 for j, hull in enumerate(hulls): v = np.asarray(hull.vertices, dtype=np.float32) f = np.asarray(hull.faces, dtype=np.int32) - if len(v) < 4 or len(f) < 4: - skipped_degenerate += 1 - continue - extent = v.max(axis=0) - v.min(axis=0) - if (extent < _DEGENERATE_EPS).any(): - skipped_degenerate += 1 - continue - min_ext = float(extent.min()) - max_ext = float(extent.max()) - if max_ext > 0 and (min_ext / max_ext) < 0.05: - skipped_degenerate += 1 - continue - if min_ext < 5e-3: - skipped_degenerate += 1 - continue - try: - from scipy.spatial import ConvexHull, QhullError - - ConvexHull(v, qhull_options="Qt") - except (QhullError, ValueError): + if not _valid_hull(v, f): skipped_degenerate += 1 continue asset_name = f"{prim.name}_h{j:03d}" obj_file = cache_dir / f"{asset_name}.obj" - o3d_mesh = o3d.geometry.TriangleMesh() - o3d_mesh.vertices = o3d.utility.Vector3dVector(v.astype(np.float64)) - o3d_mesh.triangles = o3d.utility.Vector3iVector(f) - o3d_mesh.compute_vertex_normals() - if not o3d.io.write_triangle_mesh( - str(obj_file), - o3d_mesh, - write_vertex_normals=True, - write_vertex_colors=False, - ): - raise RuntimeError(f"open3d failed to write OBJ: {obj_file}") + _write_hull_obj(obj_file, v, f) total_tris += len(f) n_hulls += 1 asset_lines.append(_ASSET_LINE.format(name=asset_name, file=str(obj_file))) geom_lines.append(_GEOM_LINE.format(name=f"{asset_name}_geom", mesh=asset_name)) - if not asset_lines: - raise RuntimeError( - "bake_scene_mjcf: every hull came out degenerate; nothing left to collide against" - ) - logger.info( - f"bake_scene_mjcf: baked {n_hulls} convex hulls from {len(prims)} prims " - f"({total_tris} tris total), VHACD-decomposed {n_decomposed} shell prims, " - f"skipped {skipped_degenerate} degenerate hulls" + return _BakeArtifacts( + asset_lines=asset_lines, + geom_lines=geom_lines, + total_tris=total_tris, + skipped_degenerate=skipped_degenerate, + n_hulls=n_hulls, + n_decomposed=n_decomposed, ) + +def _collision_hulls(tm: Any, single_hull: Any, prim_name: str) -> tuple[list[Any], bool]: + if float(single_hull.volume) <= _SHELL_VOLUME_M3: + return [single_hull], False + try: + parts = tm.convex_decomposition(maxConvexHulls=64, resolution=200_000) + hulls = parts if isinstance(parts, list) else [parts] + logger.info( + f" {prim_name}: VHACD decomposed " + f"({single_hull.volume:.1f} m³ shell -> {len(hulls)} sub-hulls)" + ) + return hulls, True + except Exception as e: + logger.warning( + f" VHACD failed for {prim_name}: {e}; using single hull " + "(large rooms may collide as a solid shell)" + ) + return [single_hull], False + + +def _valid_hull(v: np.ndarray, f: np.ndarray) -> bool: + if len(v) < 4 or len(f) < 4: + return False + extent = v.max(axis=0) - v.min(axis=0) + if (extent < _DEGENERATE_EPS).any(): + return False + min_ext = float(extent.min()) + max_ext = float(extent.max()) + if max_ext > 0 and (min_ext / max_ext) < 0.05: + return False + if min_ext < 5e-3: + return False + try: + from scipy.spatial import ConvexHull, QhullError + + ConvexHull(v, qhull_options="Qt") + except (QhullError, ValueError): + return False + return True + + +def _write_hull_obj(obj_file: Path, vertices: np.ndarray, faces: np.ndarray) -> None: + o3d_mesh = o3d.geometry.TriangleMesh() + o3d_mesh.vertices = o3d.utility.Vector3dVector(vertices.astype(np.float64)) + o3d_mesh.triangles = o3d.utility.Vector3iVector(faces) + o3d_mesh.compute_vertex_normals() + if not o3d.io.write_triangle_mesh( + str(obj_file), + o3d_mesh, + write_vertex_normals=True, + write_vertex_colors=False, + ): + raise RuntimeError(f"open3d failed to write OBJ: {obj_file}") + + +def _write_wrapper( + *, + wrapper_path: Path, + cache_key: str, + meshdir: Path, + robot_mjcf_path: Path, + asset_lines: list[str], + geom_lines: list[str], +) -> None: wrapper_xml = _WRAPPER_TEMPLATE.format( model_name=f"robot_with_scene_{cache_key}", meshdir=str(meshdir), @@ -251,19 +289,10 @@ def bake_scene_mjcf( ) wrapper_path.write_text(wrapper_xml) logger.info(f"bake_scene_mjcf: wrote wrapper {wrapper_path}") - return wrapper_path def cli_main() -> None: - """``python -m dimos.mapping.usdz_to_mjcf [scale] [--view]``. - - Bake the wrapper, verify it loads, optionally open MuJoCo's native - viewer for visual inspection. ``--view`` works on macOS without - ``mjpython`` because we're invoking ``mujoco.viewer.launch`` from - the main thread of a fresh process — the issue dimos hits in - workers is that ``launch_passive`` in a *non-main* thread requires - mjpython. - """ + """Bake a wrapper, verify it loads, optionally open MuJoCo's native viewer.""" import sys args = list(sys.argv[1:]) @@ -273,7 +302,7 @@ def cli_main() -> None: args.remove("--view") if len(args) < 2: print( - "usage: python -m dimos.mapping.usdz_to_mjcf [scale] [--view]" + "usage: python -m dimos.mapping.scene_mesh_to_mjcf [scale] [--view]" ) sys.exit(2) scene = Path(args[0]) @@ -298,7 +327,7 @@ def cli_main() -> None: # toggles the rendering panel where you can switch geom groups # (group 3 = our scene collision hulls, group 1 = robot # visual mesh, group 0 = robot collision mesh). - print("\n→ launching MuJoCo viewer (press Esc / close window to exit)") + print("\nlaunching MuJoCo viewer (press Esc / close window to exit)") mujoco.viewer.launch(model) diff --git a/dimos/robot/all_blueprints.py b/dimos/robot/all_blueprints.py index cfae58530c..6783b0735e 100644 --- a/dimos/robot/all_blueprints.py +++ b/dimos/robot/all_blueprints.py @@ -180,6 +180,7 @@ "pgo": "dimos.navigation.nav_stack.modules.pgo.pgo.PGO", "phone-teleop-module": "dimos.teleop.phone.phone_teleop_module.PhoneTeleopModule", "pick-and-place-module": "dimos.manipulation.pick_and_place_module.PickAndPlaceModule", + "point-cloud-map-module": "dimos.mapping.pointcloud_map_module.PointCloudMapModule", "quest-teleop-module": "dimos.teleop.quest.quest_teleop_module.QuestTeleopModule", "real-sense-camera": "dimos.hardware.sensors.camera.realsense.camera.RealSenseCamera", "receiver-module": "dimos.utils.demo_image_encoding.ReceiverModule", @@ -202,6 +203,7 @@ "unitree-g1-skill-container": "dimos.robot.unitree.g1.skill_container.UnitreeG1SkillContainer", "unitree-skill-container": "dimos.robot.unitree.unitree_skill_container.UnitreeSkillContainer", "unity-bridge-module": "dimos.simulation.unity.module.UnityBridgeModule", + "viser-render-module": "dimos.visualization.viser.viser_render_module.ViserRenderModule", "vlm-agent": "dimos.agents.vlm_agent.VLMAgent", "vlm-stream-tester": "dimos.agents.vlm_stream_tester.VlmStreamTester", "voxel-grid-mapper": "dimos.mapping.voxels.VoxelGridMapper", diff --git a/dimos/simulation/engines/mujoco_sim_module.py b/dimos/simulation/engines/mujoco_sim_module.py index 3918ddd00d..4443c2d7d3 100644 --- a/dimos/simulation/engines/mujoco_sim_module.py +++ b/dimos/simulation/engines/mujoco_sim_module.py @@ -147,6 +147,14 @@ def __init__(self, **kwargs: Any) -> None: def _camera_enabled(self) -> bool: return self.config.enable_color or self.config.enable_depth or self.config.enable_pointcloud + @property + def _primary_camera_needed(self) -> bool: + return ( + self.config.enable_color + or self.config.enable_depth + or (self.config.enable_pointcloud and not self.config.lidar_camera_names) + ) + @property def _camera_link(self) -> str: return f"{self.config.camera_name}_link" @@ -188,17 +196,45 @@ def start(self) -> None: if not self.config.address: raise RuntimeError("MujocoSimModule: config.address (MJCF path) is required") - # SHM key — adapter derives the same key from the same MJCF path. shm_key = shm_key_from_path(self.config.address) self._shm = ManipShmWriter(shm_key) + camera_configs = self._make_camera_configs() - camera_configs: list[CameraConfig] = [] - primary_needed = ( - self.config.enable_color - or self.config.enable_depth - or (self.config.enable_pointcloud and not self.config.lidar_camera_names) + self._engine = MujocoEngine( + config_path=Path(self.config.address), + headless=self.config.headless, + cameras=camera_configs, + meshdir=self.config.meshdir, + on_before_step=self._apply_shm_commands, + on_after_step=self._after_step, + ) + + dof = self.config.dof + joint_names = list(self._engine.joint_names) + self._detect_gripper(joint_names) + + if not self._engine.connect(): + raise RuntimeError("MujocoSimModule: engine.connect() failed") + + self._shm.signal_ready(num_joints=len(joint_names)) + self._stop_event.clear() + + self._start_kinematic_base_control() + self._start_camera_publishers() + self._start_pointcloud_publisher() + + logger.info( + "MujocoSimModule started", + address=self.config.address, + dof=dof, + camera=self.config.camera_name, + camera_enabled=self._camera_enabled, + shm_key=shm_key, ) - if primary_needed: + + def _make_camera_configs(self) -> list[CameraConfig]: + camera_configs: list[CameraConfig] = [] + if self._primary_camera_needed: camera_configs.append( CameraConfig( name=self.config.camera_name, @@ -216,7 +252,7 @@ def start(self) -> None: lidar_scene_option.geomgroup[4] = 0 lidar_scene_option.geomgroup[5] = 0 for lidar_name in self.config.lidar_camera_names: - if lidar_name == self.config.camera_name and primary_needed: + if lidar_name == self.config.camera_name and self._primary_camera_needed: continue camera_configs.append( CameraConfig( @@ -227,87 +263,66 @@ def start(self) -> None: scene_option=lidar_scene_option, ) ) + return camera_configs - # Build engine with SHM hooks installed. Camera configs are optional: - # physics and SHM state exchange must keep working in headless/no-render - # deployments. - self._engine = MujocoEngine( - config_path=Path(self.config.address), - headless=self.config.headless, - cameras=camera_configs, - meshdir=self.config.meshdir, - on_before_step=self._apply_shm_commands, - on_after_step=self._publish_shm_state, - ) - - # Detect gripper (extra joint beyond dof). + def _detect_gripper(self, joint_names: list[str]) -> None: dof = self.config.dof - joint_names = list(self._engine.joint_names) - if len(joint_names) > dof: - ctrl_range = self._engine.get_actuator_ctrl_range(dof) - joint_range = self._engine.get_joint_range(dof) - if ctrl_range is None or joint_range is None: - raise ValueError(f"Gripper joint at index {dof} missing ctrl/joint range in MJCF") - self._gripper_idx = dof - self._gripper_ctrl_range = ctrl_range - self._gripper_joint_range = joint_range - logger.info( - "MujocoSimModule: gripper detected", - idx=dof, - ctrl_range=ctrl_range, - joint_range=joint_range, - ) - - # Start physics (sim thread spawned inside engine.connect()). - if not self._engine.connect(): - raise RuntimeError("MujocoSimModule: engine.connect() failed") - - self._shm.signal_ready(num_joints=len(joint_names)) - - self._stop_event.clear() + if len(joint_names) <= dof: + return + assert self._engine is not None + ctrl_range = self._engine.get_actuator_ctrl_range(dof) + joint_range = self._engine.get_joint_range(dof) + if ctrl_range is None or joint_range is None: + raise ValueError(f"Gripper joint at index {dof} missing ctrl/joint range in MJCF") + self._gripper_idx = dof + self._gripper_ctrl_range = ctrl_range + self._gripper_joint_range = joint_range + logger.info( + "MujocoSimModule: gripper detected", + idx=dof, + ctrl_range=ctrl_range, + joint_range=joint_range, + ) - if self.config.enable_kinematic_base_control: - if not self._engine.has_root_freejoint: - logger.warning("Kinematic base control requested, but MJCF has no freejoint root") - root_pose = self._engine.get_root_pose() - self._kinematic_base_z = None if root_pose is None else float(root_pose[0][2]) - self.register_disposable(Disposable(self.cmd_vel.subscribe(self._on_cmd_vel))) + def _start_kinematic_base_control(self) -> None: + if not self.config.enable_kinematic_base_control: + return + assert self._engine is not None + if not self._engine.has_root_freejoint: + logger.warning("Kinematic base control requested, but MJCF has no freejoint root") + root_pose = self._engine.get_root_pose() + self._kinematic_base_z = None if root_pose is None else float(root_pose[0][2]) + self.register_disposable(Disposable(self.cmd_vel.subscribe(self._on_cmd_vel))) + + def _start_camera_publishers(self) -> None: + if not self._primary_camera_needed: + return + self._build_camera_info() - if primary_needed: - # Camera intrinsics. - self._build_camera_info() + self._publish_thread = threading.Thread( + target=self._publish_loop, daemon=True, name="MujocoSimPublish" + ) + self._publish_thread.start() - self._publish_thread = threading.Thread( - target=self._publish_loop, daemon=True, name="MujocoSimPublish" - ) - self._publish_thread.start() - - # Periodic camera_info publishing. - interval_sec = 1.0 / self.config.camera_info_fps - self.register_disposable( - rx.interval(interval_sec).subscribe( - on_next=lambda _: self._publish_camera_info(), - on_error=lambda e: logger.error("CameraInfo publish error", error=str(e)), - ) + interval_sec = 1.0 / self.config.camera_info_fps + self.register_disposable( + rx.interval(interval_sec).subscribe( + on_next=lambda _: self._publish_camera_info(), + on_error=lambda e: logger.error("CameraInfo publish error", error=str(e)), ) + ) - # Optional pointcloud generation. - if self.config.enable_pointcloud and (primary_needed or self.config.lidar_camera_names): - pc_interval = 1.0 / self.config.pointcloud_fps - self.register_disposable( - rx.interval(pc_interval).subscribe( - on_next=lambda _: self._generate_pointcloud(), - on_error=lambda e: logger.error("Pointcloud error", error=str(e)), - ) + def _start_pointcloud_publisher(self) -> None: + if not self.config.enable_pointcloud: + return + if not (self._primary_camera_needed or self.config.lidar_camera_names): + return + pc_interval = 1.0 / self.config.pointcloud_fps + self.register_disposable( + rx.interval(pc_interval).subscribe( + on_next=lambda _: self._generate_pointcloud(), + on_error=lambda e: logger.error("Pointcloud error", error=str(e)), ) - - logger.info( - "MujocoSimModule started", - address=self.config.address, - dof=dof, - camera=self.config.camera_name, - camera_enabled=self._camera_enabled, - shm_key=shm_key, ) @rpc @@ -382,10 +397,11 @@ def _apply_cmd_vel(self, engine: MujocoEngine) -> None: fixed_z=self._kinematic_base_z, ) - def _publish_shm_state(self, engine: MujocoEngine) -> None: - """Post-step hook: publish joint state to SHM.""" + def _after_step(self, engine: MujocoEngine) -> None: self._apply_cmd_vel(engine) + self._publish_state(engine) + def _publish_state(self, engine: MujocoEngine) -> None: shm = self._shm if shm is None: return diff --git a/dimos/simulation/mujoco_scene_playground.py b/dimos/simulation/mujoco_scene_playground.py index c15ae9de03..c55aa5f5db 100644 --- a/dimos/simulation/mujoco_scene_playground.py +++ b/dimos/simulation/mujoco_scene_playground.py @@ -59,7 +59,9 @@ def _command_center_blueprints() -> list[Blueprint]: return [] try: from dimos.web.websocket_vis.websocket_vis_module import WebsocketVisModule - except ModuleNotFoundError: + except ModuleNotFoundError as exc: + if exc.name not in {"socketio", "fastapi", "uvicorn", "starlette"}: + raise import logging logging.getLogger(__name__).warning( @@ -124,7 +126,7 @@ def _command_center_blueprints() -> list[Blueprint]: if _scene_mesh_path and _scene_mesh_collision: try: from dimos.mapping.mesh_scene import SceneMeshAlignment - from dimos.mapping.usdz_to_mjcf import bake_scene_mjcf + from dimos.mapping.scene_mesh_to_mjcf import bake_scene_mjcf _sim_mjcf_path = str( bake_scene_mjcf( @@ -203,7 +205,6 @@ def _command_center_blueprints() -> list[Blueprint]: ("global_costmap", OccupancyGrid): LCMTransport("/global_costmap", OccupancyGrid), ("path", PathMsg): LCMTransport("/nav_path", PathMsg), ("clicked_point", PointStamped): LCMTransport("/clicked_point", PointStamped), - ("goal", PointStamped): LCMTransport("/goal", PointStamped), ("goal_request", PoseStamped): LCMTransport("/goal_request", PoseStamped), ("stop_movement", Bool): LCMTransport("/stop_movement", Bool), ("point_goal", PointStamped): LCMTransport("/point_goal", PointStamped), diff --git a/dimos/visualization/viser/viser_render_module.py b/dimos/visualization/viser/viser_render_module.py index 04e24454d8..db0f7a333a 100644 --- a/dimos/visualization/viser/viser_render_module.py +++ b/dimos/visualization/viser/viser_render_module.py @@ -53,6 +53,7 @@ from dimos.visualization.viser.splat import SplatAlignment, load_splat logger = setup_logger() +_WORLD_FRAME = "world" def _compose_scene_mesh_wxyz( @@ -197,20 +198,36 @@ def start(self) -> None: import viser + splat = self._load_splat() + self._load_robot_meshes() + self._server = viser.ViserServer(host="0.0.0.0", port=self._port) + self._configure_server() + logger.info(f"Viser viewer: http://localhost:{self._port}/") + + self._add_splat(splat) + self._add_scene_mesh_if_configured() + self._add_layer_controls() + self._add_robot_meshes() + self._add_camera_frustum() + self._add_click_controls() + self._subscribe_inputs() + self._start_render_thread() + + def _load_splat(self) -> Any | None: alignment = ( SplatAlignment.from_yaml(self._alignment_yaml) if self._alignment_yaml and self._alignment_yaml.exists() else SplatAlignment() ) - - if self._splat_path is not None: - logger.info(f"Viser: loading splat from {self._splat_path}") - splat = load_splat(self._splat_path, alignment=alignment) - logger.info(f"Viser: loaded {len(splat.centers)} Gaussians") - else: - splat = None + if self._splat_path is None: logger.info("Viser: splat disabled (no splat_path provided)") + return None + logger.info(f"Viser: loading splat from {self._splat_path}") + splat = load_splat(self._splat_path, alignment=alignment) + logger.info(f"Viser: loaded {len(splat.centers)} Gaussians") + return splat + def _load_robot_meshes(self) -> None: logger.info(f"Viser: loading robot meshes from {self._mjcf_path}") self._robot = load_robot_meshes(self._mjcf_path, meshdir=self._mjcf_meshdir) logger.info( @@ -218,10 +235,8 @@ def start(self) -> None: f"{len(self._robot.body_names)} bodies" ) - self._server = viser.ViserServer(host="0.0.0.0", port=self._port) - # Strip the floating control panel down to just a collapse button — - # the viewer is render-only, no GUI controls live in the panel, and - # viser exposes no API to hide the panel entirely. + def _configure_server(self) -> None: + assert self._server is not None self._server.gui.set_panel_label(None) self._server.gui.configure_theme( control_layout="collapsible", @@ -229,33 +244,29 @@ def start(self) -> None: show_share_button=False, dark_mode=True, ) - logger.info(f"Viser viewer: http://localhost:{self._port}/") - if splat is not None: - self._splat_data = splat - self._splat_handle = self._server.scene.add_gaussian_splats( - "/splat", - centers=splat.centers, - covariances=splat.covariances, - rgbs=splat.rgbs, - opacities=splat.opacities, - ) + def _add_splat(self, splat: Any | None) -> None: + if splat is None: + return + assert self._server is not None + self._splat_data = splat + self._splat_handle = self._server.scene.add_gaussian_splats( + "/splat", + centers=splat.centers, + covariances=splat.covariances, + rgbs=splat.rgbs, + opacities=splat.opacities, + ) - # Optional scene mesh (.usdz / .glb / etc.) — drawn in the same - # world frame as the robot. ``MeshCameraModule`` ray-casts the - # same mesh to feed the head-camera RGB topic. + def _add_scene_mesh_if_configured(self) -> None: if self._scene_mesh_path is not None and self._scene_mesh_path.exists(): try: self._add_scene_mesh() except Exception as e: logger.warning(f"Viser: scene mesh load failed: {e}") - # Three independent layer toggles: Splat / Mesh / Lidar. - # Each checkbox only appears when the corresponding backdrop - # actually exists in this run (no point in a "Show splat" toggle - # when no splat was loaded). Combined, they cover every subset - # — splat-only, mesh-only, lidar-only, splat+mesh, splat+lidar, - # mesh+lidar, all three. + def _add_layer_controls(self) -> None: + assert self._server is not None if self._splat_handle is not None: self._splat_checkbox = self._server.gui.add_checkbox( "Show splat", initial_value=self._splat_visible @@ -311,8 +322,9 @@ def _on_lidar_toggle(_: Any) -> None: if self._lidar_handle is not None: self._lidar_handle.visible = self._lidar_visible - # One frame per body; meshes are added as children so they - # follow when the body frame moves. + def _add_robot_meshes(self) -> None: + assert self._server is not None + assert self._robot is not None for body_id, body_name in enumerate(self._robot.body_names): self._body_frames[body_id] = self._server.scene.add_frame( f"/robot/{body_name}", @@ -334,9 +346,9 @@ def _on_lidar_toggle(_: Any) -> None: wxyz=tuple(geom.local_wxyz), ) - # Camera frustum overlay — shows where a robot-mounted RGB sensor - # would look from. Stays None if the configured mount body - # isn't in this MJCF (e.g. swap to a robot without head_link). + def _add_camera_frustum(self) -> None: + assert self._server is not None + assert self._robot is not None if self._camera_spec is not None: cam_body_id = mujoco.mj_name2id( self._robot.model, mujoco.mjtObj.mjOBJ_BODY, self._camera_spec.body_name @@ -356,10 +368,8 @@ def _on_lidar_toggle(_: Any) -> None: color=self._camera_spec.frustum_color, ) - # Click-to-navigate. We arm a one-shot scene click callback when - # the user presses "Set nav goal", because viser disables camera - # orbit while the click callback is registered (App.tsx:514) — so - # leaving it always-on would break LMB orbit globally. + def _add_click_controls(self) -> None: + assert self._server is not None nav_goal_button = self._server.gui.add_button("Set nav goal") @nav_goal_button.on_click @@ -379,11 +389,6 @@ def _rearm_button() -> None: nav_goal_button.disabled = False nav_goal_button.label = "Set nav goal" - # Click-to-point. Same one-shot-callback pattern; the click ray - # is intersected with the scene-mesh raycaster if one is loaded, - # else with an eye-height (z=1.0 m) horizontal plane so pointing - # works even when no scene mesh is configured. Published on - # /point_goal; G1ManipulationModule subscribes and runs point_at. point_goal_button = self._server.gui.add_button("Set point goal") @point_goal_button.on_click @@ -403,6 +408,7 @@ def _rearm_point_button() -> None: point_goal_button.disabled = False point_goal_button.label = "Set point goal" + def _subscribe_inputs(self) -> None: try: unsub = self.path.subscribe(self._on_path) self.register_disposable(Disposable(unsub)) @@ -427,6 +433,7 @@ def _rearm_point_button() -> None: except Exception as e: logger.warning(f"Viser: odom subscribe failed: {e}") + def _start_render_thread(self) -> None: self._render_thread = threading.Thread( target=self._render_loop, name="viser-render", daemon=True ) @@ -561,7 +568,7 @@ def _handle_floor_click(self, event: Any) -> None: except Exception as e: logger.debug(f"Viser nav-goal marker failed: {e}") - point = PointStamped(x=float(x), y=float(y), z=0.0, ts=time.time(), frame_id="map") + point = PointStamped(x=float(x), y=float(y), z=0.0, ts=time.time(), frame_id=_WORLD_FRAME) self.clicked_point.publish(point) logger.info(f"Viser nav-goal: published clicked_point=({x:.3f}, {y:.3f})") @@ -618,7 +625,9 @@ def _handle_point_goal_click(self, event: Any) -> None: except Exception as e: logger.debug(f"Viser point-goal marker failed: {e}") - point = PointStamped(x=float(x), y=float(y), z=float(z), ts=time.time(), frame_id="map") + point = PointStamped( + x=float(x), y=float(y), z=float(z), ts=time.time(), frame_id=_WORLD_FRAME + ) self.point_goal.publish(point) logger.info(f"Viser point-goal: published point_goal=({x:.3f}, {y:.3f}, {z:.3f})") diff --git a/pyproject.toml b/pyproject.toml index 389b74b584..613df3cf1a 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -304,6 +304,7 @@ sim = [ "mujoco>=3.3.4", "playground>=0.0.5", "pygame>=2.6.1", + "trimesh", "usd-core>=24.0", ] diff --git a/uv.lock b/uv.lock index b88fe316ed..8dde4a6de5 100644 --- a/uv.lock +++ b/uv.lock @@ -2191,6 +2191,7 @@ sim = [ { name = "mujoco" }, { name = "playground" }, { name = "pygame" }, + { name = "trimesh" }, { name = "usd-core" }, ] unitree = [ @@ -2252,6 +2253,7 @@ viz = [ { name = "playground" }, { name = "plyfile" }, { name = "pygame" }, + { name = "trimesh" }, { name = "usd-core" }, { name = "viser" }, ] @@ -2413,6 +2415,7 @@ requires-dist = [ { name = "torchreid", marker = "extra == 'misc'", specifier = "==0.2.5" }, { name = "transformers", extras = ["torch"], marker = "extra == 'perception'", specifier = ">=4.53.0,<4.54" }, { name = "trimesh", marker = "extra == 'manipulation'" }, + { name = "trimesh", marker = "extra == 'sim'" }, { name = "typeguard", marker = "extra == 'misc'" }, { name = "typer", specifier = ">=0.19.2,<1" }, { name = "typer", marker = "extra == 'docker'", specifier = ">=0.19.2,<1" }, From 559f25cc544c6c6f55a0af963959598a6afc209c Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 07:01:45 +0200 Subject: [PATCH 03/30] Clean up MuJoCo mapping and teleop --- dimos/mapping/pointcloud_map_module.py | 77 ------------------- .../movement_manager/movement_manager.py | 22 +++++- .../movement_manager/test_movement_manager.py | 23 ++++++ dimos/robot/all_blueprints.py | 1 - dimos/simulation/mujoco_scene_playground.py | 5 +- 5 files changed, 44 insertions(+), 84 deletions(-) delete mode 100644 dimos/mapping/pointcloud_map_module.py diff --git a/dimos/mapping/pointcloud_map_module.py b/dimos/mapping/pointcloud_map_module.py deleted file mode 100644 index b0e050e7ec..0000000000 --- a/dimos/mapping/pointcloud_map_module.py +++ /dev/null @@ -1,77 +0,0 @@ -# Copyright 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. - -"""Generic pointcloud map module backed by DimOS's existing accumulator.""" - -from __future__ import annotations - -import time -from typing import Any - -from reactivex import interval -from reactivex.disposable import Disposable - -from dimos.core.core import rpc -from dimos.core.module import Module, ModuleConfig -from dimos.core.stream import In, Out -from dimos.mapping.pointclouds.accumulators.general import GeneralPointCloudAccumulator -from dimos.msgs.sensor_msgs.PointCloud2 import PointCloud2 - - -class PointCloudMapConfig(ModuleConfig): - voxel_size: float = 0.05 - publish_interval: float = 0.5 - - -class PointCloudMapModule(Module): - """Accumulate lidar pointclouds and publish a global map.""" - - config: PointCloudMapConfig - - lidar: In[PointCloud2] - global_map: Out[PointCloud2] - - def __init__(self, **kwargs: Any) -> None: - super().__init__(**kwargs) - self._accumulator = GeneralPointCloudAccumulator( - voxel_size=self.config.voxel_size, - global_config=self.config.g, - ) - - @rpc - def start(self) -> None: - super().start() - self.register_disposable(Disposable(self.lidar.subscribe(self._add_frame))) - self.register_disposable( - interval(self.config.publish_interval).subscribe(lambda _: self._publish()) - ) - - @rpc - def stop(self) -> None: - super().stop() - - def _add_frame(self, msg: PointCloud2) -> None: - self._accumulator.add(msg.pointcloud) - - def _publish(self) -> None: - self.global_map.publish( - PointCloud2( - pointcloud=self._accumulator.get_point_cloud(), - ts=time.time(), - frame_id="world", - ) - ) - - -__all__ = ["PointCloudMapConfig", "PointCloudMapModule"] diff --git a/dimos/navigation/movement_manager/movement_manager.py b/dimos/navigation/movement_manager/movement_manager.py index ed12dc93ac..330498b239 100644 --- a/dimos/navigation/movement_manager/movement_manager.py +++ b/dimos/navigation/movement_manager/movement_manager.py @@ -41,6 +41,7 @@ # without this you can (basically) click into infinity in rerun (not good for the planner) MAX_CLICK_HORIZONTAL_M = 500.0 MAX_CLICK_VERTICAL_M = 50.0 +TELEOP_EPS = 1e-6 class MovementManagerConfig(ModuleConfig): @@ -120,11 +121,26 @@ def _on_nav(self, msg: Twist) -> None: self.cmd_vel.publish(msg) def _on_teleop(self, msg: Twist) -> None: + is_zero = ( + abs(msg.linear.x) < TELEOP_EPS + and abs(msg.linear.y) < TELEOP_EPS + and abs(msg.linear.z) < TELEOP_EPS + and abs(msg.angular.x) < TELEOP_EPS + and abs(msg.angular.y) < TELEOP_EPS + and abs(msg.angular.z) < TELEOP_EPS + ) + with self._lock: - self._teleop_active = True - self._last_teleop_time = time.monotonic() + was_active = self._teleop_active + if is_zero: + if not was_active: + return + else: + self._teleop_active = True + self._last_teleop_time = time.monotonic() - self._cancel_goal() + if not is_zero and not was_active: + self._cancel_goal() scale = self.config.tele_cmd_vel_scaling scaled = Twist( diff --git a/dimos/navigation/movement_manager/test_movement_manager.py b/dimos/navigation/movement_manager/test_movement_manager.py index e266ad3e98..e065a48c32 100644 --- a/dimos/navigation/movement_manager/test_movement_manager.py +++ b/dimos/navigation/movement_manager/test_movement_manager.py @@ -103,6 +103,29 @@ def test_nav_resumes_after_cooldown(manager_and_captured): assert len(captured.cmd_vel) == cmd_count_before + 1 +def test_idle_teleop_does_not_cancel_nav(manager_and_captured): + """Idle command-center updates should not spam stop_movement.""" + manager, captured = manager_and_captured + + manager._on_teleop(_twist()) + manager._on_teleop(_twist()) + + assert captured.stop_movement == [] + assert captured.cmd_vel == [] + + +def test_continuous_teleop_cancels_once(manager_and_captured): + """Holding WASD should not repeatedly cancel an already-cancelled goal.""" + manager, captured = manager_and_captured + + manager._on_teleop(_twist(lx=0.3)) + manager._on_teleop(_twist(lx=0.3)) + manager._on_teleop(_twist()) + + assert len(captured.stop_movement) == 1 + assert len(captured.cmd_vel) == 3 + + def test_valid_click_publishes_goal(manager_and_captured): """A valid click should publish to both goal and way_point.""" manager, captured = manager_and_captured diff --git a/dimos/robot/all_blueprints.py b/dimos/robot/all_blueprints.py index 6783b0735e..a978f4c67d 100644 --- a/dimos/robot/all_blueprints.py +++ b/dimos/robot/all_blueprints.py @@ -180,7 +180,6 @@ "pgo": "dimos.navigation.nav_stack.modules.pgo.pgo.PGO", "phone-teleop-module": "dimos.teleop.phone.phone_teleop_module.PhoneTeleopModule", "pick-and-place-module": "dimos.manipulation.pick_and_place_module.PickAndPlaceModule", - "point-cloud-map-module": "dimos.mapping.pointcloud_map_module.PointCloudMapModule", "quest-teleop-module": "dimos.teleop.quest.quest_teleop_module.QuestTeleopModule", "real-sense-camera": "dimos.hardware.sensors.camera.realsense.camera.RealSenseCamera", "receiver-module": "dimos.utils.demo_image_encoding.ReceiverModule", diff --git a/dimos/simulation/mujoco_scene_playground.py b/dimos/simulation/mujoco_scene_playground.py index c55aa5f5db..ddc0156881 100644 --- a/dimos/simulation/mujoco_scene_playground.py +++ b/dimos/simulation/mujoco_scene_playground.py @@ -25,7 +25,7 @@ from dimos.core.coordination.blueprints import Blueprint, autoconnect from dimos.core.transport import LCMTransport from dimos.mapping.costmapper import CostMapper -from dimos.mapping.pointcloud_map_module import PointCloudMapModule +from dimos.mapping.voxels import VoxelGridMapper from dimos.msgs.geometry_msgs.PointStamped import PointStamped from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped from dimos.msgs.geometry_msgs.Twist import Twist @@ -171,9 +171,8 @@ def _command_center_blueprints() -> list[Blueprint]: not in {"", "0"}, ), MovementManager.blueprint(), - PointCloudMapModule.blueprint( + VoxelGridMapper.blueprint( voxel_size=_env_float("DIMOS_GLOBAL_MAP_VOXEL_SIZE", 0.05), - publish_interval=_env_float("DIMOS_GLOBAL_MAP_PUBLISH_INTERVAL", 0.5), ), CostMapper.blueprint(), ReplanningAStarPlanner.blueprint(), From f4c63692e42e52c20a4a02631be1a16a9dc1c803 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 07:08:49 +0200 Subject: [PATCH 04/30] Remove Viser from MuJoCo sim PR --- dimos/mapping/mesh_scene.py | 16 +- dimos/mapping/scene_mesh_to_mjcf.py | 5 +- dimos/robot/all_blueprints.py | 1 - dimos/simulation/mujoco_scene_playground.py | 34 +- dimos/visualization/viser/camera.py | 207 ----- dimos/visualization/viser/robot_meshes.py | 230 ------ dimos/visualization/viser/splat.py | 217 ----- .../viser/viser_render_module.py | 774 ------------------ pyproject.toml | 6 - uv.lock | 447 +--------- 10 files changed, 10 insertions(+), 1927 deletions(-) delete mode 100644 dimos/visualization/viser/camera.py delete mode 100644 dimos/visualization/viser/robot_meshes.py delete mode 100644 dimos/visualization/viser/splat.py delete mode 100644 dimos/visualization/viser/viser_render_module.py diff --git a/dimos/mapping/mesh_scene.py b/dimos/mapping/mesh_scene.py index d85e0b5001..bc328dd2c0 100644 --- a/dimos/mapping/mesh_scene.py +++ b/dimos/mapping/mesh_scene.py @@ -189,8 +189,8 @@ def _load_usd_mesh(path: Path) -> o3d.geometry.TriangleMesh: """Walk every Mesh prim in a USD stage and concatenate to one o3d mesh. Also extracts per-vertex colors from ``primvars:displayColor`` when - present so downstream consumers (viser) can render textured-looking - Sketchfab exports without having to chase materials/textures. + present so downstream consumers can render textured-looking Sketchfab + exports without having to chase materials/textures. """ try: from pxr import Usd, UsdGeom @@ -299,13 +299,11 @@ def load_scene_mesh( if suffix in {".usdz", ".usd", ".usdc", ".usda"}: mesh = _load_usd_mesh(path) elif suffix in {".glb", ".gltf"}: - # GEOMETRY-ONLY GLB load. Used by floor-z probing and ``MeshCameraModule`` - # ray-casting — neither needs PBR materials. The Viser viewer takes the - # GLB-native path (``add_glb`` from raw bytes) so it doesn't go through - # here. ``trimesh.load(path, force="mesh")`` would flatten the scene by - # decompressing every embedded texture and sampling per-vertex colors — - # for a scene with hundreds of 4K PBR textures (~895 MP total in dimos's - # office mesh) that allocates ~10 GB transiently and OOMs 32 GB boxes. + # GEOMETRY-ONLY GLB load. Used by floor-z probing and ray-casting; + # it does not need PBR materials. ``trimesh.load(path, force="mesh")`` + # would flatten the scene by decompressing every embedded texture and + # sampling per-vertex colors. For a scene with hundreds of 4K PBR + # textures, that allocates ~10 GB transiently and OOMs 32 GB boxes. # We open in Scene mode (no flattening, no texture decode), walk the # instance graph applying each instance's world transform, and emit a # single concatenated mesh — peak stays under ~1 GB. diff --git a/dimos/mapping/scene_mesh_to_mjcf.py b/dimos/mapping/scene_mesh_to_mjcf.py index b989fdd59b..c9f77f6fd2 100644 --- a/dimos/mapping/scene_mesh_to_mjcf.py +++ b/dimos/mapping/scene_mesh_to_mjcf.py @@ -82,10 +82,7 @@ def bake_scene_mjcf( robot_mjcf_path: the base robot MJCF the wrapper will ````. alignment: scale / translation / rotation / y-up swap to bake - into the OBJ before MuJoCo sees it. Authoritative for all - three views (MuJoCo physics, viser, mesh camera); the - blueprint passes the same ``SceneMeshAlignment`` to each - so the world frames agree to the millimeter. + into the OBJ before MuJoCo sees it. meshdir: directory MuJoCo should resolve unqualified mesh filenames against. ``None`` uses the robot MJCF's parent directory. Blueprints for robot assets stored elsewhere diff --git a/dimos/robot/all_blueprints.py b/dimos/robot/all_blueprints.py index a978f4c67d..cfae58530c 100644 --- a/dimos/robot/all_blueprints.py +++ b/dimos/robot/all_blueprints.py @@ -202,7 +202,6 @@ "unitree-g1-skill-container": "dimos.robot.unitree.g1.skill_container.UnitreeG1SkillContainer", "unitree-skill-container": "dimos.robot.unitree.unitree_skill_container.UnitreeSkillContainer", "unity-bridge-module": "dimos.simulation.unity.module.UnityBridgeModule", - "viser-render-module": "dimos.visualization.viser.viser_render_module.ViserRenderModule", "vlm-agent": "dimos.agents.vlm_agent.VLMAgent", "vlm-stream-tester": "dimos.agents.vlm_stream_tester.VlmStreamTester", "voxel-grid-mapper": "dimos.mapping.voxels.VoxelGridMapper", diff --git a/dimos/simulation/mujoco_scene_playground.py b/dimos/simulation/mujoco_scene_playground.py index ddc0156881..1dbacd4a56 100644 --- a/dimos/simulation/mujoco_scene_playground.py +++ b/dimos/simulation/mujoco_scene_playground.py @@ -12,13 +12,12 @@ # See the License for the specific language governing permissions and # limitations under the License. -"""MuJoCo scene playground with optional Viser mesh/splat visualization.""" +"""MuJoCo scene playground with optional mesh collision.""" from __future__ import annotations import os from pathlib import Path -import tempfile from dimos_lcm.std_msgs import Bool # type: ignore[import-untyped] @@ -36,7 +35,6 @@ from dimos.navigation.movement_manager.movement_manager import MovementManager from dimos.navigation.replanning_a_star.module import ReplanningAStarPlanner from dimos.simulation.engines.mujoco_sim_module import MujocoSimModule -from dimos.visualization.viser.viser_render_module import ViserRenderModule def _env_float(name: str, default: float) -> float: @@ -75,7 +73,6 @@ def _command_center_blueprints() -> list[Blueprint]: _default_mjcf = Path("data/mujoco_sim/g1_gear_wbc.xml") _default_scene_mesh = Path("data/dimos_office_mesh/dimos_office_mesh.glb") -_default_splat = Path("data/dimos_office/dimos_office.ply") _mjcf_path = os.environ.get("DIMOS_MJCF_PATH") or str(_default_mjcf) _mjcf_meshdir = os.environ.get("DIMOS_MJCF_MESHDIR") if _mjcf_meshdir is None and Path(_mjcf_path) == _default_mjcf: @@ -99,21 +96,6 @@ def _command_center_blueprints() -> list[Blueprint]: _scene_mesh_rotation = _env_xyz("DIMOS_SCENE_MESH_ROTATION_ZYX_DEG", (0.0, 0.0, 0.0)) _scene_mesh_translation = _env_xyz("DIMOS_SCENE_MESH_TRANSLATION", (0.0, 0.0, 0.0)) _scene_mesh_collision = os.environ.get("DIMOS_SCENE_MESH_COLLISION", "1") not in {"", "0"} -_splat_path_override = os.environ.get("DIMOS_SPLAT_PATH") or None -_splat_path = _splat_path_override or ( - str(_default_splat) if _scene_mesh_path_override is None and _default_splat.exists() else None -) -_splat_alignment_yaml = os.environ.get("DIMOS_SPLAT_ALIGNMENT") -if _splat_alignment_yaml is None and _splat_path == str(_default_splat): - _office_splat_yaml = Path(tempfile.gettempdir()) / "dimos_office_to_artist_mesh.yaml" - _office_splat_yaml.write_text( - "# Maps the original Y-up dimos_office.ply into the artist mesh frame.\n" - f"scale: {_scene_mesh_scale}\n" - f"translation: [0.0, 0.0, {0.7734 * _scene_mesh_scale}]\n" - "rotation_zyx: [164.6633, -0.0865, -95.4786]\n" - "y_up: false\n" - ) - _splat_alignment_yaml = str(_office_splat_yaml) _enable_depth_cloud = os.environ.get("DIMOS_ENABLE_DEPTH_CLOUD", "0").lower() in { "1", "true", @@ -176,19 +158,6 @@ def _command_center_blueprints() -> list[Blueprint]: ), CostMapper.blueprint(), ReplanningAStarPlanner.blueprint(), - ViserRenderModule.blueprint( - splat_path=_splat_path, - mjcf_path=_sim_mjcf_path, - mjcf_meshdir=_mjcf_meshdir, - port=int(os.environ.get("DIMOS_VISER_PORT", "8082")), - alignment_yaml=_splat_alignment_yaml, - scene_mesh_path=_scene_mesh_path, - scene_mesh_scale=_scene_mesh_scale, - scene_mesh_translation=_scene_mesh_translation, - scene_mesh_rotation_zyx_deg=_scene_mesh_rotation, - scene_mesh_y_up=_scene_mesh_y_up, - pointcloud_point_size=_env_float("DIMOS_POINTCLOUD_POINT_SIZE", 0.04), - ), *_command_center_blueprints(), ).transports( { @@ -200,7 +169,6 @@ def _command_center_blueprints() -> list[Blueprint]: ("pointcloud", PointCloud2): LCMTransport("/lidar", PointCloud2), ("lidar", PointCloud2): LCMTransport("/lidar", PointCloud2), ("global_map", PointCloud2): LCMTransport("/global_map", PointCloud2), - ("pointcloud_overlay", PointCloud2): LCMTransport("/global_map", PointCloud2), ("global_costmap", OccupancyGrid): LCMTransport("/global_costmap", OccupancyGrid), ("path", PathMsg): LCMTransport("/nav_path", PathMsg), ("clicked_point", PointStamped): LCMTransport("/clicked_point", PointStamped), diff --git a/dimos/visualization/viser/camera.py b/dimos/visualization/viser/camera.py deleted file mode 100644 index 296b7f3be3..0000000000 --- a/dimos/visualization/viser/camera.py +++ /dev/null @@ -1,207 +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. - -"""Robot-mounted camera spec + frustum overlay helpers. - -A ``CameraSpec`` is a fixed-mount RGB camera attached to a body in the -robot MJCF. It carries everything a renderer (or a frustum overlay) -needs: the parent body name, a local mount transform in the body -frame, image-plane intrinsics, and an output resolution. - -Conventions: - * Mount quaternion is in **wxyz** order, expressing the camera's - optical frame in the body frame: image-x = right, image-y = down, - image-z = forward. This matches OpenCV / viser camera conventions. - * Robot body frame in the bundled G1 MJCF is the standard ROS one: - body-x = forward, body-y = left, body-z = up. - -The default ``g1_d435_default()`` mounts a RealSense D435i color -sensor on ``head_link`` looking forward — a sensible "robot's eye -view" for office walking. Override the spec to pitch down for -manipulation, mount on torso, swap to a different sensor, etc. -""" - -from __future__ import annotations - -from dataclasses import dataclass - -import mujoco -import numpy as np - - -@dataclass(frozen=True) -class CameraSpec: - """Fixed-mount RGB camera attached to a robot body.""" - - body_name: str - """MJCF body name to mount on (e.g. 'head_link', 'torso_link').""" - - mount_pos: tuple[float, float, float] - """Camera optical-center position in the parent body's local frame, meters.""" - - mount_wxyz: tuple[float, float, float, float] - """Quaternion (w, x, y, z) mapping body frame to camera optical frame.""" - - vfov_deg: float - """Vertical field of view, degrees. Horizontal FOV is derived from aspect.""" - - width: int - """Image width, pixels.""" - - height: int - """Image height, pixels.""" - - frustum_scale: float = 0.15 - """Frustum wireframe size in meters when overlaid in viser.""" - - frustum_color: tuple[int, int, int] = (50, 255, 100) - """RGB 0..255 for the frustum overlay. Lime by default.""" - - @property - def aspect(self) -> float: - return self.width / self.height - - def focal_pixels(self) -> float: - """Focal length in pixels, derived from VFOV. Square pixels assumed.""" - return 0.5 * self.height / float(np.tan(np.radians(self.vfov_deg) * 0.5)) - - def fx(self) -> float: - return self.focal_pixels() - - def fy(self) -> float: - return self.focal_pixels() - - def cx(self) -> float: - return 0.5 * self.width - - def cy(self) -> float: - return 0.5 * self.height - - -def _quat_from_matrix(R: np.ndarray) -> tuple[float, float, float, float]: - """3x3 rotation matrix -> (w, x, y, z) via mujoco. Stable, no scipy dep.""" - flat = np.asarray(R, dtype=np.float64).flatten() - out = np.zeros(4, dtype=np.float64) - mujoco.mju_mat2Quat(out, flat) - return (float(out[0]), float(out[1]), float(out[2]), float(out[3])) - - -def g1_d435_default() -> CameraSpec: - """RealSense D435i color sensor mounted on G1 torso, pitched down. - - Mount: on ``torso_link``. Offset - ``(0.0576, 0.0325, 0.4299)`` matches the URDF d435_joint position - (Intel-spec RGB sensor offset already baked in). Optical axis - pitched down by ~47.6° (0.831 rad) — same value Matrix uses on - real G1 deployments — so the camera sees the workspace in front - of the chest, not the horizon. This is what manipulation / - object registration consume; pick-and-place needs a downward - view of the table. - - Intrinsics are Intel datasheet for D435i color - (HFOV 69.4°, VFOV 42.5°), binned to 320x180. - """ - # Body frame : +x forward, +y left, +z up - # Image frame : +x right, +y down, +z forward - # body_R_image = horizontal_forward @ R_pitch_down(47.6°) - pitch_rad = 0.831 - c, s = np.cos(pitch_rad), np.sin(pitch_rad) - horizontal = np.array( - [ - [0.0, 0.0, 1.0], - [-1.0, 0.0, 0.0], - [0.0, -1.0, 0.0], - ], - dtype=np.float64, - ) - pitch_down = np.array( - [[1.0, 0.0, 0.0], [0.0, c, s], [0.0, -s, c]], - dtype=np.float64, - ) - body_R_image = horizontal @ pitch_down - return CameraSpec( - body_name="torso_link", - mount_pos=(0.0576, 0.0325, 0.4299), - mount_wxyz=_quat_from_matrix(body_R_image), - vfov_deg=42.5, - width=320, - height=180, - ) - - -def g1_d435_forward() -> CameraSpec: - """RealSense D435i mounted forward at G1 eye level (no pitch). - - Alternate to ``g1_d435_default`` for when the agent wants a - "robot's eye view" of the room — looking at the horizon, walls, - people — instead of the manipulation-oriented downward pitch. - Useful for navigation / exploration / scene understanding tasks - that don't care about the table workspace in front of the chest. - - Mount: on ``torso_link`` at ``(0.10, 0.0, 0.40)`` — 10 cm forward - of the torso origin and 40 cm up, roughly at eye level just past - the forehead mesh. Optical axis horizontal. - - Intrinsics are Intel datasheet for D435i color - (HFOV 69.4°, VFOV 42.5°), binned to 320x180. - """ - body_R_image = np.array( - [ - [0.0, 0.0, 1.0], - [-1.0, 0.0, 0.0], - [0.0, -1.0, 0.0], - ], - dtype=np.float64, - ) - return CameraSpec( - body_name="torso_link", - mount_pos=(0.10, 0.0, 0.40), - mount_wxyz=_quat_from_matrix(body_R_image), - vfov_deg=42.5, - width=320, - height=180, - ) - - -def world_pose( - body_world_pos: np.ndarray, - body_world_wxyz: np.ndarray, - spec: CameraSpec, -) -> tuple[np.ndarray, np.ndarray]: - """Compose the camera's world pose from its parent body's world pose. - - Returns ``(world_pos (3,), world_wxyz (4,))`` ready to feed straight - into viser's ``add_camera_frustum`` (which uses the same - +Z-forward / +Y-down convention the camera spec is in). - """ - # World rotation: q_world_image = q_world_body * q_body_image - out_quat = np.zeros(4, dtype=np.float64) - mujoco.mju_mulQuat( - out_quat, - np.asarray(body_world_wxyz, dtype=np.float64), - np.asarray(spec.mount_wxyz, dtype=np.float64), - ) - - # World translation: p_world_image = p_world_body + R_world_body @ mount_pos - body_R_world = np.zeros(9, dtype=np.float64) - mujoco.mju_quat2Mat(body_R_world, np.asarray(body_world_wxyz, dtype=np.float64)) - body_R_world = body_R_world.reshape(3, 3) - out_pos = np.asarray(body_world_pos, dtype=np.float64) + body_R_world @ np.asarray( - spec.mount_pos, dtype=np.float64 - ) - - return out_pos, out_quat - - -__all__ = ["CameraSpec", "g1_d435_default", "g1_d435_forward", "world_pose"] diff --git a/dimos/visualization/viser/robot_meshes.py b/dimos/visualization/viser/robot_meshes.py deleted file mode 100644 index 1e02ce1cbe..0000000000 --- a/dimos/visualization/viser/robot_meshes.py +++ /dev/null @@ -1,230 +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. - -"""MuJoCo-based robot mesh extractor + FK helper for the Viser viewer. - -Loads an MJCF (the same one the sim subprocess loads), pulls out visual -mesh geoms with their parent-body indices and local poses, and runs FK -on demand to give world poses for every body in the model. - -Lets the Viser render module display the same robot the simulation is -stepping, without forcing a separate URDF or duplicating geometry. -""" - -from __future__ import annotations - -from dataclasses import dataclass -from pathlib import Path -import xml.etree.ElementTree as ET - -import mujoco -import numpy as np - - -# dimos joint names look like ``g1/left_hip_pitch`` (slash-separated -# hardware id + snake_case suffix — the canonical convention since -# Mustafa's #1954 G1 coordinator integration unified naming with the -# Unitree SDK). MJCF joint names look like ``left_hip_pitch_joint``. -# Strip the hardware prefix and append ``_joint``. -def dimos_joint_to_mjcf(name: str) -> str: - parts = name.split("/", 1) - suffix = parts[1] if len(parts) > 1 else parts[0] - return f"{suffix}_joint" - - -@dataclass -class GeomInstance: - """A single visual mesh geom, parented to a body.""" - - body_name: str - vertices: np.ndarray # (V, 3) - faces: np.ndarray # (F, 3) - local_pos: np.ndarray # (3,) - local_wxyz: np.ndarray # (4,) - rgba: tuple[float, float, float, float] - - -@dataclass -class RobotMeshes: - model: mujoco.MjModel - data: mujoco.MjData - geoms: list[GeomInstance] - # joint-name (in MJCF order) -> qpos address. Used to splice incoming - # joint_state values into the right slots of qpos. - qpos_addr_by_mjcf_name: dict[str, int] - # body_id -> body name (for viser entity paths). - body_names: list[str] - - -def load_robot_meshes( - mjcf_path: str | Path, - *, - visual_groups: tuple[int, ...] = (0, 1, 2), - meshdir: str | Path | None = None, - assets: dict[str, bytes] | None = None, -) -> RobotMeshes: - """Parse the MJCF, pull visual mesh geoms into Python arrays. - - ``visual_groups`` defaults to MuJoCo's convention where group 0-2 are - visual and group 3+ are collision. Most menagerie / dimos models - follow this; if a model uses different groups, override it. - - ``meshdir`` points MuJoCo at a local mesh directory when an MJCF - uses bare mesh filenames. - - ``assets`` is an optional ``{filename: bytes}`` map for embedded assets. - """ - path = Path(mjcf_path) - xml = path.read_text() - if meshdir is not None: - root = ET.fromstring(xml) - compiler = root.find("compiler") - if compiler is None: - compiler = ET.Element("compiler") - root.insert(0, compiler) - compiler.set("meshdir", str(Path(meshdir).expanduser().resolve())) - for include in root.iter("include"): - include_file = include.get("file") - if include_file and not Path(include_file).is_absolute(): - include.set("file", str((path.parent / include_file).resolve())) - xml = ET.tostring(root, encoding="unicode") - model = mujoco.MjModel.from_xml_string(xml, assets or {}) - data = mujoco.MjData(model) - - geoms: list[GeomInstance] = [] - for gid in range(model.ngeom): - if int(model.geom_group[gid]) not in visual_groups: - continue - gtype = int(model.geom_type[gid]) - body_id = int(model.geom_bodyid[gid]) - body_name = mujoco.mj_id2name(model, mujoco.mjtObj.mjOBJ_BODY, body_id) or f"body_{body_id}" - rgba = tuple(float(x) for x in model.geom_rgba[gid]) - local_pos = np.array(model.geom_pos[gid], dtype=np.float32).copy() - local_wxyz = np.array(model.geom_quat[gid], dtype=np.float32).copy() - size = model.geom_size[gid] - - # Mesh: pull vertices/faces from the model. - if gtype == mujoco.mjtGeom.mjGEOM_MESH: - mesh_id = int(model.geom_dataid[gid]) - if mesh_id < 0: - continue - v_start = int(model.mesh_vertadr[mesh_id]) - v_count = int(model.mesh_vertnum[mesh_id]) - f_start = int(model.mesh_faceadr[mesh_id]) - f_count = int(model.mesh_facenum[mesh_id]) - vertices = np.array( - model.mesh_vert[v_start : v_start + v_count], - dtype=np.float32, - ).copy() - faces = np.array( - model.mesh_face[f_start : f_start + f_count], - dtype=np.int32, - ).copy() - # Box: tessellate as 8 verts + 12 triangles, half-sizes from - # geom_size[0..2]. Lets us render primitives - # (manip_table, manip_cube, scene-editor exports) without a - # mesh asset. - elif gtype == mujoco.mjtGeom.mjGEOM_BOX: - hx, hy, hz = float(size[0]), float(size[1]), float(size[2]) - vertices = np.array( - [ - [-hx, -hy, -hz], - [hx, -hy, -hz], - [hx, hy, -hz], - [-hx, hy, -hz], - [-hx, -hy, hz], - [hx, -hy, hz], - [hx, hy, hz], - [-hx, hy, hz], - ], - dtype=np.float32, - ) - # Outward-facing CCW triangles (verified by cross-product). - faces = np.array( - [ - [0, 2, 1], - [0, 3, 2], # -Z (bottom) - [4, 5, 6], - [4, 6, 7], # +Z (top) - [0, 1, 5], - [0, 5, 4], # -Y - [1, 2, 6], - [1, 6, 5], # +X - [2, 3, 7], - [2, 7, 6], # +Y - [3, 0, 4], - [3, 4, 7], # -X - ], - dtype=np.int32, - ) - else: - # Sphere, cylinder, plane, etc. — skip for now. Only manip - # rigs and scene-editor exports use boxes; everything else - # the dimos sims care about is a mesh. - continue - - geoms.append( - GeomInstance( - body_name=body_name, - vertices=vertices, - faces=faces, - local_pos=local_pos, - local_wxyz=local_wxyz, - rgba=rgba, # type: ignore[arg-type] - ) - ) - - qpos_addr_by_mjcf_name: dict[str, int] = {} - for jid in range(model.njnt): - jname = mujoco.mj_id2name(model, mujoco.mjtObj.mjOBJ_JOINT, jid) - if jname is None: - continue - qpos_addr_by_mjcf_name[jname] = int(model.jnt_qposadr[jid]) - - body_names = [ - mujoco.mj_id2name(model, mujoco.mjtObj.mjOBJ_BODY, bid) or f"body_{bid}" - for bid in range(model.nbody) - ] - - return RobotMeshes( - model=model, - data=data, - geoms=geoms, - qpos_addr_by_mjcf_name=qpos_addr_by_mjcf_name, - body_names=body_names, - ) - - -def apply_state( - rm: RobotMeshes, - *, - base_pos: np.ndarray | None = None, - base_wxyz: np.ndarray | None = None, - joint_positions: dict[str, float] | None = None, -) -> None: - """Splice base + joint values into qpos and run FK in-place. - - After this returns, ``rm.data.xpos`` and ``rm.data.xquat`` hold each - body's world pose. Cheap (~50 us for G1). - """ - if base_pos is not None: - rm.data.qpos[0:3] = base_pos - if base_wxyz is not None: - rm.data.qpos[3:7] = base_wxyz - if joint_positions: - for name, q in joint_positions.items(): - adr = rm.qpos_addr_by_mjcf_name.get(name) - if adr is not None: - rm.data.qpos[adr] = q - mujoco.mj_kinematics(rm.model, rm.data) diff --git a/dimos/visualization/viser/splat.py b/dimos/visualization/viser/splat.py deleted file mode 100644 index 87b94c50bb..0000000000 --- a/dimos/visualization/viser/splat.py +++ /dev/null @@ -1,217 +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. - -"""3DGS PLY loader for Viser. - -Reads a Gaussian splat PLY (3DGS-format), applies an alignment transform -(rotation + translation + uniform scale), and returns the -``(centers, covariances, rgbs, opacities)`` arrays Viser's -``add_gaussian_splats`` expects. - -The alignment transform is needed because 3DGS splats trained from -COLMAP come out in the COLMAP world frame, which is Y-up and in -arbitrary scale. Dimos uses Z-up metric. See -``data/scenes/.yaml`` for per-scene alignment values. -""" - -from __future__ import annotations - -from dataclasses import dataclass -from typing import TYPE_CHECKING - -import numpy as np - -if TYPE_CHECKING: - from pathlib import Path - -# 3DGS spherical harmonic DC coefficient. -_SH_C0 = 0.28209479177387814 - -# Y-up (3DGS / COLMAP) -> Z-up (dimos). (x, y, z) -> (x, z, -y). -_Y_UP_TO_Z_UP = np.array( - [[1, 0, 0], [0, 0, 1], [0, -1, 0]], - dtype=np.float32, -) - - -@dataclass -class SplatAlignment: - """Per-scene splat alignment. - - Loaded from a YAML next to the PLY: - - scale: 1.0 # multiplicative; COLMAP units -> meters - translation: [0, 0, 0] # post-rotation offset in world frame, meters - rotation_zyx: [0, 0, 0] # extra yaw/pitch/roll in degrees, applied after Y->Z - y_up: true # apply standard Y-up -> Z-up - """ - - scale: float = 1.0 - translation: tuple[float, float, float] = (0.0, 0.0, 0.0) - rotation_zyx_deg: tuple[float, float, float] = (0.0, 0.0, 0.0) - y_up: bool = True - - @classmethod - def from_yaml(cls, path: str | Path) -> SplatAlignment: - import yaml - - with open(path) as f: - d = yaml.safe_load(f) or {} - return cls( - scale=float(d.get("scale", 1.0)), - translation=tuple(d.get("translation", [0.0, 0.0, 0.0])), # type: ignore[arg-type] - rotation_zyx_deg=tuple(d.get("rotation_zyx", [0.0, 0.0, 0.0])), # type: ignore[arg-type] - y_up=bool(d.get("y_up", True)), - ) - - def world_from_splat(self) -> np.ndarray: - """3x3 rotation: scaled rotation that maps splat-frame -> world-frame.""" - R = _Y_UP_TO_Z_UP if self.y_up else np.eye(3, dtype=np.float32) - rz, ry, rx = (np.deg2rad(a) for a in self.rotation_zyx_deg) - cz, sz = np.cos(rz), np.sin(rz) - cy, sy = np.cos(ry), np.sin(ry) - cx, sx = np.cos(rx), np.sin(rx) - Rz = np.array([[cz, -sz, 0], [sz, cz, 0], [0, 0, 1]], dtype=np.float32) - Ry = np.array([[cy, 0, sy], [0, 1, 0], [-sy, 0, cy]], dtype=np.float32) - Rx = np.array([[1, 0, 0], [0, cx, -sx], [0, sx, cx]], dtype=np.float32) - return (Rz @ Ry @ Rx @ R).astype(np.float32) - - -@dataclass -class SplatData: - centers: np.ndarray # (N, 3) float32, world frame - covariances: np.ndarray # (N, 3, 3) float32, world frame. For viser. - rgbs: np.ndarray # (N, 3) float32, [0, 1] - opacities: np.ndarray # (N, 1) float32, [0, 1] - # Primitive form for renderers that prefer it (e.g. gsplat). - # All in the same world frame as ``centers``/``covariances``. - quats_wxyz: np.ndarray # (N, 4) float32 - scales: np.ndarray # (N, 3) float32, post-alignment uniform-scaled - - -def load_splat(ply_path: str | Path, alignment: SplatAlignment | None = None) -> SplatData: - """Load a 3DGS PLY and bake the alignment into centers + covariances. - - Returns arrays in dimos world frame, ready to feed straight into - ``viser.scene.add_gaussian_splats``. Heavy: ~1-2 GB for a 250 MB PLY, - so do this once at module start, not per frame. - """ - if alignment is None: - alignment = SplatAlignment() - from plyfile import PlyData - - ply = PlyData.read(str(ply_path)) - v = ply["vertex"] - props = {p.name for p in v.properties} - - pos = np.stack( - [v["x"], v["y"], v["z"]], - axis=-1, - ).astype(np.float32) - - if "rot_0" in props: - rw = v["rot_0"].astype(np.float32) - rx = v["rot_1"].astype(np.float32) - ry = v["rot_2"].astype(np.float32) - rz = v["rot_3"].astype(np.float32) - n = np.sqrt(rw * rw + rx * rx + ry * ry + rz * rz).clip(1e-12) - rw, rx, ry, rz = rw / n, rx / n, ry / n, rz / n - R = np.empty((len(rw), 3, 3), dtype=np.float32) - R[:, 0, 0] = 1 - 2 * (ry * ry + rz * rz) - R[:, 0, 1] = 2 * (rx * ry - rw * rz) - R[:, 0, 2] = 2 * (rx * rz + rw * ry) - R[:, 1, 0] = 2 * (rx * ry + rw * rz) - R[:, 1, 1] = 1 - 2 * (rx * rx + rz * rz) - R[:, 1, 2] = 2 * (ry * rz - rw * rx) - R[:, 2, 0] = 2 * (rx * rz - rw * ry) - R[:, 2, 1] = 2 * (ry * rz + rw * rx) - R[:, 2, 2] = 1 - 2 * (rx * rx + ry * ry) - else: - R = np.tile(np.eye(3, dtype=np.float32), (len(pos), 1, 1)) - - if "scale_0" in props: - s = np.exp(np.stack([v["scale_0"], v["scale_1"], v["scale_2"]], axis=-1).astype(np.float32)) - else: - s = np.ones((len(pos), 3), dtype=np.float32) - - if "opacity" in props: - op = (1.0 / (1.0 + np.exp(-v["opacity"].astype(np.float32)))).reshape(-1, 1) - else: - op = np.ones((len(pos), 1), dtype=np.float32) - - if all(f"f_dc_{i}" in props for i in range(3)): - sh_dc = np.stack( - [v["f_dc_0"], v["f_dc_1"], v["f_dc_2"]], - axis=-1, - ).astype(np.float32) - rgbs = (_SH_C0 * sh_dc + 0.5).clip(0.0, 1.0).astype(np.float32) - else: - rgbs = np.ones((len(pos), 3), dtype=np.float32) - - # Covariance in original splat frame: C = R diag(s^2) R^T. - cov_splat = np.einsum("nij,nj,nkj->nik", R, s * s, R) - - # Apply alignment. Centers: world = scale * (M @ splat) + t. Covariances: - # transform as bilinear forms: C' = scale^2 * M C M^T (translation drops). - M = alignment.world_from_splat() - centers = (alignment.scale * pos @ M.T) + np.asarray(alignment.translation, dtype=np.float32) - covariances = (alignment.scale * alignment.scale) * np.einsum("ij,njk,lk->nil", M, cov_splat, M) - - # Same alignment applied to the primitive (quat, scale) form. Renderers - # like gsplat operate directly on these instead of full covariances. - quats_splat = np.stack([rw, rx, ry, rz], axis=-1) if "rot_0" in props else None - if quats_splat is None: - quats_world = np.tile(np.array([1.0, 0.0, 0.0, 0.0], dtype=np.float32), (len(pos), 1)) - else: - # Rotate every Gaussian's local frame by M: q_world = q_M ⊗ q_splat. - qM = _mat3_to_wxyz(M) - quats_world = _quat_mul_left(qM, quats_splat).astype(np.float32) - scales_world = (alignment.scale * s).astype(np.float32) - - return SplatData( - centers=centers, - covariances=covariances, - rgbs=rgbs, - opacities=op, - quats_wxyz=quats_world, - scales=scales_world, - ) - - -def _mat3_to_wxyz(R: np.ndarray) -> np.ndarray: - """3x3 rotation matrix -> (w, x, y, z), via mujoco for numerical stability.""" - import mujoco - - out = np.zeros(4, dtype=np.float64) - mujoco.mju_mat2Quat(out, np.asarray(R, dtype=np.float64).flatten()) - return out.astype(np.float32) - - -def _quat_mul_left(q1: np.ndarray, q2: np.ndarray) -> np.ndarray: - """Left-multiply ``q1 ⊗ q2`` for q1: (4,) wxyz and q2: (N, 4) wxyz. - - Vectorised — the per-Gaussian alternative through ``mujoco.mju_mulQuat`` - in a Python loop is ~50x slower for 1M Gaussians. - """ - aw, ax, ay, az = q1[0], q1[1], q1[2], q1[3] - bw, bx, by, bz = q2[:, 0], q2[:, 1], q2[:, 2], q2[:, 3] - return np.stack( - [ - aw * bw - ax * bx - ay * by - az * bz, - aw * bx + ax * bw + ay * bz - az * by, - aw * by - ax * bz + ay * bw + az * bx, - aw * bz + ax * by - ay * bx + az * bw, - ], - axis=-1, - ) diff --git a/dimos/visualization/viser/viser_render_module.py b/dimos/visualization/viser/viser_render_module.py deleted file mode 100644 index db0f7a333a..0000000000 --- a/dimos/visualization/viser/viser_render_module.py +++ /dev/null @@ -1,774 +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. - -"""Viser-based 3D viewer module for dimos. - -Streams a Gaussian splat scene + the robot (MJCF meshes, FK from -``/coordinator/joint_state`` + ``/odom``) into a browser at -http://localhost:/. - -This is render-only — the viewer subscribes to existing LCM topics and -does not feed back into the control path. Teleop continues to come -from the existing command-center dashboard. -""" - -from __future__ import annotations - -from pathlib import Path as FilePath -import threading -import time -from typing import Any - -import mujoco -import numpy as np -from reactivex.disposable import Disposable - -from dimos.core.core import rpc -from dimos.core.module import Module -from dimos.core.stream import In, Out -from dimos.msgs.geometry_msgs.PointStamped import PointStamped -from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped -from dimos.msgs.nav_msgs.Path import Path as PathMsg -from dimos.msgs.sensor_msgs.JointState import JointState -from dimos.msgs.sensor_msgs.PointCloud2 import PointCloud2 -from dimos.utils.logging_config import setup_logger -from dimos.visualization.viser.camera import CameraSpec, world_pose -from dimos.visualization.viser.robot_meshes import ( - RobotMeshes, - apply_state, - dimos_joint_to_mjcf, - load_robot_meshes, -) -from dimos.visualization.viser.splat import SplatAlignment, load_splat - -logger = setup_logger() -_WORLD_FRAME = "world" - - -def _compose_scene_mesh_wxyz( - *, y_up: bool, rotation_zyx_deg: tuple[float, float, float] -) -> tuple[float, float, float, float]: - """Build the viser wxyz quaternion that applies (y_up swap then zyx euler) — - same convention as SceneMeshAlignment, just expressed as a parent-frame - transform so we don't have to bake it into vertices.""" - R = np.eye(3, dtype=np.float64) - if y_up: - R = np.array([[1, 0, 0], [0, 0, 1], [0, -1, 0]], dtype=np.float64) - rz, ry, rx = (np.deg2rad(a) for a in rotation_zyx_deg) - cz, sz = np.cos(rz), np.sin(rz) - cy, sy = np.cos(ry), np.sin(ry) - cx, sx = np.cos(rx), np.sin(rx) - Rz = np.array([[cz, -sz, 0], [sz, cz, 0], [0, 0, 1]], dtype=np.float64) - Ry = np.array([[cy, 0, sy], [0, 1, 0], [-sy, 0, cy]], dtype=np.float64) - Rx = np.array([[1, 0, 0], [0, cx, -sx], [0, sx, cx]], dtype=np.float64) - R = Rz @ Ry @ Rx @ R - import mujoco - - out = np.zeros(4, dtype=np.float64) - mujoco.mju_mat2Quat(out, R.flatten()) - return (float(out[0]), float(out[1]), float(out[2]), float(out[3])) - - -class ViserRenderModule(Module): - """Viser viewer that overlays the live robot on a Gaussian splat. - - Inputs: - joint_state: per-joint q values from the coordinator. - odom: base pose from the sim (or future real-hw) adapter. - """ - - joint_state: In[JointState] - odom: In[PoseStamped] - path: In[PathMsg] - # Optional pointcloud overlay. Named distinctly (not `lidar`) so the - # global transport map doesn't collide with VoxelGridMapper's `lidar` - # In port — the coordinator keys transports by (port_name, type) and - # the last-registered module wins, so a name clash silently overrides - # whichever transport was registered first. Blueprints typically - # wire this to /global_map (accumulated voxel cloud) for a persistent - # obstacle-memory overlay; /lidar (per-scan, transient) also works - # if the latest sweep is what you want. - pointcloud_overlay: In[PointCloud2] - clicked_point: Out[PointStamped] - # Interactive pointing-target publisher. Wired up by the "Set point - # goal" button: armed by the user pressing the button, the next - # scene click ray-casts against the scene mesh (if loaded) or - # intersects the eye-height plane, and the resulting world-frame - # point is published here. G1ManipulationModule subscribes and runs - # point_at on each value. Separate stream from clicked_point so a - # human's pointing click doesn't accidentally retarget the navigator. - point_goal: Out[PointStamped] - - def __init__( - self, - splat_path: str | FilePath | None, - mjcf_path: str | FilePath, - *, - port: int = 8082, - alignment_yaml: str | FilePath | None = None, - render_hz: float = 30.0, - camera_spec: CameraSpec | None = None, - mjcf_meshdir: str | FilePath | None = None, - scene_mesh_path: str | FilePath | None = None, - scene_mesh_scale: float = 1.0, - scene_mesh_translation: tuple[float, float, float] = (0.0, 0.0, 0.0), - scene_mesh_rotation_zyx_deg: tuple[float, float, float] = (0.0, 0.0, 0.0), - scene_mesh_y_up: bool = True, - pointcloud_point_size: float = 0.04, - **kwargs: Any, - ) -> None: - super().__init__(**kwargs) - # Empty / None splat_path means "no splat in the viewer" — useful when - # the world is provided as a mesh instead (DIMOS_SCENE_MESH_PATH). - self._splat_path = FilePath(splat_path) if splat_path else None - self._mjcf_path = FilePath(mjcf_path) - self._mjcf_meshdir = FilePath(mjcf_meshdir) if mjcf_meshdir else None - self._alignment_yaml = FilePath(alignment_yaml) if alignment_yaml else None - self._port = port - self._render_dt = 1.0 / float(render_hz) - self._camera_spec = camera_spec - self._scene_mesh_path = FilePath(scene_mesh_path) if scene_mesh_path else None - self._scene_mesh_scale = scene_mesh_scale - self._scene_mesh_translation = scene_mesh_translation - self._scene_mesh_rotation_zyx_deg = scene_mesh_rotation_zyx_deg - self._scene_mesh_y_up = scene_mesh_y_up - self._pointcloud_point_size = pointcloud_point_size - - # viser handles for view-mode toggle - self._splat_handle: Any = None - self._scene_mesh_handle: Any = None - # Open3D RaycastingScene built from the scene-mesh geometry. Used - # by the "Set point goal" button to resolve a 2D click into an - # exact 3D surface hit. None when no scene mesh is configured. - self._raycast_scene: Any = None - - # Mutable shared state — written from In subscribers, read from - # the render loop. Plain dict + lock; values are lightweight. - self._state_lock = threading.Lock() - self._latest_joints: dict[str, float] = {} - self._latest_base_pos: np.ndarray | None = None - self._latest_base_wxyz: np.ndarray | None = None - - self._server: Any = None # viser.ViserServer - self._body_frames: dict[int, Any] = {} # body_id -> viser frame handle - self._camera_body_id: int | None = None - self._camera_frustum: Any = None # viser frustum handle - self._robot: RobotMeshes | None = None - self._render_thread: threading.Thread | None = None - self._stop_event = threading.Event() - self._path_handle: Any = None - # Layer-visibility state. Three independent toggles in the - # viser GUI panel — Splat / Mesh / Lidar — each gating one - # backdrop so any subset can be shown. The current and - # previous designs (a Splat-vs-Mesh dropdown plus separate - # checkboxes) were redundant because they overlapped on mesh - # visibility and forced exclusivity the user didn't want. - # GaussianSplatHandle in viser 1.0.26 advertises `.visible` but - # the splat shader pipeline (still labeled "work-in-progress" - # in the docstring) ignores it — flipping the property does - # nothing in the browser. Keep a copy of the loaded splat so - # the toggle can re-add the handle on demand instead. - self._splat_visible: bool = True - self._splat_checkbox: Any = None - self._splat_data: Any = None # cached load_splat() result - self._scene_mesh_visible: bool = True - self._scene_mesh_checkbox: Any = None - # Lidar overlay handle is replaced (not appended) on every - # incoming /global_map message so we don't accumulate - # cloud-on-cloud. `_lidar_visible` gates the upload itself - # so toggling off costs nothing. - self._lidar_handle: Any = None - self._lidar_visible: bool = True - self._lidar_checkbox: Any = None - - @rpc - def start(self) -> None: - super().start() - - import viser - - splat = self._load_splat() - self._load_robot_meshes() - self._server = viser.ViserServer(host="0.0.0.0", port=self._port) - self._configure_server() - logger.info(f"Viser viewer: http://localhost:{self._port}/") - - self._add_splat(splat) - self._add_scene_mesh_if_configured() - self._add_layer_controls() - self._add_robot_meshes() - self._add_camera_frustum() - self._add_click_controls() - self._subscribe_inputs() - self._start_render_thread() - - def _load_splat(self) -> Any | None: - alignment = ( - SplatAlignment.from_yaml(self._alignment_yaml) - if self._alignment_yaml and self._alignment_yaml.exists() - else SplatAlignment() - ) - if self._splat_path is None: - logger.info("Viser: splat disabled (no splat_path provided)") - return None - logger.info(f"Viser: loading splat from {self._splat_path}") - splat = load_splat(self._splat_path, alignment=alignment) - logger.info(f"Viser: loaded {len(splat.centers)} Gaussians") - return splat - - def _load_robot_meshes(self) -> None: - logger.info(f"Viser: loading robot meshes from {self._mjcf_path}") - self._robot = load_robot_meshes(self._mjcf_path, meshdir=self._mjcf_meshdir) - logger.info( - f"Viser: {len(self._robot.geoms)} visual meshes across " - f"{len(self._robot.body_names)} bodies" - ) - - def _configure_server(self) -> None: - assert self._server is not None - self._server.gui.set_panel_label(None) - self._server.gui.configure_theme( - control_layout="collapsible", - show_logo=False, - show_share_button=False, - dark_mode=True, - ) - - def _add_splat(self, splat: Any | None) -> None: - if splat is None: - return - assert self._server is not None - self._splat_data = splat - self._splat_handle = self._server.scene.add_gaussian_splats( - "/splat", - centers=splat.centers, - covariances=splat.covariances, - rgbs=splat.rgbs, - opacities=splat.opacities, - ) - - def _add_scene_mesh_if_configured(self) -> None: - if self._scene_mesh_path is not None and self._scene_mesh_path.exists(): - try: - self._add_scene_mesh() - except Exception as e: - logger.warning(f"Viser: scene mesh load failed: {e}") - - def _add_layer_controls(self) -> None: - assert self._server is not None - if self._splat_handle is not None: - self._splat_checkbox = self._server.gui.add_checkbox( - "Show splat", initial_value=self._splat_visible - ) - - @self._splat_checkbox.on_update - def _on_splat_toggle(_: Any) -> None: - visible = bool(self._splat_checkbox.value) - self._splat_visible = visible - # `.visible = False` is silently ignored on - # GaussianSplatHandle in viser 1.0.26, so add/remove - # the handle outright. Re-add costs ~one frame from - # the cached splat data. - if visible: - if self._splat_handle is None and self._splat_data is not None: - d = self._splat_data - self._splat_handle = self._server.scene.add_gaussian_splats( - "/splat", - centers=d.centers, - covariances=d.covariances, - rgbs=d.rgbs, - opacities=d.opacities, - ) - else: - if self._splat_handle is not None: - try: - self._splat_handle.remove() - except Exception as e: - logger.debug(f"Viser splat remove failed: {e}") - self._splat_handle = None - - if self._scene_mesh_handle is not None: - self._scene_mesh_checkbox = self._server.gui.add_checkbox( - "Show mesh", initial_value=self._scene_mesh_visible - ) - - @self._scene_mesh_checkbox.on_update - def _on_scene_mesh_toggle(_: Any) -> None: - self._scene_mesh_visible = bool(self._scene_mesh_checkbox.value) - if self._scene_mesh_handle is not None: - self._scene_mesh_handle.visible = self._scene_mesh_visible - - # Lidar map overlay toggle is unconditional — when no publisher is - # connected the cloud stays empty, but having the checkbox - # always present makes the overlay discoverable. - self._lidar_checkbox = self._server.gui.add_checkbox( - "Show lidar map", initial_value=self._lidar_visible - ) - - @self._lidar_checkbox.on_update - def _on_lidar_toggle(_: Any) -> None: - self._lidar_visible = bool(self._lidar_checkbox.value) - if self._lidar_handle is not None: - self._lidar_handle.visible = self._lidar_visible - - def _add_robot_meshes(self) -> None: - assert self._server is not None - assert self._robot is not None - for body_id, body_name in enumerate(self._robot.body_names): - self._body_frames[body_id] = self._server.scene.add_frame( - f"/robot/{body_name}", - show_axes=False, - ) - for i, geom in enumerate(self._robot.geoms): - color_rgb = ( - int(geom.rgba[0] * 255), - int(geom.rgba[1] * 255), - int(geom.rgba[2] * 255), - ) - self._server.scene.add_mesh_simple( - f"/robot/{geom.body_name}/geom_{i}", - vertices=geom.vertices, - faces=geom.faces, - color=color_rgb, - opacity=float(geom.rgba[3]) if geom.rgba[3] > 0 else 1.0, - position=tuple(geom.local_pos), - wxyz=tuple(geom.local_wxyz), - ) - - def _add_camera_frustum(self) -> None: - assert self._server is not None - assert self._robot is not None - if self._camera_spec is not None: - cam_body_id = mujoco.mj_name2id( - self._robot.model, mujoco.mjtObj.mjOBJ_BODY, self._camera_spec.body_name - ) - if cam_body_id < 0: - logger.warning( - f"Viser: camera mount body '{self._camera_spec.body_name}' not in MJCF; " - "frustum overlay disabled" - ) - else: - self._camera_body_id = cam_body_id - self._camera_frustum = self._server.scene.add_camera_frustum( - "/robot/_camera_frustum", - fov=float(np.radians(self._camera_spec.vfov_deg)), - aspect=float(self._camera_spec.aspect), - scale=float(self._camera_spec.frustum_scale), - color=self._camera_spec.frustum_color, - ) - - def _add_click_controls(self) -> None: - assert self._server is not None - nav_goal_button = self._server.gui.add_button("Set nav goal") - - @nav_goal_button.on_click - def _arm_nav_goal_click(_event: Any) -> None: - nav_goal_button.disabled = True - nav_goal_button.label = "Click on floor..." - - @self._server.scene.on_pointer_event(event_type="click") - def _on_floor_click(event: Any) -> None: - try: - self._handle_floor_click(event) - finally: - self._server.scene.remove_pointer_callback() - - @self._server.scene.on_pointer_callback_removed - def _rearm_button() -> None: - nav_goal_button.disabled = False - nav_goal_button.label = "Set nav goal" - - point_goal_button = self._server.gui.add_button("Set point goal") - - @point_goal_button.on_click - def _arm_point_goal_click(_event: Any) -> None: - point_goal_button.disabled = True - point_goal_button.label = "Click target..." - - @self._server.scene.on_pointer_event(event_type="click") - def _on_point_click(event: Any) -> None: - try: - self._handle_point_goal_click(event) - finally: - self._server.scene.remove_pointer_callback() - - @self._server.scene.on_pointer_callback_removed - def _rearm_point_button() -> None: - point_goal_button.disabled = False - point_goal_button.label = "Set point goal" - - def _subscribe_inputs(self) -> None: - try: - unsub = self.path.subscribe(self._on_path) - self.register_disposable(Disposable(unsub)) - except Exception as e: - logger.warning(f"Viser: path subscribe failed: {e}") - - try: - unsub = self.pointcloud_overlay.subscribe(self._on_lidar) - self.register_disposable(Disposable(unsub)) - except Exception as e: - logger.warning(f"Viser: lidar subscribe failed: {e}") - - try: - unsub = self.joint_state.subscribe(self._on_joint_state) - self.register_disposable(Disposable(unsub)) - except Exception as e: - logger.warning(f"Viser: joint_state subscribe failed: {e}") - - try: - unsub = self.odom.subscribe(self._on_odom) - self.register_disposable(Disposable(unsub)) - except Exception as e: - logger.warning(f"Viser: odom subscribe failed: {e}") - - def _start_render_thread(self) -> None: - self._render_thread = threading.Thread( - target=self._render_loop, name="viser-render", daemon=True - ) - self._render_thread.start() - - @rpc - def stop(self) -> None: - self._stop_event.set() - if self._render_thread and self._render_thread.is_alive(): - self._render_thread.join(timeout=2.0) - if self._server is not None: - try: - self._server.stop() - except Exception: - pass - super().stop() - - def _add_scene_mesh(self) -> None: - """Add the configured scene mesh to viser. - - For ``.glb``/``.gltf`` we hand the file's bytes straight to - ``server.scene.add_glb()`` — the browser renders the PBR materials - natively. This is critical: going through ``load_scene_mesh()`` calls - ``trimesh.load(force="mesh")`` which decompresses every embedded - texture to sample per-vertex colors, allocating ~10 GB peak for a - scene with many 4K PBR textures (e.g. the office mesh has 321 textures - totaling ~895 MP). For unknown extensions (USD, OBJ, etc.) we fall back - to the geometry path — those generally don't have the embedded-texture - problem. - """ - assert self._scene_mesh_path is not None - path = self._scene_mesh_path - suffix = path.suffix.lower() - - # Alignment for viser: handed to add_glb as scale + wxyz + position so - # we don't touch the geometry at all on this path. - wxyz = _compose_scene_mesh_wxyz( - y_up=self._scene_mesh_y_up, - rotation_zyx_deg=self._scene_mesh_rotation_zyx_deg, - ) - position = tuple(float(x) for x in self._scene_mesh_translation) - scale = float(self._scene_mesh_scale) - - # Always build a server-side raycaster from the geometry so the - # "Set point goal" button can resolve clicks to surface hits. - # Cheap now that GLBs are geometry-only (textures stripped at - # asset-prep time) — load_scene_mesh peaks at ~1 GB even for the - # 1.4M-vert office mesh. - from dimos.mapping.mesh_scene import ( - SceneMeshAlignment, - load_scene_mesh, - make_raycasting_scene, - ) - - mesh_alignment = SceneMeshAlignment( - scale=self._scene_mesh_scale, - rotation_zyx_deg=self._scene_mesh_rotation_zyx_deg, - translation=self._scene_mesh_translation, - y_up=self._scene_mesh_y_up, - ) - - if suffix in {".glb", ".gltf"}: - logger.info(f"Viser: loading scene mesh {path} (GLB native path)") - with open(path, "rb") as f: - glb_bytes = f.read() - self._scene_mesh_handle = self._server.scene.add_glb( - "/scene_mesh", - glb_data=glb_bytes, - scale=scale, - wxyz=wxyz, - position=position, - ) - logger.info(f"Viser: scene mesh added ({len(glb_bytes) / 1e6:.1f} MB GLB)") - # Build raycaster from geometry separately (browser already - # has the bytes for display; we need o3d structures here). - try: - scene_mesh = load_scene_mesh(path, alignment=mesh_alignment) - self._raycast_scene = make_raycasting_scene(scene_mesh) - logger.info("Viser: scene-mesh raycaster ready for click-to-point") - except Exception as e: - logger.warning( - f"Viser: raycaster build failed (point-goal will use plane fallback): {e}" - ) - return - - # Non-GLB path: USD, OBJ, PLY — geometry-only, no texture decode blowup. - logger.info(f"Viser: loading scene mesh {path}") - scene_mesh = load_scene_mesh(path, alignment=mesh_alignment) - vertices = np.asarray(scene_mesh.vertices, dtype=np.float32) - faces = np.asarray(scene_mesh.triangles, dtype=np.int32) - self._scene_mesh_handle = self._server.scene.add_mesh_simple( - "/scene_mesh", - vertices=vertices, - faces=faces, - color=(180, 180, 180), - opacity=1.0, - ) - logger.info(f"Viser: scene mesh added ({len(vertices)} verts, {len(faces)} tris)") - try: - self._raycast_scene = make_raycasting_scene(scene_mesh) - logger.info("Viser: scene-mesh raycaster ready for click-to-point") - except Exception as e: - logger.warning(f"Viser: raycaster build failed: {e}") - - def _handle_floor_click(self, event: Any) -> None: - """Project the click ray onto the z=0 floor and publish a goal.""" - ray_origin = event.ray_origin - ray_direction = event.ray_direction - if ray_origin is None or ray_direction is None: - return - - ox, oy, oz = ray_origin - dx, dy, dz = ray_direction - if abs(dz) < 1e-6: - logger.info("Viser nav-goal: click ray is parallel to floor, ignoring") - return - t = -oz / dz - if t <= 0: - logger.info("Viser nav-goal: click is above the horizon, ignoring") - return - x = ox + t * dx - y = oy + t * dy - - marker_color = (0, 200, 255) - try: - self._server.scene.add_icosphere( - "/nav_goal_marker", - radius=0.08, - position=(float(x), float(y), 0.05), - color=marker_color, - ) - except Exception as e: - logger.debug(f"Viser nav-goal marker failed: {e}") - - point = PointStamped(x=float(x), y=float(y), z=0.0, ts=time.time(), frame_id=_WORLD_FRAME) - self.clicked_point.publish(point) - logger.info(f"Viser nav-goal: published clicked_point=({x:.3f}, {y:.3f})") - - def _handle_point_goal_click(self, event: Any) -> None: - """Click → 3D world point → publish to /point_goal. - - Resolution order: - 1. Cast against the loaded scene-mesh raycaster (exact surface hit). - 2. Fall back to intersecting an eye-height z=1.0 m plane — picking - a floor target makes no sense for pointing, and eye height is a - reasonable default for "the user clicked on empty space". - """ - ray_origin = event.ray_origin - ray_direction = event.ray_direction - if ray_origin is None or ray_direction is None: - return - - ox, oy, oz = (float(v) for v in ray_origin) - dx, dy, dz = (float(v) for v in ray_direction) - - hit_xyz: tuple[float, float, float] | None = None - - # 1. Scene-mesh ray-cast if we have one. - if self._raycast_scene is not None: - import open3d.core as o3c - - rays = o3c.Tensor( - np.array([[ox, oy, oz, dx, dy, dz]], dtype=np.float32), - dtype=o3c.Dtype.Float32, - ) - t_hit = float(self._raycast_scene.cast_rays(rays)["t_hit"].numpy()[0]) - if np.isfinite(t_hit) and t_hit > 0: - hit_xyz = (ox + t_hit * dx, oy + t_hit * dy, oz + t_hit * dz) - - # 2. Fallback: intersect z = 1.0 m plane. - if hit_xyz is None: - if abs(dz) < 1e-6: - logger.info("Viser point-goal: ray parallel to eye plane, ignoring") - return - t = (1.0 - oz) / dz - if t <= 0: - logger.info("Viser point-goal: target behind camera, ignoring") - return - hit_xyz = (ox + t * dx, oy + t * dy, 1.0) - - x, y, z = hit_xyz - try: - self._server.scene.add_icosphere( - "/point_goal_marker", - radius=0.06, - position=(float(x), float(y), float(z)), - color=(255, 80, 200), # magenta — distinct from nav-goal cyan - ) - except Exception as e: - logger.debug(f"Viser point-goal marker failed: {e}") - - point = PointStamped( - x=float(x), y=float(y), z=float(z), ts=time.time(), frame_id=_WORLD_FRAME - ) - self.point_goal.publish(point) - logger.info(f"Viser point-goal: published point_goal=({x:.3f}, {y:.3f}, {z:.3f})") - - def _on_path(self, msg: PathMsg) -> None: - """Draw the planner's path as a polyline floating above the floor.""" - poses = msg.poses - if len(poses) < 2: - handle = self._path_handle - if handle is not None: - try: - handle.remove() - except Exception: - pass - self._path_handle = None - return - - path_height = 0.10 # lift above floor so it doesn't z-fight with the splat - pts = np.array( - [[p.position.x, p.position.y, path_height] for p in poses], - dtype=np.float32, - ) - # add_line_segments wants (N, 2, 3): start/end of each segment. - segments = np.stack([pts[:-1], pts[1:]], axis=1) - - try: - self._path_handle = self._server.scene.add_line_segments( - "/nav_path", - points=segments, - colors=(255, 30, 30), - line_width=4.0, - ) - except Exception as e: - logger.debug(f"Viser nav-path render failed: {e}") - - def _on_lidar(self, msg: PointCloud2) -> None: - """Replace the lidar overlay in viser with the latest pointcloud. - - The publisher hands us an ``open3d`` PointCloud whose points are - already in the world frame (this is what ``VoxelGridMapper`` - consumes too — see its docstring). We pass the (N, 3) array to - viser's ``add_point_cloud``; the previous handle is overwritten - in-place so we don't accumulate cloud-on-cloud across frames. - """ - if not self._lidar_visible or self._server is None: - return - try: - pcd = msg.pointcloud - pts = np.asarray(pcd.points, dtype=np.float32) - if pts.size == 0: - return - # Per-point colors via height-mapped turbo colormap — same - # gradient + same z-normalization formula rerun's pointcloud - # path uses (PointCloud2.to_rerun) so the two viewers look - # identical when both are running. - from dimos.msgs.sensor_msgs.PointCloud2 import _get_colormap_lut - - lut = _get_colormap_lut("turbo") # (256, 3) uint8, lru-cached - z = pts[:, 2] - z_min, z_max = float(z.min()), float(z.max()) - class_ids = ((z - z_min) / (z_max - z_min + 1e-8) * 255).astype(np.uint8) - colors = lut[class_ids] # (N, 3) uint8 - self._lidar_handle = self._server.scene.add_point_cloud( - "/lidar_overlay", - points=pts, - colors=colors, - point_size=self._pointcloud_point_size, - ) - self._lidar_handle.visible = self._lidar_visible - except Exception as e: - logger.debug(f"Viser lidar overlay update failed: {e}") - - def _on_joint_state(self, msg: JointState) -> None: - names = list(msg.name) - positions = list(msg.position) - if not names or len(names) != len(positions): - return - with self._state_lock: - for n, q in zip(names, positions, strict=False): - self._latest_joints[dimos_joint_to_mjcf(n)] = float(q) - - def _on_odom(self, msg: PoseStamped) -> None: - with self._state_lock: - self._latest_base_pos = np.array( - [msg.position.x, msg.position.y, msg.position.z], - dtype=np.float64, - ) - # PoseStamped quaternion is (x, y, z, w); MuJoCo / Viser want (w, x, y, z). - self._latest_base_wxyz = np.array( - [msg.orientation.w, msg.orientation.x, msg.orientation.y, msg.orientation.z], - dtype=np.float64, - ) - - def _render_loop(self) -> None: - assert self._robot is not None - next_tick = time.monotonic() - while not self._stop_event.is_set(): - with self._state_lock: - joints = dict(self._latest_joints) - base_pos = None if self._latest_base_pos is None else self._latest_base_pos.copy() - base_wxyz = ( - None if self._latest_base_wxyz is None else self._latest_base_wxyz.copy() - ) - - try: - apply_state( - self._robot, - base_pos=base_pos, - base_wxyz=base_wxyz, - joint_positions=joints, - ) - self._update_camera_frustum() - xpos = self._robot.data.xpos - xquat = self._robot.data.xquat - for body_id, frame in self._body_frames.items(): - frame.position = tuple(float(x) for x in xpos[body_id]) - frame.wxyz = tuple(float(x) for x in xquat[body_id]) - except Exception as e: - logger.debug(f"Viser render tick failed: {e}") - - next_tick += self._render_dt - sleep_for = next_tick - time.monotonic() - if sleep_for > 0: - time.sleep(sleep_for) - else: - next_tick = time.monotonic() - - def _update_camera_frustum(self) -> None: - """Place the camera frustum at the current pose of its mount body.""" - if self._camera_frustum is None or self._camera_body_id is None: - return - if self._camera_spec is None: - return - assert self._robot is not None - body_pos = self._robot.data.xpos[self._camera_body_id] - body_wxyz = self._robot.data.xquat[self._camera_body_id] - cam_pos, cam_wxyz = world_pose(body_pos, body_wxyz, self._camera_spec) - self._camera_frustum.position = tuple(float(x) for x in cam_pos) - self._camera_frustum.wxyz = tuple(float(x) for x in cam_wxyz) - - -viser_render = ViserRenderModule.blueprint - - -__all__ = ["ViserRenderModule", "viser_render"] diff --git a/pyproject.toml b/pyproject.toml index 613df3cf1a..a5b022e089 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -308,12 +308,6 @@ sim = [ "usd-core>=24.0", ] -viz = [ - "dimos[sim]", - "viser>=1.0.26", - "plyfile>=1.1.3", -] - navigation = [ "gtsam-extended>=4.3a1.post1", ] diff --git a/uv.lock b/uv.lock index 8dde4a6de5..3109084908 100644 --- a/uv.lock +++ b/uv.lock @@ -2248,15 +2248,6 @@ visualization = [ { name = "dimos-viewer" }, { name = "rerun-sdk" }, ] -viz = [ - { name = "mujoco" }, - { name = "playground" }, - { name = "plyfile" }, - { name = "pygame" }, - { name = "trimesh" }, - { name = "usd-core" }, - { name = "viser" }, -] web = [ { name = "fastapi" }, { name = "ffmpeg-python" }, @@ -2285,7 +2276,6 @@ requires-dist = [ { name = "dimos", extras = ["agents", "base", "cpu", "cuda", "dev", "docker", "drone", "manipulation", "misc", "perception", "psql", "sim", "unitree", "visualization", "web"], marker = "extra == 'all'" }, { name = "dimos", extras = ["agents", "web", "visualization"], marker = "extra == 'base'" }, { name = "dimos", extras = ["base"], marker = "extra == 'unitree'" }, - { name = "dimos", extras = ["sim"], marker = "extra == 'viz'" }, { name = "dimos", extras = ["unitree"], marker = "extra == 'unitree-dds'" }, { name = "dimos-lcm" }, { name = "dimos-lcm", marker = "extra == 'docker'" }, @@ -2354,7 +2344,6 @@ requires-dist = [ { name = "plotly", marker = "extra == 'manipulation'", specifier = ">=5.9.0" }, { name = "plum-dispatch", specifier = "==2.5.7" }, { name = "plum-dispatch", marker = "extra == 'docker'", specifier = "==2.5.7" }, - { name = "plyfile", marker = "extra == 'viz'", specifier = ">=1.1.3" }, { name = "portal", marker = "extra == 'misc'" }, { name = "pre-commit", marker = "extra == 'dev'", specifier = "==4.2.0" }, { name = "protobuf", specifier = ">=6.33.5,<7" }, @@ -2443,7 +2432,6 @@ requires-dist = [ { name = "unitree-webrtc-connect-leshy", marker = "extra == 'unitree'", specifier = ">=2.0.7" }, { name = "usd-core", marker = "extra == 'sim'", specifier = ">=24.0" }, { name = "uvicorn", marker = "extra == 'web'", specifier = ">=0.34.0" }, - { name = "viser", marker = "extra == 'viz'", specifier = ">=1.0.26" }, { name = "watchdog", marker = "extra == 'dev'", specifier = ">=3.0.0" }, { name = "xacro", marker = "extra == 'manipulation'" }, { name = "xarm-python-sdk", marker = "extra == 'manipulation'", specifier = ">=1.17.0" }, @@ -2451,7 +2439,7 @@ requires-dist = [ { name = "xformers", marker = "platform_machine == 'x86_64' and extra == 'cuda'", specifier = ">=0.0.20" }, { name = "yapf", marker = "extra == 'misc'", specifier = "==0.40.2" }, ] -provides-extras = ["misc", "visualization", "agents", "web", "perception", "unitree", "unitree-dds", "manipulation", "cpu", "cuda", "dev", "psql", "sim", "viz", "navigation", "drone", "dds", "docker", "base", "all"] +provides-extras = ["misc", "visualization", "agents", "web", "perception", "unitree", "unitree-dds", "manipulation", "cpu", "cuda", "dev", "psql", "sim", "navigation", "drone", "dds", "docker", "base", "all"] [[package]] name = "dimos-lcm" @@ -2695,35 +2683,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/87/62/9773de14fe6c45c23649e98b83231fffd7b9892b6cf863251dc2afa73643/einops-0.8.1-py3-none-any.whl", hash = "sha256:919387eb55330f5757c6bea9165c5ff5cfe63a642682ea788a6d472576d81737", size = 64359, upload-time = "2025-02-09T03:17:01.998Z" }, ] -[[package]] -name = "embreex" -version = "4.4.0" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11' and platform_machine == 'x86_64'" }, - { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11' and platform_machine == 'x86_64'" }, -] -wheels = [ - { url = "https://files.pythonhosted.org/packages/14/fe/cedef264696768248f8139c569e10796ffb76627383adb5a60e1eaf28a20/embreex-4.4.0-cp310-cp310-macosx_13_0_x86_64.whl", hash = "sha256:daf8b1848798523d7d71cc22f2610401ab02ec93ea063f9cbb90dcb9abda2ccf", size = 13215487, upload-time = "2026-04-22T19:46:32.769Z" }, - { url = "https://files.pythonhosted.org/packages/11/f5/460b7f79689ac5e6ceb3ec2a1194176a0a66d6c4e010dae68ba899a1c927/embreex-4.4.0-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:f548cbebc550624ef08530ed9dcd147eeddcd181fd8f32cf3378800b39b21034", size = 14438524, upload-time = "2026-04-22T19:46:35.533Z" }, - { url = "https://files.pythonhosted.org/packages/9f/c2/aef3606d7ca2b4d2d18e57c8f65762b94d253e678a05c946649bb1913f5e/embreex-4.4.0-cp310-cp310-win_amd64.whl", hash = "sha256:58921ef7ad488dbd514b3053e7c4a9fdcd2f7008426b3185b9f1bd394c608edd", size = 13119003, upload-time = "2026-04-22T19:46:38.442Z" }, - { url = "https://files.pythonhosted.org/packages/4c/0c/1bcdcb8cb09713d40c3cc6d303a4e456113df859dacb28a1b7af8a19a718/embreex-4.4.0-cp311-cp311-macosx_13_0_x86_64.whl", hash = "sha256:96a187753f578cb685051f8fd679dc7986f887fcb922bb81a9924f5b89e941d8", size = 13214875, upload-time = "2026-04-22T19:46:43.439Z" }, - { url = "https://files.pythonhosted.org/packages/7d/1d/bed6f27a57b89ad028c8ec5adf6f1877a1ef92d983d703abb7a70717f0d9/embreex-4.4.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:8415d14c8956afec7eb05749f1e0bf396bb51efd566054ca169e10e4089e7bb7", size = 14474358, upload-time = "2026-04-22T19:46:46.056Z" }, - { url = "https://files.pythonhosted.org/packages/21/f4/c3515fde7bacab245673988398ef40928ce0b9fb54e2b51e90a4a4535479/embreex-4.4.0-cp311-cp311-win_amd64.whl", hash = "sha256:bfa54fb71cbb3a41c2366cabd09bb2dbbc8700843872f2c8655a3215a73459a7", size = 13119132, upload-time = "2026-04-22T19:46:48.753Z" }, - { url = "https://files.pythonhosted.org/packages/6d/78/8cc0960cc0f2d60d581869a66c8013e1bf1c73bf5bf9609bd8aa79e0f721/embreex-4.4.0-cp312-cp312-macosx_13_0_x86_64.whl", hash = "sha256:8e93bce7cf905365117dea2d0726d19262c88a010044d00631db6bb7dc145612", size = 13214768, upload-time = "2026-04-22T19:46:54.088Z" }, - { url = "https://files.pythonhosted.org/packages/79/b0/05a5b4d49749602b12e13d1871f8e6d1fe6db806eda75f6f57bb4f1acf6f/embreex-4.4.0-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:cb0872f5bc231f465b840b122847acbaf468ac48f49bfaff127c5347ec0db94f", size = 14529899, upload-time = "2026-04-22T19:46:56.824Z" }, - { url = "https://files.pythonhosted.org/packages/b5/96/625e035f3433071c91de07e66265a261be7bb708367f785000f93d7a992a/embreex-4.4.0-cp312-cp312-win_amd64.whl", hash = "sha256:6c092ee1adf5c48b7430c7ae3902943863745e54b4aef4327ecb3473e0a299d7", size = 13119305, upload-time = "2026-04-22T19:46:59.329Z" }, - { url = "https://files.pythonhosted.org/packages/36/d2/9bbde8d9d520c2a7bcad892631165b9676d9dcbde381f25bfda06d0f6e42/embreex-4.4.0-cp313-cp313-macosx_13_0_x86_64.whl", hash = "sha256:078bae4dcebb2a64c8dde6b3c178f258f966c4514e265608620033a6c907e21b", size = 13212105, upload-time = "2026-04-22T19:47:04.511Z" }, - { url = "https://files.pythonhosted.org/packages/03/5d/3e5ca5dea1c2c5b4604f3bedb67ea4beaa465398d9c04d8124ca3d657b05/embreex-4.4.0-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:cd305875e2cd7c51004a423fe7da9881fa266fa4a50e61dd546978e10f020e66", size = 14486730, upload-time = "2026-04-22T19:47:07.229Z" }, - { url = "https://files.pythonhosted.org/packages/45/00/26741306e557129d398744601cd9bca4069d52cebe146ba99e535f9f2c65/embreex-4.4.0-cp313-cp313-win_amd64.whl", hash = "sha256:433de9063843804d70bb3c1680619bb28bc6403b79d3d94560ec9acc3df96eda", size = 13117246, upload-time = "2026-04-22T19:47:10.08Z" }, - { url = "https://files.pythonhosted.org/packages/f5/ac/638a6b4a6cb67125a3c2676a108fb73d75e67b3ce3813f25b6056d0b77cd/embreex-4.4.0-cp314-cp314-macosx_13_0_x86_64.whl", hash = "sha256:ab3c50ecd3aa6c39491928d975b00c9f5eeaa1b39b74bab87170c17e2df1bfde", size = 13212439, upload-time = "2026-04-22T19:47:15.009Z" }, - { url = "https://files.pythonhosted.org/packages/39/1c/567194e9f5bdbb5099144dae3202452821319ff348e328b50c0fbacc3828/embreex-4.4.0-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:3b0bd41b10dc2f1ad4995faef08d924d5f33a5d47afb97ba5801c820f305db6d", size = 14480771, upload-time = "2026-04-22T19:47:17.681Z" }, - { url = "https://files.pythonhosted.org/packages/d1/8d/a46fb6ca4cc898e8d06449a4b46a8c22a28971f1e6d9bb6c99459bbb96d1/embreex-4.4.0-cp314-cp314-win_amd64.whl", hash = "sha256:80f938291832ab11dc7a604d609bce2587d574b4fe862be91d117562629f1b94", size = 13373573, upload-time = "2026-04-22T19:47:21.487Z" }, - { url = "https://files.pythonhosted.org/packages/61/5e/da7c1448c209f406a5b43a8feb07489e8652a64c48450b5642d3f34cf9e7/embreex-4.4.0-cp314-cp314t-macosx_13_0_x86_64.whl", hash = "sha256:ea332cfe60f3b242ecb557ef7b5fcbffec5edd0f3127241bed343d090ac735e2", size = 13218445, upload-time = "2026-04-22T19:47:25.847Z" }, - { url = "https://files.pythonhosted.org/packages/a5/d4/8cb8a41b25138999a98286ae1562e5903c7579ec71becc05bfa1c10d571f/embreex-4.4.0-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:1e3481b76df80f23128173486ac0efe55e9199fc311bc74707452b4f19951eff", size = 14589303, upload-time = "2026-04-22T19:47:28.544Z" }, - { url = "https://files.pythonhosted.org/packages/93/3d/8b393b35016909143ecac7bf7bf418f79236e1f83faf3867b5c5cb50c97f/embreex-4.4.0-cp314-cp314t-win_amd64.whl", hash = "sha256:a2fedc756a36729da6803425398aa4987b27d1d89e9fad403d8ef371fad5ca01", size = 13389585, upload-time = "2026-04-22T19:47:31.398Z" }, -] - [[package]] name = "empy" version = "3.3.4" @@ -3637,20 +3596,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/9c/1f/19ebc343cc71a7ffa78f17018535adc5cbdd87afb31d7c34874680148b32/ifaddr-0.2.0-py3-none-any.whl", hash = "sha256:085e0305cfe6f16ab12d72e2024030f5d52674afad6911bb1eee207177b8a748", size = 12314, upload-time = "2022-06-15T21:40:25.756Z" }, ] -[[package]] -name = "imageio" -version = "2.37.3" -source = { registry = "https://pypi.org/simple" } -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 = "pillow" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/b1/84/93bcd1300216ea50811cee96873b84a1bebf8d0489ffaf7f2a3756bab866/imageio-2.37.3.tar.gz", hash = "sha256:bbb37efbfc4c400fcd534b367b91fcd66d5da639aaa138034431a1c5e0a41451", size = 389673, upload-time = "2026-03-09T11:31:12.573Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/49/fa/391e437a34e55095173dca5f24070d89cbc233ff85bf1c29c93248c6588d/imageio-2.37.3-py3-none-any.whl", hash = "sha256:46f5bb8522cd421c0f5ae104d8268f569d856b29eb1a13b92829d1970f32c9f0", size = 317646, upload-time = "2026-03-09T11:31:10.771Z" }, -] - [[package]] name = "importlib-metadata" version = "8.7.1" @@ -5070,118 +5015,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/ca/28/2635a8141c9a4f4bc23f5135a92bbcf48d928d8ca094088c962df1879d64/lz4-4.4.5-cp314-cp314-win_arm64.whl", hash = "sha256:d994b87abaa7a88ceb7a37c90f547b8284ff9da694e6afcfaa8568d739faf3f7", size = 93812, upload-time = "2025-11-03T13:02:26.133Z" }, ] -[[package]] -name = "manifold3d" -version = "3.4.1" -source = { registry = "https://pypi.org/simple" } -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' and python_full_version < '3.14'" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/b0/fd/4dfc246e076e3912c45a821764f4de8b6c8117fa36fc67f8e44bf9dfe59b/manifold3d-3.4.1.tar.gz", hash = "sha256:b517927e2c15dc52169fff0cd12e1949eceb4ca49f3a5b8c0568b1116a561ab1", size = 269275, upload-time = "2026-03-24T06:22:40.062Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/5b/43/9ce593ad180d69f802e7b9837da95567c30e6af3cb1b66f3c254d0eb4445/manifold3d-3.4.1-cp310-cp310-macosx_10_14_universal2.whl", hash = "sha256:2ec55079d4c4ada4aaa3708559a473b41817ed9d226c61e1a6d43b0ef17390c5", size = 1739369, upload-time = "2026-03-24T06:21:35.762Z" }, - { url = "https://files.pythonhosted.org/packages/6a/7a/547b4098cffecedc5e4dc5d8eb753d8ede90bed5b325e75476ae5edb7340/manifold3d-3.4.1-cp310-cp310-macosx_10_14_x86_64.whl", hash = "sha256:6cf5abadc56c094fbaf135e2474db79ade3dba6210bb9b7aff90d48361c328b1", size = 942685, upload-time = "2026-03-24T06:21:37.512Z" }, - { url = "https://files.pythonhosted.org/packages/4e/94/f8baf4269dcd34d4d1a4ef42c4724231f5fc57a81f0ad65fcbade2cdf00d/manifold3d-3.4.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:274d87ead558f0e29eec874e588789200f578b6132b3bd8e4ce4e1da21fe10a8", size = 828147, upload-time = "2026-03-24T06:21:39.172Z" }, - { url = "https://files.pythonhosted.org/packages/94/c9/8a634c6304c0a9f4d0ca1c59cf798f90a3ad174d32d9390a7b938b0f7bf5/manifold3d-3.4.1-cp310-cp310-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0002baedc42cb1562cf723d0362ef99a9675bf5455dabd1d9ba893868a132ad0", size = 1238708, upload-time = "2026-03-24T06:21:40.623Z" }, - { url = "https://files.pythonhosted.org/packages/a9/62/3df433dce9f87e7a4d76bbdbb6339a70a674fd8e350055bf88b4085c1e80/manifold3d-3.4.1-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:308e3dda79236b9258dd0d13cfc56f932a372ca5f56677bb06ed65585a447045", size = 1340136, upload-time = "2026-03-24T06:21:42.013Z" }, - { url = "https://files.pythonhosted.org/packages/cc/65/462e5422e39f7e57a28281bb5c5c55b7a1a50f71bcbbc34730ade5f3fb33/manifold3d-3.4.1-cp310-cp310-win_amd64.whl", hash = "sha256:ef8d5bb14f827738179d472f9deeb43323e82b92afe9ee359c175120ce5194d0", size = 970295, upload-time = "2026-03-24T06:21:43.654Z" }, - { url = "https://files.pythonhosted.org/packages/af/14/42f1d0fbe0dbbaf7abd9ffb83596a84cea7b3d84c40f0c20a3474a23e397/manifold3d-3.4.1-cp311-cp311-macosx_10_14_universal2.whl", hash = "sha256:5b4ba7b71ffd6bf16682acff89cb72ade3eba54ea05d58d956c3a95d982ed8e4", size = 1753383, upload-time = "2026-03-24T06:21:45.602Z" }, - { url = "https://files.pythonhosted.org/packages/35/47/3d5369c2485c48c2510eab4e803b29296edecbce78c9069995731bff9635/manifold3d-3.4.1-cp311-cp311-macosx_10_14_x86_64.whl", hash = "sha256:095b072e89485f00af8aeed0a88e72c19f9740467824d6653b329851c3928c14", size = 956296, upload-time = "2026-03-24T06:21:47.257Z" }, - { url = "https://files.pythonhosted.org/packages/75/d4/d01a5579b636e49a106071365f82d0c7a695226cbc6dc077304e51bfc86f/manifold3d-3.4.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:539c2467abc58754b74dc9bb3422ddd4e73a5b11b006f27c0ba6302bab6ecfe9", size = 841995, upload-time = "2026-03-24T06:21:48.529Z" }, - { url = "https://files.pythonhosted.org/packages/d8/63/32c64efc0a34f23776dc339f8b1cdbcc61b12a80ade261f2e7a358af52d9/manifold3d-3.4.1-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:42c0c8ab2495acd514e8f46e5acd9465937c46c8c06e45e2f02da983b849bcea", size = 1252454, upload-time = "2026-03-24T06:21:50.317Z" }, - { url = "https://files.pythonhosted.org/packages/d7/f2/6c7ec5986bc3cfc9251878ade6e65354538a8bc569c5e51c483aa4310063/manifold3d-3.4.1-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:aa75de877ccda5482493f65659de240d4bb7c96e3cc4ce96509ecd6ef9f91fbc", size = 1353505, upload-time = "2026-03-24T06:21:52.428Z" }, - { url = "https://files.pythonhosted.org/packages/94/61/9e8ab3a9ce6e7e6099794afd25abe1e4e7934f31529c55331bf8019bc736/manifold3d-3.4.1-cp311-cp311-win_amd64.whl", hash = "sha256:2aff8707558e2fa5ff241185fe71da18ac8bd4156fb2811401df3366e461c562", size = 983641, upload-time = "2026-03-24T06:21:53.876Z" }, - { url = "https://files.pythonhosted.org/packages/d9/59/def4c589dd55aa32026a720f8a31d71aa2162fef8e3963b6241a7945ef4e/manifold3d-3.4.1-cp312-cp312-macosx_10_14_universal2.whl", hash = "sha256:967c89daf24ec9ff863323d593cce98e4c130abbaaa9504df6789f9d8c780d0d", size = 1752517, upload-time = "2026-03-24T06:21:55.203Z" }, - { url = "https://files.pythonhosted.org/packages/b1/a9/377800999cc8421ce8bfa40787d09570bb635e0099f44959170fee751dd7/manifold3d-3.4.1-cp312-cp312-macosx_10_14_x86_64.whl", hash = "sha256:c29db9a1bda414ecaa56dd2cd274f06bbbe740e463133c5b69943d82c3dcfb96", size = 956343, upload-time = "2026-03-24T06:21:57.134Z" }, - { url = "https://files.pythonhosted.org/packages/6a/72/7f988a0deae9b3fbed3a6b2e9285e96fd9105e95f6755f5457e3a80e103e/manifold3d-3.4.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2ae6855a6f652acd89e228f1981e5b710d4b10e06d7c06e5bada3b3fb31904a3", size = 840924, upload-time = "2026-03-24T06:21:58.462Z" }, - { url = "https://files.pythonhosted.org/packages/bf/46/787ad4b53a35ccf1d31fbd3d2ffe0653dab67057b1f561db51d2edc494ba/manifold3d-3.4.1-cp312-cp312-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:a8068f85416034e290d23b424f2bea15d2f1da1c5ccb79b442bdb50ed4e1a4b6", size = 1253014, upload-time = "2026-03-24T06:21:59.734Z" }, - { url = "https://files.pythonhosted.org/packages/e2/45/29d2380ac477b11629a72483b21dd544861caccaedbc87043bf315a15a50/manifold3d-3.4.1-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:fe9ff5ce3d949c72b21120318121eb926ddba4299eab0e8bab2c6784a9843ffb", size = 1355512, upload-time = "2026-03-24T06:22:01.518Z" }, - { url = "https://files.pythonhosted.org/packages/7f/7f/310688a725a5a23d00e9f29e614a2b7906b399df27731b1aa6e153e4f465/manifold3d-3.4.1-cp312-cp312-win_amd64.whl", hash = "sha256:1bd6fa1b20238603ec3df7f6060ddba1181cf9464104e82b746747b487d12092", size = 983293, upload-time = "2026-03-24T06:22:03.273Z" }, - { url = "https://files.pythonhosted.org/packages/e3/d0/b066b476242dddfad98db51425a28ac41ab008a4e7697f6d6bca21a24881/manifold3d-3.4.1-cp313-cp313-macosx_10_14_universal2.whl", hash = "sha256:210ec6918870611d9e3f888c00657aad842cfa89a7967e94546a568bf8dfc2f1", size = 1752343, upload-time = "2026-03-24T06:22:04.731Z" }, - { url = "https://files.pythonhosted.org/packages/11/2c/10b5cb142b00bb7b14bb5698c584ce7722c68c3ed58ae4173693a35d2108/manifold3d-3.4.1-cp313-cp313-macosx_10_14_x86_64.whl", hash = "sha256:d4e1dd76a3c5fe935bc14eb62f98ce2361e0e505fcfca08abb2f9d8a1d01e0db", size = 956241, upload-time = "2026-03-24T06:22:06.404Z" }, - { url = "https://files.pythonhosted.org/packages/05/a7/af84e5f6e6af2d07d800355345ffb303c4e8de96dbf3194633322f3d8335/manifold3d-3.4.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:7e1bf4857f64311fb5113ff286898c47efc0f199e4d860cfc663b5f69ce90ede", size = 840900, upload-time = "2026-03-24T06:22:07.974Z" }, - { url = "https://files.pythonhosted.org/packages/80/1c/f274d6e35652c3fb72b54c5fcafc5fc474e1a93d3fd17fb8df3c9c765873/manifold3d-3.4.1-cp313-cp313-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:9b23435456d5ed64e48a34a281869c3b626da8ccd8872e54637b77f420716f9a", size = 1252521, upload-time = "2026-03-24T06:22:09.259Z" }, - { url = "https://files.pythonhosted.org/packages/97/90/82081bcbffc68e36f9f34c36f041d6e0176cbb462e9041683d82ff17b626/manifold3d-3.4.1-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6871adaf9e5081303d2c9446de5a76a9af84bcf938949fa198cc5f0ae9cad19f", size = 1355366, upload-time = "2026-03-24T06:22:10.892Z" }, - { url = "https://files.pythonhosted.org/packages/0d/db/26df1d96a2c61a4d79aeb0ca2f8bfbfd4af94fdb944469dda38ced240f2f/manifold3d-3.4.1-cp313-cp313-win_amd64.whl", hash = "sha256:0a93e8202cccea16c76a6c3a7d02300755cccea6536874ccfc160f8c4d8948c4", size = 983317, upload-time = "2026-03-24T06:22:12.257Z" }, - { url = "https://files.pythonhosted.org/packages/26/50/d62f9fed01bdeaea50d3dd821498573c0bf1c286e54e5a632f47cef8fffa/manifold3d-3.4.1-cp314-cp314-macosx_10_15_universal2.whl", hash = "sha256:632525867f23a5d34ab4a7b9129dc440a6ed2b4a0444d9feddb6069361107555", size = 1752191, upload-time = "2026-03-24T06:22:13.521Z" }, - { url = "https://files.pythonhosted.org/packages/1c/2e/464f3898f8f1b727a248d4b2bedc310d60efed1a0f43f9977f95f122fcf4/manifold3d-3.4.1-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:c4e755c0a1d808603185fb5a562c045c71918b4e64a498c489eba658df49692b", size = 956239, upload-time = "2026-03-24T06:22:14.864Z" }, - { url = "https://files.pythonhosted.org/packages/0e/ec/da4bdba9ae1fe9049be9e2f42336ebf700dfd839795b561fb0cee9cb03f6/manifold3d-3.4.1-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:2c9c20b479e15ec5f0710951d3ae4f95635d0bbf6502f03e43ed87e310e69230", size = 840646, upload-time = "2026-03-24T06:22:16.471Z" }, - { url = "https://files.pythonhosted.org/packages/eb/e0/c476d79d5940da31cf6d0aa9353e56d70fe709fefbadd3c99804594aeb4d/manifold3d-3.4.1-cp314-cp314-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:145b94b7bb73b425fa42bb795d5c8eaea5de5e45cba9731f2542c7311f3a73c3", size = 1253522, upload-time = "2026-03-24T06:22:17.734Z" }, - { url = "https://files.pythonhosted.org/packages/89/fa/2d5838248950b8cb41ba22496dfc7e95222582761ec83e473a210a0be059/manifold3d-3.4.1-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:1093c002a5f5c012219208bfb0b49f4821974f887cbd357316b9dbab74b7fa5b", size = 1356044, upload-time = "2026-03-24T06:22:19.375Z" }, - { url = "https://files.pythonhosted.org/packages/95/a7/2b8e4b88a613b0057b871ca71342d7237289c5eccf2f75ce10afa04e080e/manifold3d-3.4.1-cp314-cp314-win_amd64.whl", hash = "sha256:04c99b94fbb92572051288d3c6163baf9c81a647dab33d1fdce418457b0a1a44", size = 1014216, upload-time = "2026-03-24T06:22:20.977Z" }, - { url = "https://files.pythonhosted.org/packages/4f/06/c8c5e38b5f93ce2268aa0fc2e4e995a04c8722045868dc75021a7c2a5bc9/manifold3d-3.4.1-cp314-cp314t-macosx_10_15_universal2.whl", hash = "sha256:22bb8c202c88072fd5cd3fb24243715e7b200151a8aa3da78661b3611e07924f", size = 1760559, upload-time = "2026-03-24T06:22:22.701Z" }, - { url = "https://files.pythonhosted.org/packages/7e/93/5defaadef6a57bb864a51f68c824435929a7c7de1205f95e166325cba55e/manifold3d-3.4.1-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:9ade2f14cf906271604ccfa5c49bb5704f0c14b08367e6d3aa0c4ed6ed56f919", size = 961249, upload-time = "2026-03-24T06:22:24.364Z" }, - { url = "https://files.pythonhosted.org/packages/fd/fa/5705986493097e268f26d87b3cfce8e966f6c62a1b8f38fa4086b704cf4d/manifold3d-3.4.1-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:b4b24047cf423b024f477c09e2c44fed5991cbca4906abf34bf6ced62f37ef93", size = 846070, upload-time = "2026-03-24T06:22:25.946Z" }, - { url = "https://files.pythonhosted.org/packages/2a/84/925d96698fbd90e9990a7a4fdd9a7a8b038e166de696673cfd141bf54e85/manifold3d-3.4.1-cp314-cp314t-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:2e02108ee43c6dcf1f40b208569ad49dcf1a6ceed21fd6d5fd6e8f09c02a8b60", size = 1260343, upload-time = "2026-03-24T06:22:27.266Z" }, - { url = "https://files.pythonhosted.org/packages/07/0a/f2d1c6390ebd565fa44357cddc9e6aa783fbccb0cc952996217bcbc69699/manifold3d-3.4.1-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:b1ac2b29c6ca1412f63a1ac2c240ae067fe03f666bb12a21729012275fbbde85", size = 1361860, upload-time = "2026-03-24T06:22:28.945Z" }, - { url = "https://files.pythonhosted.org/packages/8b/9b/5d0cf29530e31c2ef66cc9b2780031a82955002ad924b0eb23ac5e3dd90f/manifold3d-3.4.1-cp314-cp314t-win_amd64.whl", hash = "sha256:4d3f795cfcaa857f4bd9bf62bd3f15061bae502fb4cea87e820f4bba67045ff8", size = 1022928, upload-time = "2026-03-24T06:22:30.285Z" }, -] - -[[package]] -name = "mapbox-earcut" -version = "2.0.0" -source = { registry = "https://pypi.org/simple" } -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'" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/bc/7b/bbf6b00488662be5d2eb7a188222c264b6f713bac10dc4a77bf37a4cb4b6/mapbox_earcut-2.0.0.tar.gz", hash = "sha256:81eab6b86cf99551deb698b98e3f7502c57900e5c479df15e1bdaf1a57f0f9d6", size = 39934, upload-time = "2025-11-16T18:41:27.251Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/a8/d3/5222339a8fad091bf64f2e3041e48606d69d69f0609a7632ca17a8a05d5a/mapbox_earcut-2.0.0-cp310-cp310-macosx_10_13_x86_64.whl", hash = "sha256:c9a1dab7529f8e54bdb377f908e56f1e2b9a7e27ed168c64d3c7c38ed04ac201", size = 55920, upload-time = "2025-11-16T18:40:09.254Z" }, - { url = "https://files.pythonhosted.org/packages/19/e4/88d06e83ab75db2f4ae140a1e03ad8f84b02ac8af585dd61108aba73b8ed/mapbox_earcut-2.0.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:5e5953098ea198253c8a40e2f282ca5b04d50ec2b9661e20c4cd2b2be39f0bb0", size = 52557, upload-time = "2025-11-16T18:40:10.536Z" }, - { url = "https://files.pythonhosted.org/packages/22/88/abefd244ea049e42334c5f7a9e3b58f4ec3c84d063119ba3c8d27ff31932/mapbox_earcut-2.0.0-cp310-cp310-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:efe5fd5de409e3b6d13907e73f295c8f1d63bdb6b8ca155dde4c93865796eafe", size = 56950, upload-time = "2025-11-16T18:40:11.905Z" }, - { url = "https://files.pythonhosted.org/packages/3c/e2/11122fddd086b930502eb4a954735da0f75e9d658fdab2d9e5914b9ebd2a/mapbox_earcut-2.0.0-cp310-cp310-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:cd04da6edbca1dd68ddbfac2398a95c763f35d7317fed227fde5b3aff1253b18", size = 59618, upload-time = "2025-11-16T18:40:13.017Z" }, - { url = "https://files.pythonhosted.org/packages/e8/fd/e62195729daa3111fe95404a99c7a6b3aa174800373d10111b7e7278a789/mapbox_earcut-2.0.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:8bdb8881e857d6d9277df696e9cfb8749c00d6162021d9359cba9da58dfdd4f5", size = 153021, upload-time = "2025-11-16T18:40:14.294Z" }, - { url = "https://files.pythonhosted.org/packages/2c/6a/d39ebaaa9010ea6c9f4d468f8812b1a1b31a40fba4f02ff29bc1bf321c30/mapbox_earcut-2.0.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:6e2d1bf5af90d5857955775b4d8ea15b02e172f2a8f194bba50ff95f8ff3e80e", size = 157736, upload-time = "2025-11-16T18:40:16.344Z" }, - { url = "https://files.pythonhosted.org/packages/20/00/6a59cdb8d8c1bf7e3cc92f0404f68fdb1a3cb0bbb0837af0dbb93d6290a6/mapbox_earcut-2.0.0-cp310-cp310-win32.whl", hash = "sha256:5b0aa63dd890d712343095b05eb7b60e071912ad3ced1fc4187d6a6a739677bc", size = 51564, upload-time = "2025-11-16T18:40:17.852Z" }, - { url = "https://files.pythonhosted.org/packages/bc/7b/af69669c959d8f7fd1bd49c15deace2360bf6a79dad7bf9f7a7f1c137da6/mapbox_earcut-2.0.0-cp310-cp310-win_amd64.whl", hash = "sha256:b1355f13af89ea815b32f59a5455db295c965d51ab501bde0459cddc010a7149", size = 56793, upload-time = "2025-11-16T18:40:18.953Z" }, - { url = "https://files.pythonhosted.org/packages/07/9f/fbd15d9e348e75e986d6912c4eab99888106b7e5fb0a01e765422f7cd464/mapbox_earcut-2.0.0-cp311-cp311-macosx_10_13_x86_64.whl", hash = "sha256:9b5040e79e3783295e99c90277f31c1cbaddd3335297275331995ba5680e3649", size = 55773, upload-time = "2025-11-16T18:40:20.045Z" }, - { url = "https://files.pythonhosted.org/packages/72/40/be761298704fbbaa81c5618bb306f1510fb068e482f6a1c8b3b6c1b31479/mapbox_earcut-2.0.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:1cf43baafec3ef1e967319d9b5da96bc6ddf3dbb204b6f3535275eda4b519a72", size = 52444, upload-time = "2025-11-16T18:40:21.501Z" }, - { url = "https://files.pythonhosted.org/packages/5a/0b/0c0c08db9663238ffb82c48259582dc0047a3255d98c0ac83c48026b7544/mapbox_earcut-2.0.0-cp311-cp311-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:3a283531847f603dd9d69afb75b21bd009d385ca9485fcd3e5a7fa5db1ccd913", size = 56803, upload-time = "2025-11-16T18:40:22.891Z" }, - { url = "https://files.pythonhosted.org/packages/f0/4a/86796859383d7d11fa5d4bcf1983f94c6cbb9eeb60fb3bab527fec4b32fa/mapbox_earcut-2.0.0-cp311-cp311-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:ab697676f4cec4572d4e941b7a3429a6687bf2ac6e8db3f3781024e3239ae3a0", size = 59403, upload-time = "2025-11-16T18:40:24.021Z" }, - { url = "https://files.pythonhosted.org/packages/6c/db/adaf981ab3bcfcf993ef317636b1f27210d6834bb1e8d63db6ad7c08214a/mapbox_earcut-2.0.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:f1bdac76e048f4299accf4eaf797079ddfc330442e7231c15535ed198100d6c5", size = 152876, upload-time = "2025-11-16T18:40:25.588Z" }, - { url = "https://files.pythonhosted.org/packages/d2/83/86417974039e7554c9e1e55c852a7e9c2a1390d64675eb85d70e5fa7eb37/mapbox_earcut-2.0.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:4a6945b23f859bef11ce3194303d17bd371c86b637e7029f81b1feaff3db3758", size = 157548, upload-time = "2025-11-16T18:40:27.202Z" }, - { url = "https://files.pythonhosted.org/packages/aa/4c/c82a292bb21e5c651d81334123db2d654c5c9d19b2197080d3429dc1e49a/mapbox_earcut-2.0.0-cp311-cp311-win32.whl", hash = "sha256:8e119524c29406afb5eaa15e933f297d35679293a3ca62ced22f97a14c484cb5", size = 51424, upload-time = "2025-11-16T18:40:28.415Z" }, - { url = "https://files.pythonhosted.org/packages/30/57/6c39d7db81f72a3e4814ef152c8fb8dfe275dc4b03c9bfa073d251e3755f/mapbox_earcut-2.0.0-cp311-cp311-win_amd64.whl", hash = "sha256:378bbbb3304e446023752db8f44ecd6e7ef965bcbda36541d2ae64442ba94254", size = 56662, upload-time = "2025-11-16T18:40:29.863Z" }, - { url = "https://files.pythonhosted.org/packages/f4/d6/a1ef6e196b3d6968bf6546d4f7e54c559f9cff8991fdb880df0ba1618f52/mapbox_earcut-2.0.0-cp311-cp311-win_arm64.whl", hash = "sha256:6d249a431abd6bbff36f1fd0493247a86de962244cc4081b4d5050b02ed48fb1", size = 50505, upload-time = "2025-11-16T18:40:30.992Z" }, - { url = "https://files.pythonhosted.org/packages/8d/93/846804029d955c3c841d8efff77c2b0e8d9aab057d3a077dc8e3f88b5ea4/mapbox_earcut-2.0.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:db55ce18e698bc9d90914ee7d4f8c3e4d23827456ece7c5d7a1ec91e90c7122b", size = 55623, upload-time = "2025-11-16T18:40:32.113Z" }, - { url = "https://files.pythonhosted.org/packages/d3/f6/cc9ece104bc3876b350dba6fef7f34fb7b20ecc028d2cdbdbecb436b1ed1/mapbox_earcut-2.0.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:01dd6099d16123baf582a11b2bd1d59ce848498cf0cdca3812fd1f8b20ff33b7", size = 52028, upload-time = "2025-11-16T18:40:33.516Z" }, - { url = "https://files.pythonhosted.org/packages/88/6e/230da4aabcc56c99e9bddb4c43ce7d4ba3609c0caf2d316fb26535d7c60c/mapbox_earcut-2.0.0-cp312-cp312-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:2d5a098aae26a52282bc981a38e7bf6b889d2ea7442f2cd1903d2ba842f4ff07", size = 56351, upload-time = "2025-11-16T18:40:35.217Z" }, - { url = "https://files.pythonhosted.org/packages/1a/f7/5cdd3752526e91d91336c7263af7767b291d21e63c89d7190a60051f0f87/mapbox_earcut-2.0.0-cp312-cp312-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:de35f241d0b9110ad9260f295acedd9d7cc0d7acfe30d36b1b3ee8419c2caba1", size = 59209, upload-time = "2025-11-16T18:40:36.634Z" }, - { url = "https://files.pythonhosted.org/packages/7b/a2/b7781416cb93b37b95d0444e03f87184de8815e57ff202ce4105fa921325/mapbox_earcut-2.0.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:6cb63ab85e2e430c350f93e75c13f8b91cb8c8a045f3cd714c390b69a720368a", size = 152316, upload-time = "2025-11-16T18:40:38.147Z" }, - { url = "https://files.pythonhosted.org/packages/c1/74/396338e3d345e4e36fb23a0380921098b6a95ce7fb19c4777f4185a5974e/mapbox_earcut-2.0.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:fb3c9f069fc3795306db87f8139f70c4f047532f897a3de05f54dc1faebc97f6", size = 157268, upload-time = "2025-11-16T18:40:39.753Z" }, - { url = "https://files.pythonhosted.org/packages/56/2c/66fd137ea86c508f6cd7247f7f6e2d1dabffc9f0e9ccf14c71406b197af1/mapbox_earcut-2.0.0-cp312-cp312-win32.whl", hash = "sha256:eb290e6676217707ed238dd55e07b0a8ca3ab928f6a27c4afefb2ff3af08d7cb", size = 51226, upload-time = "2025-11-16T18:40:41.018Z" }, - { url = "https://files.pythonhosted.org/packages/b8/84/7b78e37b0c2109243c0dad7d9ba9774b02fcee228bf61cf727a5aa1702e2/mapbox_earcut-2.0.0-cp312-cp312-win_amd64.whl", hash = "sha256:5ef5b3319a43375272ad2cad9333ed16e569b5102e32a4241451358897e6f6ee", size = 56417, upload-time = "2025-11-16T18:40:42.173Z" }, - { url = "https://files.pythonhosted.org/packages/75/7f/cd7195aa27c1c8f2b9d38025a5a8663f32cd01c07b648a54b1308ab26c15/mapbox_earcut-2.0.0-cp312-cp312-win_arm64.whl", hash = "sha256:a4a3706feb5cc8c782d8f68bb0110c8d551304043f680a87a54b0651a2c208c3", size = 50111, upload-time = "2025-11-16T18:40:43.334Z" }, - { url = "https://files.pythonhosted.org/packages/8b/7c/c5dd5b255b9828ba5df729e62fdd470a322c938f07ef392ca03c0592bb3a/mapbox_earcut-2.0.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:582329a81bd36cf0f82e443c395bcb8cfdb10caddafec76acaebac7c20bf1c31", size = 55619, upload-time = "2025-11-16T18:40:44.44Z" }, - { url = "https://files.pythonhosted.org/packages/1a/3f/03f23eac9831e7d0d8da3d6993695a9a3724659c94e9997f6b7aaccc199d/mapbox_earcut-2.0.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:d2ac5f610b3e44a3a0c4df06b5552d503b4f1c2c409eeca20dbe05112bd60955", size = 52023, upload-time = "2025-11-16T18:40:45.857Z" }, - { url = "https://files.pythonhosted.org/packages/39/f3/a92ccee494b3e437e4bd81ecd358e39d231dc90af010d6c43930506c10ad/mapbox_earcut-2.0.0-cp313-cp313-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:58cc88513b87734b243d86f0d3fb87e96e0a78d9abd8fd615c55f766dd63f949", size = 56357, upload-time = "2025-11-16T18:40:47.27Z" }, - { url = "https://files.pythonhosted.org/packages/03/30/e54ececd0403a5495c340b693075abec92a6d17dc44283b6cb059534f7ed/mapbox_earcut-2.0.0-cp313-cp313-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:40218d887798451932f3c335992834aa807c35cd497c6e0733470fdbd77f9521", size = 59215, upload-time = "2025-11-16T18:40:48.682Z" }, - { url = "https://files.pythonhosted.org/packages/6e/e1/8fbff13a074c1fbf702b30ce7ec4d878bc664d659c1c2b1697831f4ea3a8/mapbox_earcut-2.0.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:39fa5cfa0e855b028ec9b0200c88ebfa252448f343ce2f67b6fc07fe1f22a3ae", size = 152304, upload-time = "2025-11-16T18:40:49.85Z" }, - { url = "https://files.pythonhosted.org/packages/b9/d5/c757030b3cb3a9f2278ded6f7312d2b9d3761db6f3da8d395f7f7303dd66/mapbox_earcut-2.0.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:476b558473b8a43f238d46e819bc0f830c427842ec5feb19e23b4dcac8ad2455", size = 157270, upload-time = "2025-11-16T18:40:51.093Z" }, - { url = "https://files.pythonhosted.org/packages/96/63/589c6decb1f032d8811f1066da552f0a718830f592e6d6539fa4c3c766b8/mapbox_earcut-2.0.0-cp313-cp313-win32.whl", hash = "sha256:8c2d125c182acbc490b39503c0dec4f937bae180d0849a26bcea0ee4a76024bd", size = 51207, upload-time = "2025-11-16T18:40:52.285Z" }, - { url = "https://files.pythonhosted.org/packages/76/75/a79a6020c46d4f07731e88ec5cc9324f6b43343aba835def1dc0bf59fecf/mapbox_earcut-2.0.0-cp313-cp313-win_amd64.whl", hash = "sha256:e049e6a37c228d7a9cb2f54ae405aa21d35c5175d849530fb32064ddb38ad5ab", size = 56416, upload-time = "2025-11-16T18:40:53.474Z" }, - { url = "https://files.pythonhosted.org/packages/ce/5f/83e878c2b3e9e6db1f60b598a2cc5ed4c2b5bc8d281575c964869414a159/mapbox_earcut-2.0.0-cp313-cp313-win_arm64.whl", hash = "sha256:8a833d73d63d4b6291bbd8b4d2f551e87f663282cdc547ecbbd9b423849ee996", size = 50103, upload-time = "2025-11-16T18:40:54.954Z" }, - { url = "https://files.pythonhosted.org/packages/96/fc/f1b74324c83f510213ff91eb8b1d2697ad5a12418c5fba966e80f1104a5f/mapbox_earcut-2.0.0-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:ad1dc141797037b7d4c9d8d2e52b9665b36294913a8ec31008b282d1a95b9bdc", size = 55728, upload-time = "2025-11-16T18:40:56.098Z" }, - { url = "https://files.pythonhosted.org/packages/7b/59/053c04e29c4bd22157d3b6255f1e5c19c46cb7a594c4314298bdcbca723f/mapbox_earcut-2.0.0-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:0f0f5c6f5ed8ffdce8efe6a003ba598089d0ee07eabd41868db183be50484f9f", size = 52063, upload-time = "2025-11-16T18:40:57.227Z" }, - { url = "https://files.pythonhosted.org/packages/a6/77/acc2d553c3bb8c769535a280545bb7d9608141e90511a2e6215a54611776/mapbox_earcut-2.0.0-cp314-cp314-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:82cd92775f37fd1e4b8464c5e74a00e87130eecc55ee3df2492b8ca2bdf6ef3e", size = 56522, upload-time = "2025-11-16T18:40:58.349Z" }, - { url = "https://files.pythonhosted.org/packages/1a/f5/627dd6defd3c1a2b3069e9e27482aa04d268c841735e576c1e22848a34f6/mapbox_earcut-2.0.0-cp314-cp314-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:626ffc1310e0cc8910283e4ac3139e5fb0458f18f2c4874162f66159951933ff", size = 59204, upload-time = "2025-11-16T18:41:00.095Z" }, - { url = "https://files.pythonhosted.org/packages/4a/3e/819185542ab095ba1244ad65ececb3edcde6fd0111248a0f9318d695bfcf/mapbox_earcut-2.0.0-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:ea951d764a356cad95b23fef950d8aa3b44b933795ad09d977fea7d4dbe377c3", size = 152550, upload-time = "2025-11-16T18:41:01.233Z" }, - { url = "https://files.pythonhosted.org/packages/a9/ad/85e0f815e4774b90ad6761bce55c80d13ee21b2a24014b0be0d5010b0049/mapbox_earcut-2.0.0-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:df1f217624abb5e02ecabcbd84369de970b8d8bc1e4e7c164c1cfcaddad76ca3", size = 157322, upload-time = "2025-11-16T18:41:02.866Z" }, - { url = "https://files.pythonhosted.org/packages/27/4c/0f56369e7a000d2f3177d17baf34263559b206ae524fcd0c4c5d1d960dab/mapbox_earcut-2.0.0-cp314-cp314-win32.whl", hash = "sha256:6fa61307d38b50fc9bd5449c00dbae46d270a32b372c6fc3b8af4b85c85746e4", size = 52916, upload-time = "2025-11-16T18:41:04.122Z" }, - { url = "https://files.pythonhosted.org/packages/c2/9d/8c557dd9b3d9fe2344f5bd5ff3bb0b2a42ed6addb7e43ca4358051743b04/mapbox_earcut-2.0.0-cp314-cp314-win_amd64.whl", hash = "sha256:0da20ed3c81b240450118773bcedfac34e70a56998f66147222c46f4356fff67", size = 57713, upload-time = "2025-11-16T18:41:05.204Z" }, - { url = "https://files.pythonhosted.org/packages/3b/ec/678c5553938d3a29d02dd41dd898672267f054afc4e2821958dee6ec86ce/mapbox_earcut-2.0.0-cp314-cp314-win_arm64.whl", hash = "sha256:847e74bd5878e4c64793dc100f9288f5443f87c55c3fe391fd90509029136ff6", size = 51872, upload-time = "2025-11-16T18:41:06.323Z" }, - { url = "https://files.pythonhosted.org/packages/18/37/94f2d973669cbfef811e536713fe56ec012ba74e5f8795a832337b1866a3/mapbox_earcut-2.0.0-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:ddc9e7175fc903185c64afbbf91febee56b50787dd0962fce2bfb4f20cf80d27", size = 56447, upload-time = "2025-11-16T18:41:07.443Z" }, - { url = "https://files.pythonhosted.org/packages/c9/1c/e0afcc82659cc1727a7e59c4f9e9880bbc3f048a4a5325772b44d4a91dfd/mapbox_earcut-2.0.0-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:6dc8a7568066af9a858018d6d92b7e77e164578f9fcd79093f1cbe4ec203461b", size = 53154, upload-time = "2025-11-16T18:41:08.618Z" }, - { url = "https://files.pythonhosted.org/packages/6c/2d/9845281c8c35da2bea733b8c2df5b9fe694e73e7b05fe8a1d4c3c439a1bc/mapbox_earcut-2.0.0-cp314-cp314t-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:6abc5340edd9b433ab2dab2ee033082a199d5c51cce445124626c0040ec0d81b", size = 56285, upload-time = "2025-11-16T18:41:09.728Z" }, - { url = "https://files.pythonhosted.org/packages/97/8e/eeea762a519490662b8f480e2b35bf03701b0bcc5a446b62a4c5a1500b06/mapbox_earcut-2.0.0-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:df7afdd8078a9aa28f469d9242531d304e09a4b14e514f048e021a949f3777b4", size = 58601, upload-time = "2025-11-16T18:41:10.872Z" }, - { url = "https://files.pythonhosted.org/packages/b9/67/932f80aa6af9bc1a317b6119052c74f327d81e00b457003a049e324b810c/mapbox_earcut-2.0.0-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:1a286f73e612a46cafd6d6c843365265090517af16823e2f37277c13cd8b6f09", size = 154924, upload-time = "2025-11-16T18:41:12.104Z" }, - { url = "https://files.pythonhosted.org/packages/87/38/5db4a91f9f90cbb447be61da5468a2955fad3a840ae4c7dbde789b09d45a/mapbox_earcut-2.0.0-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:8d081fe1d00dc553e3e68c02fc395324aad0d8ed955f3ff59289264c9b21ace4", size = 159194, upload-time = "2025-11-16T18:41:13.364Z" }, - { url = "https://files.pythonhosted.org/packages/6b/03/de3843b13fe854a010fb2f8b25551d4d5fe1c879ff2e7c8d7d8d7d735a8e/mapbox_earcut-2.0.0-cp314-cp314t-win32.whl", hash = "sha256:13049ca96431bbc7ef7fd7780dd1872209ca11a5c1977f7aa91a1b574a8af863", size = 54143, upload-time = "2025-11-16T18:41:14.564Z" }, - { url = "https://files.pythonhosted.org/packages/9a/89/fbdee5a56ba51df9be6098b5428636ad75aa994e98d8bec6113d5cba401e/mapbox_earcut-2.0.0-cp314-cp314t-win_amd64.whl", hash = "sha256:6ace78e4fdba3b8cbb7768d44d77a981698305862a07f94bbb6f5cc16659adb4", size = 60833, upload-time = "2025-11-16T18:41:15.694Z" }, -] - [[package]] name = "markdown" version = "3.10.2" @@ -5773,62 +5606,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/81/f2/08ace4142eb281c12701fc3b93a10795e4d4dc7f753911d836675050f886/msgpack-1.1.2-cp314-cp314t-win_arm64.whl", hash = "sha256:d99ef64f349d5ec3293688e91486c5fdb925ed03807f64d98d205d2713c60b46", size = 70868, upload-time = "2025-10-08T09:15:44.959Z" }, ] -[[package]] -name = "msgspec" -version = "0.21.1" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/e3/60/f79b9b013a16fa3a58350c9295ddc6789f2e335f36ea61ed10a21b215364/msgspec-0.21.1.tar.gz", hash = "sha256:2313508e394b0d208f8f56892ca9b2799e2561329de9763b19619595a6c0f72c", size = 319193, upload-time = "2026-04-12T21:44:50.394Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/96/38/d591d9f66d43d897ecbd249f2833665823d19c8b043f16619bc8343e23df/msgspec-0.21.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:72d9cd03241b8b2edb2e12dcc66c500fa480d8cbd71a8bac105809d468882064", size = 195172, upload-time = "2026-04-12T21:43:45.062Z" }, - { url = "https://files.pythonhosted.org/packages/69/1a/6899188b5982ec1324e0c629b7801eed2db987f6634fab58abd9fc82d317/msgspec-0.21.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:ed2ab278200e743a1d2610a4e0c8fc74f6cecb8548544cdec43f927bd9265238", size = 188316, upload-time = "2026-04-12T21:43:46.641Z" }, - { url = "https://files.pythonhosted.org/packages/9e/95/7e591b4fa11fdbbf9891164473c23420a8c781ef553295abe416bf335f42/msgspec-0.21.1-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:dd677e3001fdfed9186de72eab434da2976303cd5eb9550921d3d0c3e3e168ce", size = 216565, upload-time = "2026-04-12T21:43:48.081Z" }, - { url = "https://files.pythonhosted.org/packages/19/86/714feeaf3b84cf2027235681725593840153dedd2868578f9f2715e296bb/msgspec-0.21.1-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:f667b90b37fad734a91671abd68e0d7f4d066862771b87e91c53996dcb7a9027", size = 222689, upload-time = "2026-04-12T21:43:49.385Z" }, - { url = "https://files.pythonhosted.org/packages/7d/b9/4384243e814f2579e5205e17d170b9c1a30121afd1393298d904817a7fa7/msgspec-0.21.1-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:49880fd20fdbcfe1b793f07dd83f12572bab679c9800352c8b2240289aa46a06", size = 222343, upload-time = "2026-04-12T21:43:50.612Z" }, - { url = "https://files.pythonhosted.org/packages/04/01/4b227d9c4057346271043632bad41979cf8c3dca372e41bb1f7d546395b2/msgspec-0.21.1-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:ae0162e22849a5e91eaad907766525107523b0daea3df267a9fcb5ba4e0936ae", size = 225607, upload-time = "2026-04-12T21:43:52.129Z" }, - { url = "https://files.pythonhosted.org/packages/c1/ce/27021d1c3e5da837743092a7b7a5e8818397e1f4c05ee8b068bd7d1fd78a/msgspec-0.21.1-cp310-cp310-win_amd64.whl", hash = "sha256:f041a2279f31e3a53319005e4d60ba77c085cfcbe394cdc7ce803c2d01fe9449", size = 188392, upload-time = "2026-04-12T21:43:53.384Z" }, - { url = "https://files.pythonhosted.org/packages/80/2b/daf7a8d6d7cf00e0dcd0439178b284ade701234abdcadf3385601da04fbd/msgspec-0.21.1-cp310-cp310-win_arm64.whl", hash = "sha256:1bf17cbd7b28a5dffc7e764c654eed8ccde5e0f1de7970628608304640d4ce4e", size = 174191, upload-time = "2026-04-12T21:43:54.6Z" }, - { url = "https://files.pythonhosted.org/packages/ba/7f/bbc4e74cd33d316b75541149e4d35b163b63bce066530ae185a2ec3b5bfc/msgspec-0.21.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:b504b6e7f7a22a24b27232b73034421692147865162daaec9f3bf62439007c87", size = 193131, upload-time = "2026-04-12T21:43:56.094Z" }, - { url = "https://files.pythonhosted.org/packages/c1/60/504886af1aaf854112663b842d5eea9a15d9588f9bf7d0d2df736424b84d/msgspec-0.21.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:4692b7c1609155708c4418f88e92f63c13fdf08aa095c84bae82bad75b53389b", size = 186597, upload-time = "2026-04-12T21:43:57.242Z" }, - { url = "https://files.pythonhosted.org/packages/fa/54/d24ddeaa65b5278c9e67f48ce3c17a9831e8f3722f3c8322ee120aca22ef/msgspec-0.21.1-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:d3124010b3815451494c85ff345e693cb9fe5889cfcbbef39ed8622e0e72319c", size = 215158, upload-time = "2026-04-12T21:43:58.442Z" }, - { url = "https://files.pythonhosted.org/packages/9f/75/bb79c8b89a93ae23cd33c0d802373f16feaf9633f05d8af77091350dda0a/msgspec-0.21.1-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6badc03b9725352219cca017bfe71c61f2fbd0fb5982b410ac17c97c213deb30", size = 219856, upload-time = "2026-04-12T21:44:00.015Z" }, - { url = "https://files.pythonhosted.org/packages/b4/9c/c5ca26b46f0ebbd3a6683695ef89396712cb9e4199fd1f0bc1dd968216b1/msgspec-0.21.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:5d2d4116ebe3035a78d9ec76e99a9d64e5fa6d44fe61a9c5de7fd1acf54bcc69", size = 220314, upload-time = "2026-04-12T21:44:01.548Z" }, - { url = "https://files.pythonhosted.org/packages/c8/31/645a351c4285dce40ed6755c3dcc0aa648e26dacb20a98018fe2cce5e87b/msgspec-0.21.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:0d1009f6715f5bff3b54d4ff5c7428ad96197e0534e1645b8e9b955890c84664", size = 223215, upload-time = "2026-04-12T21:44:02.884Z" }, - { url = "https://files.pythonhosted.org/packages/09/af/8bf15736a6dd3cb4f90c5467f6dc39197d2daaf10754490cdc0aa17b7312/msgspec-0.21.1-cp311-cp311-win_amd64.whl", hash = "sha256:c6faffe5bb644ec884052679af4dfd776d4b5ca90e4a7ec7e7e319e4e6b93a6e", size = 188554, upload-time = "2026-04-12T21:44:04.151Z" }, - { url = "https://files.pythonhosted.org/packages/ef/29/cc7db3a165b62d16e64a83f82eccb79655055cb5bc1f60459a6f9d7c82f2/msgspec-0.21.1-cp311-cp311-win_arm64.whl", hash = "sha256:ee9e3f11fa94603f7d673bf795cfa31b549c4a2c723bc39b45beb1e7f5a3fb99", size = 174517, upload-time = "2026-04-12T21:44:05.66Z" }, - { url = "https://files.pythonhosted.org/packages/6e/cf/317224852c00248c620a9bcf4b26e2e4ab8afd752f18d2a6ef73ebd423b6/msgspec-0.21.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:d4248cf0b6129b7d230eacd493c17cc2d4f3989f3bb7f633a928a85b7dcfa251", size = 196188, upload-time = "2026-04-12T21:44:07.181Z" }, - { url = "https://files.pythonhosted.org/packages/6d/81/074612945c0666078f7366f40000013de9f6ba687491d450df699bceebc9/msgspec-0.21.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:5102c7e9b3acff82178449b85006d96310e690291bb1ea0142f1b24bcb8aabcb", size = 188473, upload-time = "2026-04-12T21:44:08.736Z" }, - { url = "https://files.pythonhosted.org/packages/8a/37/655101799590bcc5fddb2bd3fe0e6194e816c2d1da7c361725f5eb89a910/msgspec-0.21.1-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:846758412e9518252b2ac9bffd6f0e54d9ff614f5f9488df7749f81ff5c80920", size = 218871, upload-time = "2026-04-12T21:44:09.917Z" }, - { url = "https://files.pythonhosted.org/packages/b5/d1/d4cd9fe89c7d400d7a18f86ccc94daa3f0927f53558846fcb60791dce5d6/msgspec-0.21.1-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:21995e74b5c598c2e004110ad66ec7f1b8c20bf2bcf3b2de8fd9a3094422d3ff", size = 225025, upload-time = "2026-04-12T21:44:11.191Z" }, - { url = "https://files.pythonhosted.org/packages/24/bf/e20549e602b9edccadeeff98760345a416f9cce846a657e8b18e3396b212/msgspec-0.21.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:6129f0cca52992e898fd5344187f7c8127b63d810b2fd73e36fca73b4c6475ee", size = 222672, upload-time = "2026-04-12T21:44:12.481Z" }, - { url = "https://files.pythonhosted.org/packages/b4/68/04d7a8f0f786545cf9b8c280c57aa6befb5977af6e884b8b54191cbe44b3/msgspec-0.21.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:ef3ec2296248d1f8b9231acb051b6d471dfde8f21819e86c9adaaa9f42918521", size = 227303, upload-time = "2026-04-12T21:44:13.709Z" }, - { url = "https://files.pythonhosted.org/packages/cc/4d/619866af2840875be408047bf9e70ceafbae6ab50660de7134ed1b25eb86/msgspec-0.21.1-cp312-cp312-win_amd64.whl", hash = "sha256:d4ab834a054c6f0cbeef6df9e7e1b33d5f1bc7b86dea1d2fd7cad003873e783d", size = 190017, upload-time = "2026-04-12T21:44:14.977Z" }, - { url = "https://files.pythonhosted.org/packages/5e/2e/a8f9eca8fd00e097d7a9e99ba8a4685db994494448e3d4f0b7f6e9a3c0f7/msgspec-0.21.1-cp312-cp312-win_arm64.whl", hash = "sha256:628aaa35c74950a8c59da330d7e98917e1c7188f983745782027748ee4ca573e", size = 175345, upload-time = "2026-04-12T21:44:16.431Z" }, - { url = "https://files.pythonhosted.org/packages/7e/74/f11ede02839b19ff459f88e3145df5d711626ca84da4e23520cebf819367/msgspec-0.21.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:764173717a01743f007e9f74520ed281f24672c604514f7d76c1c3a10e8edb66", size = 196176, upload-time = "2026-04-12T21:44:17.613Z" }, - { url = "https://files.pythonhosted.org/packages/bb/40/4476c1bd341418a046c4955aff632ec769315d1e3cb94e6acf86d461f9ed/msgspec-0.21.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:344c7cd0eaed1fb81d7959f99100ef71ec9b536881a376f11b9a6c4803365697", size = 188524, upload-time = "2026-04-12T21:44:18.815Z" }, - { url = "https://files.pythonhosted.org/packages/ca/d9/9e9d7d7e5061b47540d03d640fab9b3965ba7ae49c1b2154861c8f007518/msgspec-0.21.1-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:48943e278b3854c2f89f955ddc6f9f430d3f0784b16e47d10604ee0463cd21f5", size = 218880, upload-time = "2026-04-12T21:44:20.028Z" }, - { url = "https://files.pythonhosted.org/packages/74/66/2bb344f34abb4b57e60c7c9c761994e0417b9718ec1460bf00c296f2a7ea/msgspec-0.21.1-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a9aa659ebb0101b1cbc31461212b87e341d961f0ab0772aaf068a99e001ec4aa", size = 225050, upload-time = "2026-04-12T21:44:21.577Z" }, - { url = "https://files.pythonhosted.org/packages/1a/84/7c1e412f76092277bf760cef12b7979d03314d259ab5b5cafde5d0c1722d/msgspec-0.21.1-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:f7b27d1a8ead2b6f5b0c4f2d07b8be1ccfcc041c8a0e704781edebe3ae13c484", size = 222713, upload-time = "2026-04-12T21:44:22.83Z" }, - { url = "https://files.pythonhosted.org/packages/4e/27/0bba04b2b4ef05f3d068429410bc71d2cea925f1596a8f41152cccd5edb8/msgspec-0.21.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:38fe93e86b61328fe544cb7fd871fad5a27c8734bfda90f65e5dbe288ae50f61", size = 227259, upload-time = "2026-04-12T21:44:24.11Z" }, - { url = "https://files.pythonhosted.org/packages/b0/2d/09574b0eea02fed2c2c1383dbaae2c7f79dc16dcd6487a886000afb5d7c4/msgspec-0.21.1-cp313-cp313-win_amd64.whl", hash = "sha256:8bc666331c35fcce05a7cd2d6221adbe0f6058f8e750711413d22793c080ac6a", size = 189857, upload-time = "2026-04-12T21:44:25.359Z" }, - { url = "https://files.pythonhosted.org/packages/46/34/105b1576ad182879914f0c821f17ee1d13abb165cb060448f96fe2aff078/msgspec-0.21.1-cp313-cp313-win_arm64.whl", hash = "sha256:42bb1241e0750c1a4346f2aa84db26c5ffd99a4eb3a954927d9f149ff2f42898", size = 175403, upload-time = "2026-04-12T21:44:26.608Z" }, - { url = "https://files.pythonhosted.org/packages/5a/ad/86954e987d1d6a5c579e2c2e7832b65e0fff194179fdac4f581536086024/msgspec-0.21.1-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:fab48eb45fdbfbdb2c0edfec00ffc53b6b6085beefc6b50b61e01659f9f8757f", size = 196261, upload-time = "2026-04-12T21:44:27.807Z" }, - { url = "https://files.pythonhosted.org/packages/d1/a1/c5e46c3e42b866199365e35d11dddfd1fbd8bba4fdb3c52f965b1607ce94/msgspec-0.21.1-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:3cb779ea0c35bc807ff941d415875c1f69ca0be91a2e907ab99a171811d86a9a", size = 188729, upload-time = "2026-04-12T21:44:28.99Z" }, - { url = "https://files.pythonhosted.org/packages/85/7d/1e29a319d678d6cb962ae5bdf32a6858ebdf38f73bc654c0e9c742a0c2c8/msgspec-0.21.1-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:68604db36b3b4dd9bf160e436e12798a4738848144cea1aca1cb984011eb160f", size = 219866, upload-time = "2026-04-12T21:44:31.104Z" }, - { url = "https://files.pythonhosted.org/packages/25/1f/cca084ca2572810fff12ea9dbdcbe39eac048f40daf4a9077b49fcbe8cee/msgspec-0.21.1-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:3d6b9dc50948eaf65df54d2fd0ff66e6d8c32f116037209ee861810eb9b676cb", size = 224993, upload-time = "2026-04-12T21:44:32.649Z" }, - { url = "https://files.pythonhosted.org/packages/71/94/d2120fc9d419a89a3a7c13e5b7078798c4b392a96a02a6e2b3ce43a8766c/msgspec-0.21.1-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:52c5e21930942302394429c5a582ce7e6b62c7f983b3760834c2ce107e0dd6df", size = 223535, upload-time = "2026-04-12T21:44:33.839Z" }, - { url = "https://files.pythonhosted.org/packages/75/17/42418b66a3ad972a89bab73dd78b79cc6282bb488a25e73c853cee7443b9/msgspec-0.21.1-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:abbb39d65681fa24ed394e01af3d59d869068324f900c61d06062b7fb9980f2f", size = 227222, upload-time = "2026-04-12T21:44:35.093Z" }, - { url = "https://files.pythonhosted.org/packages/c4/33/265c894268cca88ff67b144ca2b4c522fc8b9a6f1966a3640c70516e78e1/msgspec-0.21.1-cp314-cp314-win_amd64.whl", hash = "sha256:5666b1b560b97b6ec2eb3fca8a502298ebac56e13bbca1f88523538ce83d01ea", size = 193810, upload-time = "2026-04-12T21:44:36.612Z" }, - { url = "https://files.pythonhosted.org/packages/3b/8f/a6d35f25bf1fc63c492fdd88fdce01ba0875ead48c2b91f90f33653b4131/msgspec-0.21.1-cp314-cp314-win_arm64.whl", hash = "sha256:d8b8578e4c83b14ceea4cef0d0b747e31d9330fe4b03b2b2ad4063866a178f93", size = 179125, upload-time = "2026-04-12T21:44:38.198Z" }, - { url = "https://files.pythonhosted.org/packages/c6/39/74839641e64b99d87da55af0fc472854d42b46e2183b9e2a67fe1bb2a512/msgspec-0.21.1-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:15f523d51c00ebad412213bfe9f06f0a50ec2b93e0c19e824a2d267cabb48ea2", size = 200171, upload-time = "2026-04-12T21:44:39.414Z" }, - { url = "https://files.pythonhosted.org/packages/70/9b/ce0cca6d2d87fcd4b6ff97600790494e64f26a2c55d61507cd2755c16193/msgspec-0.21.1-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:4e47390360583ba3d5c6cb44cf0a9f61b0a06a899d3c2c00627cedebb2e2884b", size = 192879, upload-time = "2026-04-12T21:44:40.882Z" }, - { url = "https://files.pythonhosted.org/packages/a7/08/673a7bb05e5702dc787ddd3011195b509f9867927970da59052211929987/msgspec-0.21.1-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f60800e6299b798142dc40b0644da77ceac5ea0568be58228417eae14135c847", size = 226281, upload-time = "2026-04-12T21:44:42.181Z" }, - { url = "https://files.pythonhosted.org/packages/7d/45/86508cf57283e9070b3c447e3ab25b792a7a0855a3ea4e0c6d111ac34c97/msgspec-0.21.1-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:5f8e9dfcd98419cf7568808470c4317a3fb30bef0e3715b568730a2b272a20d7", size = 229863, upload-time = "2026-04-12T21:44:43.442Z" }, - { url = "https://files.pythonhosted.org/packages/2c/62/e7c9367cd08d590559faacd711edbae36840342843e669440363f33c7d36/msgspec-0.21.1-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:92d89dfad13bd1ea640dc3e37e724ed380da1030b272bdf5ecafb983c3ad7c75", size = 230445, upload-time = "2026-04-12T21:44:44.806Z" }, - { url = "https://files.pythonhosted.org/packages/42/b4/c0f54632103846b658a10930025f4de41c8724b5e4805a5f3b395586cb7e/msgspec-0.21.1-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:0d03867786e5d7ba25d666df4b11320c27170f4aeafcb8e3a8b0a50a4fb742ca", size = 231822, upload-time = "2026-04-12T21:44:46.343Z" }, - { url = "https://files.pythonhosted.org/packages/ea/1d/0d85cc79d0ccf5508e9c846cc66552a6a16bf92abd1dbd8362617f7b35cd/msgspec-0.21.1-cp314-cp314t-win_amd64.whl", hash = "sha256:740fbf1c9d59992ca3537d6fbe9ebbf9eaf726a65fbf31448e0ecbc710697a63", size = 206650, upload-time = "2026-04-12T21:44:47.601Z" }, - { url = "https://files.pythonhosted.org/packages/90/91/56c5d560f20e6c20e9e4f55bd0e458f7f162aa689ee350346c04c48eac0b/msgspec-0.21.1-cp314-cp314t-win_arm64.whl", hash = "sha256:0d2cc73df6058d811a126ac3a8ad63a4dfa210c82f9cf5a004802eaf4712de90", size = 183149, upload-time = "2026-04-12T21:44:48.833Z" }, -] - [[package]] name = "mujoco" version = "3.5.0" @@ -7651,19 +7428,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/79/ad/45312df6b63ba64ea35b8d8f5f0c577aac16e6b416eafe8e1cb34e03f9a7/plumbum-1.10.0-py3-none-any.whl", hash = "sha256:9583d737ac901c474d99d030e4d5eec4c4e6d2d7417b1cf49728cf3be34f6dc8", size = 127383, upload-time = "2025-10-31T05:02:47.002Z" }, ] -[[package]] -name = "plyfile" -version = "1.1.3" -source = { registry = "https://pypi.org/simple" } -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'" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/78/d8/f68ec9a54568236ba4c00fc0b002f74d2a559841c1fce86ab356599da032/plyfile-1.1.3.tar.gz", hash = "sha256:1c37720cb0470b762cec2dfef573ee7996a616c359c0ec34fdd766ace3ea0634", size = 36163, upload-time = "2025-10-22T01:58:40.06Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/22/22/1755bb4c7db15bb1ed63b4eb7a7fc133bf42a3f9cc806c0d5941e107ba90/plyfile-1.1.3-py3-none-any.whl", hash = "sha256:581302f07b1c298431dcaa9038bba2ae80f3f7868b29ccb826a07bc4488ff38a", size = 36455, upload-time = "2025-10-22T01:58:38.614Z" }, -] - [[package]] name = "polars" version = "1.38.1" @@ -9571,22 +9335,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/3f/99/2e119d541d596daea39643eb9312b47c7847383951300f889166938035b1/rpyc-6.0.2-py3-none-any.whl", hash = "sha256:8072308ad30725bc281c42c011fc8c922be15f3eeda6eafb2917cafe1b6f00ec", size = 74768, upload-time = "2025-04-18T16:33:20.147Z" }, ] -[[package]] -name = "rtree" -version = "1.4.1" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/95/09/7302695875a019514de9a5dd17b8320e7a19d6e7bc8f85dcfb79a4ce2da3/rtree-1.4.1.tar.gz", hash = "sha256:c6b1b3550881e57ebe530cc6cffefc87cd9bf49c30b37b894065a9f810875e46", size = 52425, upload-time = "2025-08-13T19:32:01.413Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/04/d9/108cd989a4c0954e60b3cdc86fd2826407702b5375f6dfdab2802e5fed98/rtree-1.4.1-py3-none-macosx_10_9_x86_64.whl", hash = "sha256:d672184298527522d4914d8ae53bf76982b86ca420b0acde9298a7a87d81d4a4", size = 468484, upload-time = "2025-08-13T19:31:50.593Z" }, - { url = "https://files.pythonhosted.org/packages/f3/cf/2710b6fd6b07ea0aef317b29f335790ba6adf06a28ac236078ed9bd8a91d/rtree-1.4.1-py3-none-macosx_11_0_arm64.whl", hash = "sha256:a7e48d805e12011c2cf739a29d6a60ae852fb1de9fc84220bbcef67e6e595d7d", size = 436325, upload-time = "2025-08-13T19:31:52.367Z" }, - { url = "https://files.pythonhosted.org/packages/55/e1/4d075268a46e68db3cac51846eb6a3ab96ed481c585c5a1ad411b3c23aad/rtree-1.4.1-py3-none-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:efa8c4496e31e9ad58ff6c7df89abceac7022d906cb64a3e18e4fceae6b77f65", size = 459789, upload-time = "2025-08-13T19:31:53.926Z" }, - { url = "https://files.pythonhosted.org/packages/d1/75/e5d44be90525cd28503e7f836d077ae6663ec0687a13ba7810b4114b3668/rtree-1.4.1-py3-none-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:12de4578f1b3381a93a655846900be4e3d5f4cd5e306b8b00aa77c1121dc7e8c", size = 507644, upload-time = "2025-08-13T19:31:55.164Z" }, - { url = "https://files.pythonhosted.org/packages/fd/85/b8684f769a142163b52859a38a486493b05bafb4f2fb71d4f945de28ebf9/rtree-1.4.1-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:b558edda52eca3e6d1ee629042192c65e6b7f2c150d6d6cd207ce82f85be3967", size = 1454478, upload-time = "2025-08-13T19:31:56.808Z" }, - { url = "https://files.pythonhosted.org/packages/e9/a4/c2292b95246b9165cc43a0c3757e80995d58bc9b43da5cb47ad6e3535213/rtree-1.4.1-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:f155bc8d6bac9dcd383481dee8c130947a4866db1d16cb6dff442329a038a0dc", size = 1555140, upload-time = "2025-08-13T19:31:58.031Z" }, - { url = "https://files.pythonhosted.org/packages/74/25/5282c8270bfcd620d3e73beb35b40ac4ab00f0a898d98ebeb41ef0989ec8/rtree-1.4.1-py3-none-win_amd64.whl", hash = "sha256:efe125f416fd27150197ab8521158662943a40f87acab8028a1aac4ad667a489", size = 389358, upload-time = "2025-08-13T19:31:59.247Z" }, - { url = "https://files.pythonhosted.org/packages/3f/50/0a9e7e7afe7339bd5e36911f0ceb15fed51945836ed803ae5afd661057fd/rtree-1.4.1-py3-none-win_arm64.whl", hash = "sha256:3d46f55729b28138e897ffef32f7ce93ac335cb67f9120125ad3742a220800f0", size = 355253, upload-time = "2025-08-13T19:32:00.296Z" }, -] - [[package]] name = "ruff" version = "0.14.3" @@ -10032,74 +9780,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e1/e3/c164c88b2e5ce7b24d667b9bd83589cf4f3520d97cad01534cd3c4f55fdb/setuptools-81.0.0-py3-none-any.whl", hash = "sha256:fdd925d5c5d9f62e4b74b30d6dd7828ce236fd6ed998a08d81de62ce5a6310d6", size = 1062021, upload-time = "2026-02-06T21:10:37.175Z" }, ] -[[package]] -name = "shapely" -version = "2.1.2" -source = { registry = "https://pypi.org/simple" } -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'" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/4d/bc/0989043118a27cccb4e906a46b7565ce36ca7b57f5a18b78f4f1b0f72d9d/shapely-2.1.2.tar.gz", hash = "sha256:2ed4ecb28320a433db18a5bf029986aa8afcfd740745e78847e330d5d94922a9", size = 315489, upload-time = "2025-09-24T13:51:41.432Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/05/89/c3548aa9b9812a5d143986764dededfa48d817714e947398bdda87c77a72/shapely-2.1.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:7ae48c236c0324b4e139bea88a306a04ca630f49be66741b340729d380d8f52f", size = 1825959, upload-time = "2025-09-24T13:50:00.682Z" }, - { url = "https://files.pythonhosted.org/packages/ce/8a/7ebc947080442edd614ceebe0ce2cdbd00c25e832c240e1d1de61d0e6b38/shapely-2.1.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:eba6710407f1daa8e7602c347dfc94adc02205ec27ed956346190d66579eb9ea", size = 1629196, upload-time = "2025-09-24T13:50:03.447Z" }, - { url = "https://files.pythonhosted.org/packages/c8/86/c9c27881c20d00fc409e7e059de569d5ed0abfcec9c49548b124ebddea51/shapely-2.1.2-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:ef4a456cc8b7b3d50ccec29642aa4aeda959e9da2fe9540a92754770d5f0cf1f", size = 2951065, upload-time = "2025-09-24T13:50:05.266Z" }, - { url = "https://files.pythonhosted.org/packages/50/8a/0ab1f7433a2a85d9e9aea5b1fbb333f3b09b309e7817309250b4b7b2cc7a/shapely-2.1.2-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:e38a190442aacc67ff9f75ce60aec04893041f16f97d242209106d502486a142", size = 3058666, upload-time = "2025-09-24T13:50:06.872Z" }, - { url = "https://files.pythonhosted.org/packages/bb/c6/5a30ffac9c4f3ffd5b7113a7f5299ccec4713acd5ee44039778a7698224e/shapely-2.1.2-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:40d784101f5d06a1fd30b55fc11ea58a61be23f930d934d86f19a180909908a4", size = 3966905, upload-time = "2025-09-24T13:50:09.417Z" }, - { url = "https://files.pythonhosted.org/packages/9c/72/e92f3035ba43e53959007f928315a68fbcf2eeb4e5ededb6f0dc7ff1ecc3/shapely-2.1.2-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:f6f6cd5819c50d9bcf921882784586aab34a4bd53e7553e175dece6db513a6f0", size = 4129260, upload-time = "2025-09-24T13:50:11.183Z" }, - { url = "https://files.pythonhosted.org/packages/42/24/605901b73a3d9f65fa958e63c9211f4be23d584da8a1a7487382fac7fdc5/shapely-2.1.2-cp310-cp310-win32.whl", hash = "sha256:fe9627c39c59e553c90f5bc3128252cb85dc3b3be8189710666d2f8bc3a5503e", size = 1544301, upload-time = "2025-09-24T13:50:12.521Z" }, - { url = "https://files.pythonhosted.org/packages/e1/89/6db795b8dd3919851856bd2ddd13ce434a748072f6fdee42ff30cbd3afa3/shapely-2.1.2-cp310-cp310-win_amd64.whl", hash = "sha256:1d0bfb4b8f661b3b4ec3565fa36c340bfb1cda82087199711f86a88647d26b2f", size = 1722074, upload-time = "2025-09-24T13:50:13.909Z" }, - { url = "https://files.pythonhosted.org/packages/8f/8d/1ff672dea9ec6a7b5d422eb6d095ed886e2e523733329f75fdcb14ee1149/shapely-2.1.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:91121757b0a36c9aac3427a651a7e6567110a4a67c97edf04f8d55d4765f6618", size = 1820038, upload-time = "2025-09-24T13:50:15.628Z" }, - { url = "https://files.pythonhosted.org/packages/4f/ce/28fab8c772ce5db23a0d86bf0adaee0c4c79d5ad1db766055fa3dab442e2/shapely-2.1.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:16a9c722ba774cf50b5d4541242b4cce05aafd44a015290c82ba8a16931ff63d", size = 1626039, upload-time = "2025-09-24T13:50:16.881Z" }, - { url = "https://files.pythonhosted.org/packages/70/8b/868b7e3f4982f5006e9395c1e12343c66a8155c0374fdc07c0e6a1ab547d/shapely-2.1.2-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:cc4f7397459b12c0b196c9efe1f9d7e92463cbba142632b4cc6d8bbbbd3e2b09", size = 3001519, upload-time = "2025-09-24T13:50:18.606Z" }, - { url = "https://files.pythonhosted.org/packages/13/02/58b0b8d9c17c93ab6340edd8b7308c0c5a5b81f94ce65705819b7416dba5/shapely-2.1.2-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:136ab87b17e733e22f0961504d05e77e7be8c9b5a8184f685b4a91a84efe3c26", size = 3110842, upload-time = "2025-09-24T13:50:21.77Z" }, - { url = "https://files.pythonhosted.org/packages/af/61/8e389c97994d5f331dcffb25e2fa761aeedfb52b3ad9bcdd7b8671f4810a/shapely-2.1.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:16c5d0fc45d3aa0a69074979f4f1928ca2734fb2e0dde8af9611e134e46774e7", size = 4021316, upload-time = "2025-09-24T13:50:23.626Z" }, - { url = "https://files.pythonhosted.org/packages/d3/d4/9b2a9fe6039f9e42ccf2cb3e84f219fd8364b0c3b8e7bbc857b5fbe9c14c/shapely-2.1.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:6ddc759f72b5b2b0f54a7e7cde44acef680a55019eb52ac63a7af2cf17cb9cd2", size = 4178586, upload-time = "2025-09-24T13:50:25.443Z" }, - { url = "https://files.pythonhosted.org/packages/16/f6/9840f6963ed4decf76b08fd6d7fed14f8779fb7a62cb45c5617fa8ac6eab/shapely-2.1.2-cp311-cp311-win32.whl", hash = "sha256:2fa78b49485391224755a856ed3b3bd91c8455f6121fee0db0e71cefb07d0ef6", size = 1543961, upload-time = "2025-09-24T13:50:26.968Z" }, - { url = "https://files.pythonhosted.org/packages/38/1e/3f8ea46353c2a33c1669eb7327f9665103aa3a8dfe7f2e4ef714c210b2c2/shapely-2.1.2-cp311-cp311-win_amd64.whl", hash = "sha256:c64d5c97b2f47e3cd9b712eaced3b061f2b71234b3fc263e0fcf7d889c6559dc", size = 1722856, upload-time = "2025-09-24T13:50:28.497Z" }, - { url = "https://files.pythonhosted.org/packages/24/c0/f3b6453cf2dfa99adc0ba6675f9aaff9e526d2224cbd7ff9c1a879238693/shapely-2.1.2-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:fe2533caae6a91a543dec62e8360fe86ffcdc42a7c55f9dfd0128a977a896b94", size = 1833550, upload-time = "2025-09-24T13:50:30.019Z" }, - { url = "https://files.pythonhosted.org/packages/86/07/59dee0bc4b913b7ab59ab1086225baca5b8f19865e6101db9ebb7243e132/shapely-2.1.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:ba4d1333cc0bc94381d6d4308d2e4e008e0bd128bdcff5573199742ee3634359", size = 1643556, upload-time = "2025-09-24T13:50:32.291Z" }, - { url = "https://files.pythonhosted.org/packages/26/29/a5397e75b435b9895cd53e165083faed5d12fd9626eadec15a83a2411f0f/shapely-2.1.2-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:0bd308103340030feef6c111d3eb98d50dc13feea33affc8a6f9fa549e9458a3", size = 2988308, upload-time = "2025-09-24T13:50:33.862Z" }, - { url = "https://files.pythonhosted.org/packages/b9/37/e781683abac55dde9771e086b790e554811a71ed0b2b8a1e789b7430dd44/shapely-2.1.2-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:1e7d4d7ad262a48bb44277ca12c7c78cb1b0f56b32c10734ec9a1d30c0b0c54b", size = 3099844, upload-time = "2025-09-24T13:50:35.459Z" }, - { url = "https://files.pythonhosted.org/packages/d8/f3/9876b64d4a5a321b9dc482c92bb6f061f2fa42131cba643c699f39317cb9/shapely-2.1.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:e9eddfe513096a71896441a7c37db72da0687b34752c4e193577a145c71736fc", size = 3988842, upload-time = "2025-09-24T13:50:37.478Z" }, - { url = "https://files.pythonhosted.org/packages/d1/a0/704c7292f7014c7e74ec84eddb7b109e1fbae74a16deae9c1504b1d15565/shapely-2.1.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:980c777c612514c0cf99bc8a9de6d286f5e186dcaf9091252fcd444e5638193d", size = 4152714, upload-time = "2025-09-24T13:50:39.9Z" }, - { url = "https://files.pythonhosted.org/packages/53/46/319c9dc788884ad0785242543cdffac0e6530e4d0deb6c4862bc4143dcf3/shapely-2.1.2-cp312-cp312-win32.whl", hash = "sha256:9111274b88e4d7b54a95218e243282709b330ef52b7b86bc6aaf4f805306f454", size = 1542745, upload-time = "2025-09-24T13:50:41.414Z" }, - { url = "https://files.pythonhosted.org/packages/ec/bf/cb6c1c505cb31e818e900b9312d514f381fbfa5c4363edfce0fcc4f8c1a4/shapely-2.1.2-cp312-cp312-win_amd64.whl", hash = "sha256:743044b4cfb34f9a67205cee9279feaf60ba7d02e69febc2afc609047cb49179", size = 1722861, upload-time = "2025-09-24T13:50:43.35Z" }, - { url = "https://files.pythonhosted.org/packages/c3/90/98ef257c23c46425dc4d1d31005ad7c8d649fe423a38b917db02c30f1f5a/shapely-2.1.2-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:b510dda1a3672d6879beb319bc7c5fd302c6c354584690973c838f46ec3e0fa8", size = 1832644, upload-time = "2025-09-24T13:50:44.886Z" }, - { url = "https://files.pythonhosted.org/packages/6d/ab/0bee5a830d209adcd3a01f2d4b70e587cdd9fd7380d5198c064091005af8/shapely-2.1.2-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:8cff473e81017594d20ec55d86b54bc635544897e13a7cfc12e36909c5309a2a", size = 1642887, upload-time = "2025-09-24T13:50:46.735Z" }, - { url = "https://files.pythonhosted.org/packages/2d/5e/7d7f54ba960c13302584c73704d8c4d15404a51024631adb60b126a4ae88/shapely-2.1.2-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:fe7b77dc63d707c09726b7908f575fc04ff1d1ad0f3fb92aec212396bc6cfe5e", size = 2970931, upload-time = "2025-09-24T13:50:48.374Z" }, - { url = "https://files.pythonhosted.org/packages/f2/a2/83fc37e2a58090e3d2ff79175a95493c664bcd0b653dd75cb9134645a4e5/shapely-2.1.2-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:7ed1a5bbfb386ee8332713bf7508bc24e32d24b74fc9a7b9f8529a55db9f4ee6", size = 3082855, upload-time = "2025-09-24T13:50:50.037Z" }, - { url = "https://files.pythonhosted.org/packages/44/2b/578faf235a5b09f16b5f02833c53822294d7f21b242f8e2d0cf03fb64321/shapely-2.1.2-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:a84e0582858d841d54355246ddfcbd1fce3179f185da7470f41ce39d001ee1af", size = 3979960, upload-time = "2025-09-24T13:50:51.74Z" }, - { url = "https://files.pythonhosted.org/packages/4d/04/167f096386120f692cc4ca02f75a17b961858997a95e67a3cb6a7bbd6b53/shapely-2.1.2-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:dc3487447a43d42adcdf52d7ac73804f2312cbfa5d433a7d2c506dcab0033dfd", size = 4142851, upload-time = "2025-09-24T13:50:53.49Z" }, - { url = "https://files.pythonhosted.org/packages/48/74/fb402c5a6235d1c65a97348b48cdedb75fb19eca2b1d66d04969fc1c6091/shapely-2.1.2-cp313-cp313-win32.whl", hash = "sha256:9c3a3c648aedc9f99c09263b39f2d8252f199cb3ac154fadc173283d7d111350", size = 1541890, upload-time = "2025-09-24T13:50:55.337Z" }, - { url = "https://files.pythonhosted.org/packages/41/47/3647fe7ad990af60ad98b889657a976042c9988c2807cf322a9d6685f462/shapely-2.1.2-cp313-cp313-win_amd64.whl", hash = "sha256:ca2591bff6645c216695bdf1614fca9c82ea1144d4a7591a466fef64f28f0715", size = 1722151, upload-time = "2025-09-24T13:50:57.153Z" }, - { url = "https://files.pythonhosted.org/packages/3c/49/63953754faa51ffe7d8189bfbe9ca34def29f8c0e34c67cbe2a2795f269d/shapely-2.1.2-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:2d93d23bdd2ed9dc157b46bc2f19b7da143ca8714464249bef6771c679d5ff40", size = 1834130, upload-time = "2025-09-24T13:50:58.49Z" }, - { url = "https://files.pythonhosted.org/packages/7f/ee/dce001c1984052970ff60eb4727164892fb2d08052c575042a47f5a9e88f/shapely-2.1.2-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:01d0d304b25634d60bd7cf291828119ab55a3bab87dc4af1e44b07fb225f188b", size = 1642802, upload-time = "2025-09-24T13:50:59.871Z" }, - { url = "https://files.pythonhosted.org/packages/da/e7/fc4e9a19929522877fa602f705706b96e78376afb7fad09cad5b9af1553c/shapely-2.1.2-cp313-cp313t-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:8d8382dd120d64b03698b7298b89611a6ea6f55ada9d39942838b79c9bc89801", size = 3018460, upload-time = "2025-09-24T13:51:02.08Z" }, - { url = "https://files.pythonhosted.org/packages/a1/18/7519a25db21847b525696883ddc8e6a0ecaa36159ea88e0fef11466384d0/shapely-2.1.2-cp313-cp313t-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:19efa3611eef966e776183e338b2d7ea43569ae99ab34f8d17c2c054d3205cc0", size = 3095223, upload-time = "2025-09-24T13:51:04.472Z" }, - { url = "https://files.pythonhosted.org/packages/48/de/b59a620b1f3a129c3fecc2737104a0a7e04e79335bd3b0a1f1609744cf17/shapely-2.1.2-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:346ec0c1a0fcd32f57f00e4134d1200e14bf3f5ae12af87ba83ca275c502498c", size = 4030760, upload-time = "2025-09-24T13:51:06.455Z" }, - { url = "https://files.pythonhosted.org/packages/96/b3/c6655ee7232b417562bae192ae0d3ceaadb1cc0ffc2088a2ddf415456cc2/shapely-2.1.2-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:6305993a35989391bd3476ee538a5c9a845861462327efe00dd11a5c8c709a99", size = 4170078, upload-time = "2025-09-24T13:51:08.584Z" }, - { url = "https://files.pythonhosted.org/packages/a0/8e/605c76808d73503c9333af8f6cbe7e1354d2d238bda5f88eea36bfe0f42a/shapely-2.1.2-cp313-cp313t-win32.whl", hash = "sha256:c8876673449f3401f278c86eb33224c5764582f72b653a415d0e6672fde887bf", size = 1559178, upload-time = "2025-09-24T13:51:10.73Z" }, - { url = "https://files.pythonhosted.org/packages/36/f7/d317eb232352a1f1444d11002d477e54514a4a6045536d49d0c59783c0da/shapely-2.1.2-cp313-cp313t-win_amd64.whl", hash = "sha256:4a44bc62a10d84c11a7a3d7c1c4fe857f7477c3506e24c9062da0db0ae0c449c", size = 1739756, upload-time = "2025-09-24T13:51:12.105Z" }, - { url = "https://files.pythonhosted.org/packages/fc/c4/3ce4c2d9b6aabd27d26ec988f08cb877ba9e6e96086eff81bfea93e688c7/shapely-2.1.2-cp314-cp314-macosx_10_13_x86_64.whl", hash = "sha256:9a522f460d28e2bf4e12396240a5fc1518788b2fcd73535166d748399ef0c223", size = 1831290, upload-time = "2025-09-24T13:51:13.56Z" }, - { url = "https://files.pythonhosted.org/packages/17/b9/f6ab8918fc15429f79cb04afa9f9913546212d7fb5e5196132a2af46676b/shapely-2.1.2-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:1ff629e00818033b8d71139565527ced7d776c269a49bd78c9df84e8f852190c", size = 1641463, upload-time = "2025-09-24T13:51:14.972Z" }, - { url = "https://files.pythonhosted.org/packages/a5/57/91d59ae525ca641e7ac5551c04c9503aee6f29b92b392f31790fcb1a4358/shapely-2.1.2-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:f67b34271dedc3c653eba4e3d7111aa421d5be9b4c4c7d38d30907f796cb30df", size = 2970145, upload-time = "2025-09-24T13:51:16.961Z" }, - { url = "https://files.pythonhosted.org/packages/8a/cb/4948be52ee1da6927831ab59e10d4c29baa2a714f599f1f0d1bc747f5777/shapely-2.1.2-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:21952dc00df38a2c28375659b07a3979d22641aeb104751e769c3ee825aadecf", size = 3073806, upload-time = "2025-09-24T13:51:18.712Z" }, - { url = "https://files.pythonhosted.org/packages/03/83/f768a54af775eb41ef2e7bec8a0a0dbe7d2431c3e78c0a8bdba7ab17e446/shapely-2.1.2-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:1f2f33f486777456586948e333a56ae21f35ae273be99255a191f5c1fa302eb4", size = 3980803, upload-time = "2025-09-24T13:51:20.37Z" }, - { url = "https://files.pythonhosted.org/packages/9f/cb/559c7c195807c91c79d38a1f6901384a2878a76fbdf3f1048893a9b7534d/shapely-2.1.2-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:cf831a13e0d5a7eb519e96f58ec26e049b1fad411fc6fc23b162a7ce04d9cffc", size = 4133301, upload-time = "2025-09-24T13:51:21.887Z" }, - { url = "https://files.pythonhosted.org/packages/80/cd/60d5ae203241c53ef3abd2ef27c6800e21afd6c94e39db5315ea0cbafb4a/shapely-2.1.2-cp314-cp314-win32.whl", hash = "sha256:61edcd8d0d17dd99075d320a1dd39c0cb9616f7572f10ef91b4b5b00c4aeb566", size = 1583247, upload-time = "2025-09-24T13:51:23.401Z" }, - { url = "https://files.pythonhosted.org/packages/74/d4/135684f342e909330e50d31d441ace06bf83c7dc0777e11043f99167b123/shapely-2.1.2-cp314-cp314-win_amd64.whl", hash = "sha256:a444e7afccdb0999e203b976adb37ea633725333e5b119ad40b1ca291ecf311c", size = 1773019, upload-time = "2025-09-24T13:51:24.873Z" }, - { url = "https://files.pythonhosted.org/packages/a3/05/a44f3f9f695fa3ada22786dc9da33c933da1cbc4bfe876fe3a100bafe263/shapely-2.1.2-cp314-cp314t-macosx_10_13_x86_64.whl", hash = "sha256:5ebe3f84c6112ad3d4632b1fd2290665aa75d4cef5f6c5d77c4c95b324527c6a", size = 1834137, upload-time = "2025-09-24T13:51:26.665Z" }, - { url = "https://files.pythonhosted.org/packages/52/7e/4d57db45bf314573427b0a70dfca15d912d108e6023f623947fa69f39b72/shapely-2.1.2-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:5860eb9f00a1d49ebb14e881f5caf6c2cf472c7fd38bd7f253bbd34f934eb076", size = 1642884, upload-time = "2025-09-24T13:51:28.029Z" }, - { url = "https://files.pythonhosted.org/packages/5a/27/4e29c0a55d6d14ad7422bf86995d7ff3f54af0eba59617eb95caf84b9680/shapely-2.1.2-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:b705c99c76695702656327b819c9660768ec33f5ce01fa32b2af62b56ba400a1", size = 3018320, upload-time = "2025-09-24T13:51:29.903Z" }, - { url = "https://files.pythonhosted.org/packages/9f/bb/992e6a3c463f4d29d4cd6ab8963b75b1b1040199edbd72beada4af46bde5/shapely-2.1.2-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:a1fd0ea855b2cf7c9cddaf25543e914dd75af9de08785f20ca3085f2c9ca60b0", size = 3094931, upload-time = "2025-09-24T13:51:32.699Z" }, - { url = "https://files.pythonhosted.org/packages/9c/16/82e65e21070e473f0ed6451224ed9fa0be85033d17e0c6e7213a12f59d12/shapely-2.1.2-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:df90e2db118c3671a0754f38e36802db75fe0920d211a27481daf50a711fdf26", size = 4030406, upload-time = "2025-09-24T13:51:34.189Z" }, - { url = "https://files.pythonhosted.org/packages/7c/75/c24ed871c576d7e2b64b04b1fe3d075157f6eb54e59670d3f5ffb36e25c7/shapely-2.1.2-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:361b6d45030b4ac64ddd0a26046906c8202eb60d0f9f53085f5179f1d23021a0", size = 4169511, upload-time = "2025-09-24T13:51:36.297Z" }, - { url = "https://files.pythonhosted.org/packages/b1/f7/b3d1d6d18ebf55236eec1c681ce5e665742aab3c0b7b232720a7d43df7b6/shapely-2.1.2-cp314-cp314t-win32.whl", hash = "sha256:b54df60f1fbdecc8ebc2c5b11870461a6417b3d617f555e5033f1505d36e5735", size = 1602607, upload-time = "2025-09-24T13:51:37.757Z" }, - { url = "https://files.pythonhosted.org/packages/9a/f6/f09272a71976dfc138129b8faf435d064a811ae2f708cb147dccdf7aacdb/shapely-2.1.2-cp314-cp314t-win_amd64.whl", hash = "sha256:0036ac886e0923417932c2e6369b6c52e38e0ff5d9120b90eef5cd9a5fc5cae9", size = 1796682, upload-time = "2025-09-24T13:51:39.233Z" }, -] - [[package]] name = "shellingham" version = "1.5.4" @@ -10327,15 +10007,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/a8/45/a132b9074aa18e799b891b91ad72133c98d8042c70f6240e4c5f9dabee2f/structlog-25.5.0-py3-none-any.whl", hash = "sha256:a8453e9b9e636ec59bd9e79bbd4a72f025981b3ba0f5837aebf48f02f37a7f9f", size = 72510, upload-time = "2025-10-27T08:28:21.535Z" }, ] -[[package]] -name = "svg-path" -version = "7.0" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/66/b9/649abbe870842c185b12920e937e9b95d4c2b18de50af98d2c140df3e179/svg_path-7.0.tar.gz", hash = "sha256:9037486957cb1dcf4375ef42206499a47c111b8ffcbac6e3e55f9d079d875bb0", size = 23552, upload-time = "2025-07-06T15:20:40.823Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/3a/83/4f5b250220e1a5acd31345a5ec1c95a7769725d0d8135276f399f44062f8/svg_path-7.0-py2.py3-none-any.whl", hash = "sha256:447cb1e16a95acea2dd867fe737fa99cb75d587b4fc64dbee709a8dd6891ad9c", size = 18208, upload-time = "2025-07-06T15:20:39.59Z" }, -] - [[package]] name = "sympy" version = "1.14.0" @@ -10949,29 +10620,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/3c/b9/da09903ea53b677a58ba770112de6fe8b2acb8b4cd9bffae4ff6cfe7c072/trimesh-4.11.2-py3-none-any.whl", hash = "sha256:25e3ab2620f9eca5c9376168c67aabdd32205dad1c4eea09cd45cd4a3edf775a", size = 740328, upload-time = "2026-02-10T16:00:25.246Z" }, ] -[package.optional-dependencies] -easy = [ - { name = "charset-normalizer" }, - { name = "colorlog" }, - { name = "embreex", marker = "platform_machine == 'x86_64'" }, - { name = "httpx" }, - { name = "jsonschema" }, - { name = "lxml" }, - { name = "manifold3d", marker = "python_full_version < '3.14'" }, - { name = "mapbox-earcut" }, - { name = "networkx", version = "3.4.2", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, - { name = "networkx", version = "3.6.1", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, - { name = "pillow" }, - { name = "pycollada" }, - { name = "rtree" }, - { 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 = "shapely" }, - { name = "svg-path" }, - { name = "vhacdx" }, - { name = "xxhash" }, -] - [[package]] name = "triton" version = "3.6.0" @@ -11537,60 +11185,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e4/16/c1fd27e9549f3c4baf1dc9c20c456cd2f822dbf8de9f463824b0c0357e06/uvloop-0.22.1-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:6cde23eeda1a25c75b2e07d39970f3374105d5eafbaab2a4482be82f272d5a5e", size = 4296730, upload-time = "2025-10-16T22:17:00.744Z" }, ] -[[package]] -name = "vhacdx" -version = "0.0.10" -source = { registry = "https://pypi.org/simple" } -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'" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/15/e3/d2abc3dc4c1cb216c2efdc70b36f80efeb1bdbd7d420a676ddc9d9d980e1/vhacdx-0.0.10.tar.gz", hash = "sha256:fcc23201e319d79fe25e064847efc254bd39ac30af28cc761409e1f9142dd033", size = 58125, upload-time = "2025-12-02T20:58:45.358Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/c4/f4/da308d86daaa9c636851357cbd928715d47963beecd525b3749d2d5c9537/vhacdx-0.0.10-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:4bc7be82fab608cb7231e95a0a10700be1e9422a36b21e7d49c782a598c8d37c", size = 222760, upload-time = "2025-12-02T20:57:30.778Z" }, - { url = "https://files.pythonhosted.org/packages/e0/8a/e3462a43ec6712b74d921e4af9d5a2998752378c5554bde9a594dbb0cf0c/vhacdx-0.0.10-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:4b63d1c5ad0e64c300a3a9d9404f4778df367b8c545639dfb932db4b76704ff3", size = 208812, upload-time = "2025-12-02T20:57:33.486Z" }, - { url = "https://files.pythonhosted.org/packages/fb/d1/b717275adb108431f1404193542fab7ecf4c5bae221f1552bbd570fe0e5d/vhacdx-0.0.10-cp310-cp310-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f9bcf3fe1c555598e41348108b55a0fc67534e7fef2367452c301014518c1476", size = 236999, upload-time = "2025-12-02T20:57:34.971Z" }, - { url = "https://files.pythonhosted.org/packages/bf/84/97e2305f6bd4a4de3d40bb234c38282cbcf2fa30653ff5ae4f7df9d8f3ec/vhacdx-0.0.10-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9506ca89289da63e5a3d1ac97aa7413aece47d65cbaa4b0c409469555add0e06", size = 250035, upload-time = "2025-12-02T20:57:36.037Z" }, - { url = "https://files.pythonhosted.org/packages/9d/66/eb1d8d64742b9e73557e075cea6ee7e4976dd89b84c7d3197ca3621d5a85/vhacdx-0.0.10-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:06faf9caa0abceddd5fa505e4299e2ebf14bc26c58a1e521013717cbf37bea61", size = 1224134, upload-time = "2025-12-02T20:57:37.217Z" }, - { url = "https://files.pythonhosted.org/packages/47/db/e829b21b071db94f45079c4ace2f967c684f08b10ea285919a95e9d5fe21/vhacdx-0.0.10-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:3a6b43b42290697e2bd04087977d1e3841d287c528e414c765581ecec62e66f6", size = 1284300, upload-time = "2025-12-02T20:57:38.78Z" }, - { url = "https://files.pythonhosted.org/packages/ff/aa/b401565542b927ce3e0a6d5e72acef79343a449ee1a7ad94a5c7266bab26/vhacdx-0.0.10-cp310-cp310-win_amd64.whl", hash = "sha256:27eb3b293ccef1332d477346d564bb4c474bb451e9b753e3ce9cac01cbb90a0c", size = 193069, upload-time = "2025-12-02T20:57:40.318Z" }, - { url = "https://files.pythonhosted.org/packages/b7/2c/d49df6fec3294cef3c8c88c54784162bd8350c427fecd9b16335772b760f/vhacdx-0.0.10-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:8584f33ed020b6cce678b8febcf84af22bced617ef31c85bf31fd7e2b4bba9fe", size = 224113, upload-time = "2025-12-02T20:57:41.59Z" }, - { url = "https://files.pythonhosted.org/packages/68/1d/bd2456baa6b16977c106adc2386b6e7a34c3e57ade6aeeab68bb61ceb16f/vhacdx-0.0.10-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:a9b63cdb5f34dfee386b64a01f7e1571ef0c2555244ea3d83a09d78273123bce", size = 210118, upload-time = "2025-12-02T20:57:42.749Z" }, - { url = "https://files.pythonhosted.org/packages/49/ab/15adb78489b51c2a898642755be727ecd7c3de37cac6e434ce420b8ce27c/vhacdx-0.0.10-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:915eab6c19fdf63ab256855331db546575284786a480aa2d67437db0e86b0d17", size = 238276, upload-time = "2025-12-02T20:57:43.95Z" }, - { url = "https://files.pythonhosted.org/packages/a6/f1/464c761dbe24f58d6fc354bf51729342981fb7a621e170e0d3512fadbec8/vhacdx-0.0.10-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6e335bb9af540e6867ff051166a399075823fdd8fc1fc27e9530995cc1bda1eb", size = 251383, upload-time = "2025-12-02T20:57:45.246Z" }, - { url = "https://files.pythonhosted.org/packages/b2/22/c7b4117c5431189a6a019e8fc2cf590df3ab196c38b4b7c3622292205d9b/vhacdx-0.0.10-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:c3ddbaa38eb65c3aec9b0e39a822223474c931c0e18d3e93a3a499870ffa45ad", size = 1225200, upload-time = "2025-12-02T20:57:46.639Z" }, - { url = "https://files.pythonhosted.org/packages/6c/62/c679ad28ce7854771913255e1abc588b3643c2147fb5c51a8553224aa1dd/vhacdx-0.0.10-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:d398fcc13e330ed1fd2540a7d572aeca0be9621411def78e10c7ea4132f959ee", size = 1285935, upload-time = "2025-12-02T20:57:48.51Z" }, - { url = "https://files.pythonhosted.org/packages/de/c8/a8260b780e4578d7ef19b70343f9717f74ff48f9950138c96c78f209ec01/vhacdx-0.0.10-cp311-cp311-win_amd64.whl", hash = "sha256:c9665a3ef887babcac8b5822f01288e8f06b4a949fadbbe1861670b358f111ee", size = 194137, upload-time = "2025-12-02T20:57:50.207Z" }, - { url = "https://files.pythonhosted.org/packages/cf/9c/66375e65634c80f6efb46e81915126bf3e55dc9d6615217590cbc8316d2e/vhacdx-0.0.10-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:7dd17d697d6d4d7cf66f1e947e0530041913981e05f7025236bec28a350b1a33", size = 224998, upload-time = "2025-12-02T20:57:51.639Z" }, - { url = "https://files.pythonhosted.org/packages/4e/e3/fc2644d3e7d0b2b52e2f681eb2878c0e1b9cafc53946f66736d0f01e237c/vhacdx-0.0.10-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:189ded39b709436cb732cdf694d4cf22e877aefb97e2ab2b55bf7ada9c030f93", size = 211130, upload-time = "2025-12-02T20:57:53.018Z" }, - { url = "https://files.pythonhosted.org/packages/e3/93/0b0f1977f5b3c2e1bbea5ef85e37a808ff73f1b7daf42950c57090e90dc7/vhacdx-0.0.10-cp312-cp312-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f3b03d35ab56a93beee338175dbe0b87552353e5dfb3ff37467e88f56cedf7cc", size = 239661, upload-time = "2025-12-02T20:57:54.144Z" }, - { url = "https://files.pythonhosted.org/packages/94/98/d2a6aeb1c6570a1fc1be29ee03db795f643ab03c6df7635522f23796b39d/vhacdx-0.0.10-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:ea8c54ed193fa0db0248928fbf5d438b3872d615a506889d5b89fc6467d6411a", size = 252938, upload-time = "2025-12-02T20:57:55.275Z" }, - { url = "https://files.pythonhosted.org/packages/94/2e/1e678efc161a0d7fe1806f5e037ce11cc5964db7e08ccfc220ef63951863/vhacdx-0.0.10-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:a5c898104140c72e4dc789e6125812671eee5e412916e83eff24a6148248ff5e", size = 1226696, upload-time = "2025-12-02T20:57:56.438Z" }, - { url = "https://files.pythonhosted.org/packages/90/5b/b302a0420a241c4910f4870eb9f39e6ada59858db441cc35bda511c17982/vhacdx-0.0.10-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:abdd0ba17786e578206594731df15c90e2751b6884220c8673124f47fd7ac620", size = 1287794, upload-time = "2025-12-02T20:57:57.694Z" }, - { url = "https://files.pythonhosted.org/packages/73/e9/f9729603ac75047a257f1b4ddac60cbde72b0abfd49ffed305751ba630a2/vhacdx-0.0.10-cp312-cp312-win_amd64.whl", hash = "sha256:79e7db59b4042295b21b79d55ba486a9a480550f696d466f158a30ed920dd0ec", size = 195033, upload-time = "2025-12-02T20:57:58.95Z" }, - { url = "https://files.pythonhosted.org/packages/0e/54/c2fc08d9324bbd92735caf9207cbabada3a8dd9d270d6e46ca69eb7f883d/vhacdx-0.0.10-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:0599bc2a96de8fc9aeff460b3e88b8572e84ae95b8fc6c9888ef4b92023c22d5", size = 225014, upload-time = "2025-12-02T20:58:00.938Z" }, - { url = "https://files.pythonhosted.org/packages/3b/9e/42adb642a12915acc9cb2bfab21710a6aabf045c26967ba0ff0e08a872d0/vhacdx-0.0.10-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:dc648829a1e973f34ee11393a4f334ab55e3e0e9c4b9f6d6349af966fdf1895a", size = 211127, upload-time = "2025-12-02T20:58:02.107Z" }, - { url = "https://files.pythonhosted.org/packages/51/3d/63e090cd966817b89643d7e52e13df45043b22a42c7fbf702866bdd75bc0/vhacdx-0.0.10-cp313-cp313-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:74c03f7315a434ec83cd0bff1e6bce6af4c01df61d677f48f3ffb36800606ee7", size = 239471, upload-time = "2025-12-02T20:58:03.173Z" }, - { url = "https://files.pythonhosted.org/packages/b8/b4/07ab1c828bae0eb5c72cd9a4cbe8b0376d374509be3c7055e1a399bf85c3/vhacdx-0.0.10-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:1fcd02acc3733ec3a0a0d28ca7f526d4c56f14a3ceb4b12fce45acf72c09054a", size = 253019, upload-time = "2025-12-02T20:58:04.318Z" }, - { url = "https://files.pythonhosted.org/packages/05/cb/bc8a8858b300d2c092da11096ae0586ece446b4c41cb26620bf00d1d8232/vhacdx-0.0.10-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:4b9f8a80ca4c54d7fa76419a2ebd9e9386cd177dc4d2b97f2208ac57c9a7e8aa", size = 1226933, upload-time = "2025-12-02T20:58:05.907Z" }, - { url = "https://files.pythonhosted.org/packages/15/52/213230883874615f1661903bce1ace5013d03b34696efce8d53c662a3358/vhacdx-0.0.10-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:847bd43e82afb439dd3fa972618d786d0b98d8ef04a8e8a6381f6945204d2505", size = 1288871, upload-time = "2025-12-02T20:58:07.432Z" }, - { url = "https://files.pythonhosted.org/packages/32/25/f0e6806824f88d47ab8bc1c9bf6f11634fd7b382d635d0696825f3b5672f/vhacdx-0.0.10-cp313-cp313-win_amd64.whl", hash = "sha256:ab300c5f3fe4e54f99af92f9ea27c977b09df5f59190b0a3e025161110f71ce7", size = 195091, upload-time = "2025-12-02T20:58:08.783Z" }, - { url = "https://files.pythonhosted.org/packages/b7/b8/5137c048728fddd3315a79c94ba8663f3707f9268af9af15b15e1ef3cd85/vhacdx-0.0.10-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:147030c7683be4f21a3cdfb202b121c01716694b61ddad794345fcd9fa43d0ec", size = 225247, upload-time = "2025-12-02T20:58:09.918Z" }, - { url = "https://files.pythonhosted.org/packages/1b/08/5c731863db402e9878380f68be8722fabbcaf8cfe8d06237aaf15f116d95/vhacdx-0.0.10-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:069eb4381917b790921a33d4cc6ed07f7ed5362474232110baf8dd3dadcd768d", size = 211339, upload-time = "2025-12-02T20:58:10.951Z" }, - { url = "https://files.pythonhosted.org/packages/04/3a/e93ce9b653a9f435c530df8d5ad68a80b8bdc2b8518abc225fef9e7f349a/vhacdx-0.0.10-cp314-cp314-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:7702892008b1150619c1f66a62ef88d1cb8f92b09d9c39a0bfb87d147f1c5ae2", size = 239974, upload-time = "2025-12-02T20:58:12.101Z" }, - { url = "https://files.pythonhosted.org/packages/77/dc/ef34f97a65385bc1f8ed4718fa5f7d96313e299e76761f1b69efaf597797/vhacdx-0.0.10-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:b4d550dfc377471b36f11065fc12cfbbd1750d63b10a336644bfdcbf27aa8382", size = 253245, upload-time = "2025-12-02T20:58:13.303Z" }, - { url = "https://files.pythonhosted.org/packages/f4/6c/57051066bd0589b7fe68c32061821180f520b6a7ef4efa072b755dde63d3/vhacdx-0.0.10-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:edce8f0ff516a111b6f1d644782a1d496b3e9e34ff4ce09849c9b8071627bca5", size = 1227432, upload-time = "2025-12-02T20:58:14.73Z" }, - { url = "https://files.pythonhosted.org/packages/1d/49/3488f2bd991027bd86f072cf776935c80b4e630bd3bc43c3289bc6eeeba0/vhacdx-0.0.10-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:4c463abbdce73d5d0b94eab2c9f43f2b55a4d0e788d87af659cc78029b960bf9", size = 1289126, upload-time = "2025-12-02T20:58:16.009Z" }, - { url = "https://files.pythonhosted.org/packages/77/56/2f4506382a1133bf441cba2010017064e8f7af940d100141799d7e867e58/vhacdx-0.0.10-cp314-cp314-win_amd64.whl", hash = "sha256:b93c834f2bf1fa6630da5d3f77e94ea8e542fca31e385244a7ec905a32155549", size = 198706, upload-time = "2025-12-02T20:58:17.378Z" }, - { url = "https://files.pythonhosted.org/packages/db/f6/4fabfe65f3123abda09adc416a396caf8c2ad1b29c34a5178ec71754a163/vhacdx-0.0.10-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:4c0f1bafc53e156472b0367533c2d3ec7a96b676b6d57aa92dd3e37519331b07", size = 228276, upload-time = "2025-12-02T20:58:18.545Z" }, - { url = "https://files.pythonhosted.org/packages/dc/70/bdc742628adcf9966cea81be7a651300bc399b492d10a763781af6d27041/vhacdx-0.0.10-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:b0f8643dcb1f0774320fc1389ead0d0da4536e4c0fecfd4c8133baec0b6fa556", size = 214287, upload-time = "2025-12-02T20:58:19.696Z" }, - { url = "https://files.pythonhosted.org/packages/84/6a/f2e37ad333d3f671e1d59ba76bb61edc5520146539d52ee29e555becb4ac/vhacdx-0.0.10-cp314-cp314t-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:4547f3e55eb935d163d89c10ffdcadf8797c3b435a9dc82be4e0e27b1e3abff0", size = 240923, upload-time = "2025-12-02T20:58:21.105Z" }, - { url = "https://files.pythonhosted.org/packages/5b/7a/f0325cd7ece95dbbc10d0c3f6d241d47beb3b99ae4dafe2e450082cd7bd9/vhacdx-0.0.10-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:ee09c4f2b6385546001b5e8609f428417fac147cfd3ea020fbc7dec0f11c489b", size = 254257, upload-time = "2025-12-02T20:58:22.176Z" }, - { url = "https://files.pythonhosted.org/packages/ac/56/53347b910351eb4cf32a797e177f18b8d82b1ef4e4325607254cfe88ad2a/vhacdx-0.0.10-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:8b94d198e4716f9220985523f374617432ef5530910f3730051f3e7fcba71798", size = 1228434, upload-time = "2025-12-02T20:58:23.302Z" }, - { url = "https://files.pythonhosted.org/packages/be/f5/f86c63da38b0446ef6652e8e72b84451e440418eaac0f554737e159ae36e/vhacdx-0.0.10-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:39c6d31ed27e3f33e9411927e1567ba37a18ba7ce9295efd1b24414b7313b503", size = 1288854, upload-time = "2025-12-02T20:58:24.46Z" }, - { url = "https://files.pythonhosted.org/packages/0c/d1/b30dec954a24b41358297a3fbe7c30d8e2e818831f552cb34c904baa04e4/vhacdx-0.0.10-cp314-cp314t-win_amd64.whl", hash = "sha256:fc6a613082ec522a020e4f6a09f39ed42546de9aebe99548aa84938b1440871c", size = 204896, upload-time = "2025-12-02T20:58:25.825Z" }, -] - [[package]] name = "virtualenv" version = "20.36.1" @@ -11606,29 +11200,6 @@ 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" }, ] -[[package]] -name = "viser" -version = "1.0.27" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "imageio" }, - { name = "msgspec" }, - { 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 = "requests" }, - { name = "rich" }, - { name = "tqdm" }, - { name = "trimesh" }, - { name = "typing-extensions" }, - { name = "websockets" }, - { name = "yourdfpy" }, - { name = "zstandard" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/fd/f5/48adb4e5e4234f48e96a1e7fc50cca6731280df0c279833e333963f9ea5c/viser-1.0.27.tar.gz", hash = "sha256:87e3239d6c1c2c003db93ac4072430ec790e336ffe7214781f035e54faebc0af", size = 4897986, upload-time = "2026-05-06T10:30:47.556Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/7c/ad/8ae712579e294b4395fb39f7d65524b51fc7b731eacce26af096b7e59b61/viser-1.0.27-py3-none-any.whl", hash = "sha256:8da5b7934416e6e2d3a7ebcf39fc840f21030b51eb63231e8cfef457bfb49031", size = 4998748, upload-time = "2026-05-06T10:30:49.965Z" }, -] - [[package]] name = "wadler-lindig" version = "0.1.7" @@ -12397,22 +11968,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/66/c9/d4b03b2490107f13ebd68fe9496d41ae41a7de6275ead56d0d4621b11ffd/yapf-0.40.2-py3-none-any.whl", hash = "sha256:adc8b5dd02c0143108878c499284205adb258aad6db6634e5b869e7ee2bd548b", size = 254707, upload-time = "2023-09-22T18:40:43.297Z" }, ] -[[package]] -name = "yourdfpy" -version = "0.0.60" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "lxml" }, - { 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 = "six" }, - { name = "trimesh", extra = ["easy"] }, -] -sdist = { url = "https://files.pythonhosted.org/packages/ff/19/20c50861f30aff7720f9a601f386d73760c2df9961de1f98d0dbf3b85e69/yourdfpy-0.0.60.tar.gz", hash = "sha256:2af2d8bdeea1b85b642590a3b4236fdb35746d7b3e38ce460a169c18d9c4f868", size = 538238, upload-time = "2026-01-23T07:32:47.856Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/c8/60/4ea0d6df0b497d51bf2ef87eaab0eb26f8bc3b3313c012da5df3383cced9/yourdfpy-0.0.60-py3-none-any.whl", hash = "sha256:8a187a8b18c98db87c76e9a950581b3c875b761e00df83942526c17ea693166c", size = 22194, upload-time = "2026-01-23T07:32:46.481Z" }, -] - [[package]] name = "zipp" version = "3.23.0" From 99975760e523f4cdb5a4c58175014b6f7a188d38 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 07:40:37 +0200 Subject: [PATCH 05/30] Allow MuJoCo playground viewer --- dimos/simulation/mujoco_scene_playground.py | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/dimos/simulation/mujoco_scene_playground.py b/dimos/simulation/mujoco_scene_playground.py index 1dbacd4a56..e23a148c77 100644 --- a/dimos/simulation/mujoco_scene_playground.py +++ b/dimos/simulation/mujoco_scene_playground.py @@ -42,6 +42,13 @@ def _env_float(name: str, default: float) -> float: return default if raw is None or raw == "" else float(raw) +def _env_bool(name: str, default: bool) -> bool: + raw = os.environ.get(name) + if raw is None or raw == "": + return default + return raw.lower() in {"1", "true", "yes", "on"} + + def _env_xyz(name: str, default: tuple[float, float, float]) -> tuple[float, float, float]: raw = os.environ.get(name) if raw is None or raw.strip() == "": @@ -135,7 +142,7 @@ def _command_center_blueprints() -> list[Blueprint]: MujocoSimModule.blueprint( address=_sim_mjcf_path, meshdir=_mjcf_meshdir, - headless=True, + headless=_env_bool("DIMOS_MUJOCO_HEADLESS", True), dof=_dof, camera_name=os.environ.get("DIMOS_MUJOCO_CAMERA", "head_color"), enable_color=False, From 9fac37debd223efe41cf8c454d3692c941577424 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 07:48:02 +0200 Subject: [PATCH 06/30] Fix MuJoCo PR nits --- dimos/mapping/mesh_scene.py | 6 ++-- dimos/mapping/scene_mesh_to_mjcf.py | 23 +++++++++------ .../movement_manager/movement_manager.py | 8 ++--- .../movement_manager/test_movement_manager.py | 29 +++++++++---------- dimos/simulation/engines/mujoco_sim_module.py | 28 ++++++++++-------- dimos/simulation/mujoco_scene_playground.py | 4 +-- .../web/websocket_vis/websocket_vis_module.py | 16 +++++----- 7 files changed, 57 insertions(+), 57 deletions(-) diff --git a/dimos/mapping/mesh_scene.py b/dimos/mapping/mesh_scene.py index bc328dd2c0..e5db224567 100644 --- a/dimos/mapping/mesh_scene.py +++ b/dimos/mapping/mesh_scene.py @@ -12,7 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -"""Load a 3D scene mesh from disk for ray-casting + visualization. +"""Load a 3D scene mesh from disk for ray-casting and MuJoCo collision. Supports: * ``.glb`` / ``.gltf`` / ``.obj`` / ``.ply`` / ``.stl`` — via Open3D's @@ -22,8 +22,8 @@ Returned form is a single concatenated ``open3d.geometry.TriangleMesh`` in world frame, with optional scale + Y-up→Z-up + translation applied. -The same mesh can feed browser visualization, ray-casting, and MJCF -collision wrapping so the visual and physical scene share one transform. +The same mesh can feed ray-casting and MJCF collision wrapping so the +geometric query path and physical scene share one transform. """ from __future__ import annotations diff --git a/dimos/mapping/scene_mesh_to_mjcf.py b/dimos/mapping/scene_mesh_to_mjcf.py index c9f77f6fd2..8caa961451 100644 --- a/dimos/mapping/scene_mesh_to_mjcf.py +++ b/dimos/mapping/scene_mesh_to_mjcf.py @@ -19,12 +19,13 @@ from dataclasses import asdict, dataclass import hashlib from pathlib import Path +import sys from typing import Any import numpy as np import open3d as o3d # type: ignore[import-untyped] -from dimos.mapping.mesh_scene import SceneMeshAlignment +from dimos.mapping.mesh_scene import SceneMeshAlignment, load_scene_prims from dimos.utils.logging_config import setup_logger logger = setup_logger() @@ -55,6 +56,11 @@ ) _DEGENERATE_EPS = 1e-3 _SHELL_VOLUME_M3 = 2.0 +_CACHE_KEY_LEN = 12 +_VHACD_MAX_HULLS = 64 +_VHACD_RESOLUTION = 200_000 +_MIN_HULL_ASPECT_RATIO = 0.05 +_MIN_HULL_EXTENT_M = 5e-3 @dataclass @@ -116,8 +122,6 @@ def bake_scene_mjcf( cache_dir.mkdir(parents=True, exist_ok=True) - from dimos.mapping.mesh_scene import load_scene_prims - logger.info(f"bake_scene_mjcf: loading + aligning {scene_mesh_path} (per-prim)") prims = load_scene_prims(scene_mesh_path, alignment=align) logger.info(f"bake_scene_mjcf: {len(prims)} prims to bake") @@ -155,7 +159,7 @@ def _cache_key( h.update(robot_mjcf_path.read_bytes()) h.update(repr(sorted(asdict(alignment).items())).encode()) h.update(str(meshdir).encode()) - return h.hexdigest()[:12] + return h.hexdigest()[:_CACHE_KEY_LEN] def _cache_hit(wrapper_path: Path, cache_dir: Path) -> bool: @@ -218,7 +222,10 @@ def _collision_hulls(tm: Any, single_hull: Any, prim_name: str) -> tuple[list[An if float(single_hull.volume) <= _SHELL_VOLUME_M3: return [single_hull], False try: - parts = tm.convex_decomposition(maxConvexHulls=64, resolution=200_000) + parts = tm.convex_decomposition( + maxConvexHulls=_VHACD_MAX_HULLS, + resolution=_VHACD_RESOLUTION, + ) hulls = parts if isinstance(parts, list) else [parts] logger.info( f" {prim_name}: VHACD decomposed " @@ -241,9 +248,9 @@ def _valid_hull(v: np.ndarray, f: np.ndarray) -> bool: return False min_ext = float(extent.min()) max_ext = float(extent.max()) - if max_ext > 0 and (min_ext / max_ext) < 0.05: + if max_ext > 0 and (min_ext / max_ext) < _MIN_HULL_ASPECT_RATIO: return False - if min_ext < 5e-3: + if min_ext < _MIN_HULL_EXTENT_M: return False try: from scipy.spatial import ConvexHull, QhullError @@ -290,8 +297,6 @@ def _write_wrapper( def cli_main() -> None: """Bake a wrapper, verify it loads, optionally open MuJoCo's native viewer.""" - import sys - args = list(sys.argv[1:]) view = False if "--view" in args: diff --git a/dimos/navigation/movement_manager/movement_manager.py b/dimos/navigation/movement_manager/movement_manager.py index 330498b239..7db7511a8f 100644 --- a/dimos/navigation/movement_manager/movement_manager.py +++ b/dimos/navigation/movement_manager/movement_manager.py @@ -38,7 +38,7 @@ logger = setup_logger() -# without this you can (basically) click into infinity in rerun (not good for the planner) +# Reject accidental clicks far outside the local planning area. MAX_CLICK_HORIZONTAL_M = 500.0 MAX_CLICK_VERTICAL_M = 50.0 TELEOP_EPS = 1e-6 @@ -50,7 +50,7 @@ class MovementManagerConfig(ModuleConfig): class MovementManager(Module): - """Combine tele_cmd_vel (keyboard controls) and nav_cmd_vel in a sane way, output cmd_vel""" + """Mux teleop and navigation velocity commands into cmd_vel.""" config: MovementManagerConfig @@ -100,9 +100,6 @@ def _on_click(self, msg: PointStamped) -> None: def _cancel_goal(self) -> None: self.stop_movement.publish(Bool(data=True)) - # NOTE: this NaN goal is more of a safety fallback. - # It can be REALLY bad if a robot is supposed to stop moving but wont - # we should probably think a more robust/strict requirement on planners cancel = PointStamped( ts=time.time(), frame_id="map", x=float("nan"), y=float("nan"), z=float("nan") ) @@ -113,7 +110,6 @@ def _cancel_goal(self) -> None: def _on_nav(self, msg: Twist) -> None: with self._lock: if self._teleop_active: - # check if cooldown has expired elapsed = time.monotonic() - self._last_teleop_time if elapsed < self.config.tele_cooldown_sec: return diff --git a/dimos/navigation/movement_manager/test_movement_manager.py b/dimos/navigation/movement_manager/test_movement_manager.py index e065a48c32..e3de9f1ddc 100644 --- a/dimos/navigation/movement_manager/test_movement_manager.py +++ b/dimos/navigation/movement_manager/test_movement_manager.py @@ -43,29 +43,29 @@ class Captured: def _attach(module): """Subscribe to every Out port; return (captured, unsubscribers).""" captured = Captured() - unsubs = [ + unsubscribe_callbacks = [ module.cmd_vel.subscribe(captured.cmd_vel.append), module.stop_movement.subscribe(captured.stop_movement.append), module.goal.subscribe(captured.goal.append), module.way_point.subscribe(captured.way_point.append), ] - return captured, unsubs + return captured, unsubscribe_callbacks @pytest.fixture() def manager_and_captured() -> Generator[tuple[MovementManager, Captured], None, None]: module = MovementManager(tele_cooldown_sec=0.1) - captured, unsubs = _attach(module) + captured, unsubscribe_callbacks = _attach(module) try: yield module, captured finally: - for unsub in unsubs: - unsub() + for unsubscribe in unsubscribe_callbacks: + unsubscribe() module._close_module() -def _twist(lx=0.0): - return Twist(linear=Vector3(lx, 0, 0), angular=Vector3(0, 0, 0)) +def _twist(linear_x=0.0): + return Twist(linear=Vector3(linear_x, 0, 0), angular=Vector3(0, 0, 0)) def _click(x=1.0, y=2.0, z=0.0): @@ -76,17 +76,14 @@ def test_teleop_suppresses_nav_and_cancels_goal(manager_and_captured): """Teleop arriving should suppress nav, publish stop_movement, and cancel the goal with NaN.""" manager, captured = manager_and_captured manager.config.tele_cooldown_sec = 10.0 - manager._on_teleop(_twist(lx=0.3)) + manager._on_teleop(_twist(linear_x=0.3)) cmd_count_after_teleop = len(captured.cmd_vel) - manager._on_nav(_twist(lx=0.9)) - # Nav was suppressed: no new cmd_vel + manager._on_nav(_twist(linear_x=0.9)) assert len(captured.cmd_vel) == cmd_count_after_teleop - # stop_movement fired assert len(captured.stop_movement) == 1 - # Goal cancelled with NaN assert len(captured.goal) == 1 assert math.isnan(captured.goal[0].x) @@ -95,11 +92,11 @@ def test_nav_resumes_after_cooldown(manager_and_captured): """After the cooldown expires, nav commands pass through again.""" manager, captured = manager_and_captured manager.config.tele_cooldown_sec = 0.05 - manager._on_teleop(_twist(lx=0.3)) + manager._on_teleop(_twist(linear_x=0.3)) time.sleep(DEFAULT_THREAD_JOIN_TIMEOUT) cmd_count_before = len(captured.cmd_vel) - manager._on_nav(_twist(lx=0.9)) + manager._on_nav(_twist(linear_x=0.9)) assert len(captured.cmd_vel) == cmd_count_before + 1 @@ -118,8 +115,8 @@ def test_continuous_teleop_cancels_once(manager_and_captured): """Holding WASD should not repeatedly cancel an already-cancelled goal.""" manager, captured = manager_and_captured - manager._on_teleop(_twist(lx=0.3)) - manager._on_teleop(_twist(lx=0.3)) + manager._on_teleop(_twist(linear_x=0.3)) + manager._on_teleop(_twist(linear_x=0.3)) manager._on_teleop(_twist()) assert len(captured.stop_movement) == 1 diff --git a/dimos/simulation/engines/mujoco_sim_module.py b/dimos/simulation/engines/mujoco_sim_module.py index 4443c2d7d3..50c052f796 100644 --- a/dimos/simulation/engines/mujoco_sim_module.py +++ b/dimos/simulation/engines/mujoco_sim_module.py @@ -68,6 +68,13 @@ logger = setup_logger() _RX180 = R.from_euler("x", 180, degrees=True) +_LIDAR_GEOM_GROUPS = (0, 0, 1, 1, 0, 0) +_CMD_VEL_STALE_SEC = 0.5 +_ENGINE_CONNECT_TIMEOUT_SEC = 30.0 +_PUBLISH_THREAD_JOIN_TIMEOUT_SEC = 2.0 +_ENGINE_CONNECT_POLL_SEC = 0.1 +_STALE_FRAME_POLL_FRACTION = 0.5 +_RGBD_POINTCLOUD_VOXEL_SIZE = 0.005 def _default_identity_transform() -> Transform: @@ -193,6 +200,7 @@ def get_depth_scale(self) -> float: @rpc def start(self) -> None: + super().start() if not self.config.address: raise RuntimeError("MujocoSimModule: config.address (MJCF path) is required") @@ -245,12 +253,8 @@ def _make_camera_configs(self) -> list[CameraConfig]: ) lidar_scene_option = mujoco.MjvOption() - lidar_scene_option.geomgroup[0] = 0 - lidar_scene_option.geomgroup[1] = 0 - lidar_scene_option.geomgroup[2] = 1 - lidar_scene_option.geomgroup[3] = 1 - lidar_scene_option.geomgroup[4] = 0 - lidar_scene_option.geomgroup[5] = 0 + for group_id, enabled in enumerate(_LIDAR_GEOM_GROUPS): + lidar_scene_option.geomgroup[group_id] = enabled for lidar_name in self.config.lidar_camera_names: if lidar_name == self.config.camera_name and self._primary_camera_needed: continue @@ -329,7 +333,7 @@ def _start_pointcloud_publisher(self) -> None: def stop(self) -> None: self._stop_event.set() if self._publish_thread and self._publish_thread.is_alive(): - self._publish_thread.join(timeout=2.0) + self._publish_thread.join(timeout=_PUBLISH_THREAD_JOIN_TIMEOUT_SEC) self._publish_thread = None errors: list[tuple[str, BaseException]] = [] @@ -388,7 +392,7 @@ def _apply_cmd_vel(self, engine: MujocoEngine) -> None: with self._cmd_vel_lock: cmd = Twist(self._cmd_vel) age = time.monotonic() - self._last_cmd_vel_time - if age > 0.5: + if age > _CMD_VEL_STALE_SEC: cmd = Twist.zero() engine.apply_root_twist( cmd.linear.x, @@ -478,12 +482,12 @@ def _publish_loop(self) -> None: published_count = 0 # Wait for engine to actually be connected (sim thread may take a tick). - deadline = time.monotonic() + 30.0 + deadline = time.monotonic() + _ENGINE_CONNECT_TIMEOUT_SEC while not self._stop_event.is_set() and not engine.connected: if time.monotonic() > deadline: logger.error("MujocoSimModule: timed out waiting for engine to connect") return - self._stop_event.wait(timeout=0.1) + self._stop_event.wait(timeout=_ENGINE_CONNECT_POLL_SEC) if self._stop_event.is_set(): return @@ -501,7 +505,7 @@ def _publish_loop(self) -> None: return if frame is None or frame.timestamp <= last_timestamp: - self._stop_event.wait(timeout=interval * 0.5) + self._stop_event.wait(timeout=interval * _STALE_FRAME_POLL_FRACTION) continue last_timestamp = frame.timestamp ts = time.time() @@ -623,7 +627,7 @@ def _generate_pointcloud(self) -> None: camera_info=self._camera_info_base, depth_scale=1.0, ) - pcd = pcd.voxel_downsample(0.005) + pcd = pcd.voxel_downsample(_RGBD_POINTCLOUD_VOXEL_SIZE) self.pointcloud.publish(pcd) except Exception as exc: logger.error("Pointcloud generation error", error=str(exc)) diff --git a/dimos/simulation/mujoco_scene_playground.py b/dimos/simulation/mujoco_scene_playground.py index e23a148c77..ea55d2357d 100644 --- a/dimos/simulation/mujoco_scene_playground.py +++ b/dimos/simulation/mujoco_scene_playground.py @@ -16,6 +16,7 @@ from __future__ import annotations +import logging import os from pathlib import Path @@ -67,7 +68,6 @@ def _command_center_blueprints() -> list[Blueprint]: except ModuleNotFoundError as exc: if exc.name not in {"socketio", "fastapi", "uvicorn", "starlette"}: raise - import logging logging.getLogger(__name__).warning( "Command Center unavailable; install the web extra to enable WASD controls" @@ -131,8 +131,6 @@ def _command_center_blueprints() -> list[Blueprint]: ) ) except Exception as exc: - import logging - logging.getLogger(__name__).warning( "Failed to bake scene mesh into MuJoCo; lidar will only see the base MJCF: %s", exc, diff --git a/dimos/web/websocket_vis/websocket_vis_module.py b/dimos/web/websocket_vis/websocket_vis_module.py index a9bc69536f..b95659affb 100644 --- a/dimos/web/websocket_vis/websocket_vis_module.py +++ b/dimos/web/websocket_vis/websocket_vis_module.py @@ -173,26 +173,26 @@ def start(self) -> None: logger.debug(f"Failed to open browser: {e}") try: - unsub = self.odom.subscribe(self._on_robot_pose) - self.register_disposable(Disposable(unsub)) + unsubscribe = self.odom.subscribe(self._on_robot_pose) + self.register_disposable(Disposable(unsubscribe)) except Exception: ... try: - unsub = self.gps_location.subscribe(self._on_gps_location) - self.register_disposable(Disposable(unsub)) + unsubscribe = self.gps_location.subscribe(self._on_gps_location) + self.register_disposable(Disposable(unsubscribe)) except Exception: ... try: - unsub = self.path.subscribe(self._on_path) - self.register_disposable(Disposable(unsub)) + unsubscribe = self.path.subscribe(self._on_path) + self.register_disposable(Disposable(unsubscribe)) except Exception: ... try: - unsub = self.global_costmap.subscribe(self._on_global_costmap) - self.register_disposable(Disposable(unsub)) + unsubscribe = self.global_costmap.subscribe(self._on_global_costmap) + self.register_disposable(Disposable(unsubscribe)) except Exception: ... From 622ec574512ccc26028b58e78c37ccd01b7a88d1 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 07:52:38 +0200 Subject: [PATCH 07/30] Remove MovementManager changes from MuJoCo PR --- .../movement_manager/movement_manager.py | 30 ++++-------- .../movement_manager/test_movement_manager.py | 48 ++++++------------- 2 files changed, 23 insertions(+), 55 deletions(-) diff --git a/dimos/navigation/movement_manager/movement_manager.py b/dimos/navigation/movement_manager/movement_manager.py index 7db7511a8f..ed12dc93ac 100644 --- a/dimos/navigation/movement_manager/movement_manager.py +++ b/dimos/navigation/movement_manager/movement_manager.py @@ -38,10 +38,9 @@ logger = setup_logger() -# Reject accidental clicks far outside the local planning area. +# without this you can (basically) click into infinity in rerun (not good for the planner) MAX_CLICK_HORIZONTAL_M = 500.0 MAX_CLICK_VERTICAL_M = 50.0 -TELEOP_EPS = 1e-6 class MovementManagerConfig(ModuleConfig): @@ -50,7 +49,7 @@ class MovementManagerConfig(ModuleConfig): class MovementManager(Module): - """Mux teleop and navigation velocity commands into cmd_vel.""" + """Combine tele_cmd_vel (keyboard controls) and nav_cmd_vel in a sane way, output cmd_vel""" config: MovementManagerConfig @@ -100,6 +99,9 @@ def _on_click(self, msg: PointStamped) -> None: def _cancel_goal(self) -> None: self.stop_movement.publish(Bool(data=True)) + # NOTE: this NaN goal is more of a safety fallback. + # It can be REALLY bad if a robot is supposed to stop moving but wont + # we should probably think a more robust/strict requirement on planners cancel = PointStamped( ts=time.time(), frame_id="map", x=float("nan"), y=float("nan"), z=float("nan") ) @@ -110,6 +112,7 @@ def _cancel_goal(self) -> None: def _on_nav(self, msg: Twist) -> None: with self._lock: if self._teleop_active: + # check if cooldown has expired elapsed = time.monotonic() - self._last_teleop_time if elapsed < self.config.tele_cooldown_sec: return @@ -117,26 +120,11 @@ def _on_nav(self, msg: Twist) -> None: self.cmd_vel.publish(msg) def _on_teleop(self, msg: Twist) -> None: - is_zero = ( - abs(msg.linear.x) < TELEOP_EPS - and abs(msg.linear.y) < TELEOP_EPS - and abs(msg.linear.z) < TELEOP_EPS - and abs(msg.angular.x) < TELEOP_EPS - and abs(msg.angular.y) < TELEOP_EPS - and abs(msg.angular.z) < TELEOP_EPS - ) - with self._lock: - was_active = self._teleop_active - if is_zero: - if not was_active: - return - else: - self._teleop_active = True - self._last_teleop_time = time.monotonic() + self._teleop_active = True + self._last_teleop_time = time.monotonic() - if not is_zero and not was_active: - self._cancel_goal() + self._cancel_goal() scale = self.config.tele_cmd_vel_scaling scaled = Twist( diff --git a/dimos/navigation/movement_manager/test_movement_manager.py b/dimos/navigation/movement_manager/test_movement_manager.py index e3de9f1ddc..e266ad3e98 100644 --- a/dimos/navigation/movement_manager/test_movement_manager.py +++ b/dimos/navigation/movement_manager/test_movement_manager.py @@ -43,29 +43,29 @@ class Captured: def _attach(module): """Subscribe to every Out port; return (captured, unsubscribers).""" captured = Captured() - unsubscribe_callbacks = [ + unsubs = [ module.cmd_vel.subscribe(captured.cmd_vel.append), module.stop_movement.subscribe(captured.stop_movement.append), module.goal.subscribe(captured.goal.append), module.way_point.subscribe(captured.way_point.append), ] - return captured, unsubscribe_callbacks + return captured, unsubs @pytest.fixture() def manager_and_captured() -> Generator[tuple[MovementManager, Captured], None, None]: module = MovementManager(tele_cooldown_sec=0.1) - captured, unsubscribe_callbacks = _attach(module) + captured, unsubs = _attach(module) try: yield module, captured finally: - for unsubscribe in unsubscribe_callbacks: - unsubscribe() + for unsub in unsubs: + unsub() module._close_module() -def _twist(linear_x=0.0): - return Twist(linear=Vector3(linear_x, 0, 0), angular=Vector3(0, 0, 0)) +def _twist(lx=0.0): + return Twist(linear=Vector3(lx, 0, 0), angular=Vector3(0, 0, 0)) def _click(x=1.0, y=2.0, z=0.0): @@ -76,14 +76,17 @@ def test_teleop_suppresses_nav_and_cancels_goal(manager_and_captured): """Teleop arriving should suppress nav, publish stop_movement, and cancel the goal with NaN.""" manager, captured = manager_and_captured manager.config.tele_cooldown_sec = 10.0 - manager._on_teleop(_twist(linear_x=0.3)) + manager._on_teleop(_twist(lx=0.3)) cmd_count_after_teleop = len(captured.cmd_vel) - manager._on_nav(_twist(linear_x=0.9)) + manager._on_nav(_twist(lx=0.9)) + # Nav was suppressed: no new cmd_vel assert len(captured.cmd_vel) == cmd_count_after_teleop + # stop_movement fired assert len(captured.stop_movement) == 1 + # Goal cancelled with NaN assert len(captured.goal) == 1 assert math.isnan(captured.goal[0].x) @@ -92,37 +95,14 @@ def test_nav_resumes_after_cooldown(manager_and_captured): """After the cooldown expires, nav commands pass through again.""" manager, captured = manager_and_captured manager.config.tele_cooldown_sec = 0.05 - manager._on_teleop(_twist(linear_x=0.3)) + manager._on_teleop(_twist(lx=0.3)) time.sleep(DEFAULT_THREAD_JOIN_TIMEOUT) cmd_count_before = len(captured.cmd_vel) - manager._on_nav(_twist(linear_x=0.9)) + manager._on_nav(_twist(lx=0.9)) assert len(captured.cmd_vel) == cmd_count_before + 1 -def test_idle_teleop_does_not_cancel_nav(manager_and_captured): - """Idle command-center updates should not spam stop_movement.""" - manager, captured = manager_and_captured - - manager._on_teleop(_twist()) - manager._on_teleop(_twist()) - - assert captured.stop_movement == [] - assert captured.cmd_vel == [] - - -def test_continuous_teleop_cancels_once(manager_and_captured): - """Holding WASD should not repeatedly cancel an already-cancelled goal.""" - manager, captured = manager_and_captured - - manager._on_teleop(_twist(linear_x=0.3)) - manager._on_teleop(_twist(linear_x=0.3)) - manager._on_teleop(_twist()) - - assert len(captured.stop_movement) == 1 - assert len(captured.cmd_vel) == 3 - - def test_valid_click_publishes_goal(manager_and_captured): """A valid click should publish to both goal and way_point.""" manager, captured = manager_and_captured From 6897104273578250972cd933cd7632651ac19bb2 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 08:01:13 +0200 Subject: [PATCH 08/30] Remove WebsocketVis cleanup from MuJoCo PR --- .../web/websocket_vis/websocket_vis_module.py | 23 ++++++++++++------- 1 file changed, 15 insertions(+), 8 deletions(-) diff --git a/dimos/web/websocket_vis/websocket_vis_module.py b/dimos/web/websocket_vis/websocket_vis_module.py index b95659affb..ed319e52ca 100644 --- a/dimos/web/websocket_vis/websocket_vis_module.py +++ b/dimos/web/websocket_vis/websocket_vis_module.py @@ -173,26 +173,26 @@ def start(self) -> None: logger.debug(f"Failed to open browser: {e}") try: - unsubscribe = self.odom.subscribe(self._on_robot_pose) - self.register_disposable(Disposable(unsubscribe)) + unsub = self.odom.subscribe(self._on_robot_pose) + self.register_disposable(Disposable(unsub)) except Exception: ... try: - unsubscribe = self.gps_location.subscribe(self._on_gps_location) - self.register_disposable(Disposable(unsubscribe)) + unsub = self.gps_location.subscribe(self._on_gps_location) + self.register_disposable(Disposable(unsub)) except Exception: ... try: - unsubscribe = self.path.subscribe(self._on_path) - self.register_disposable(Disposable(unsubscribe)) + unsub = self.path.subscribe(self._on_path) + self.register_disposable(Disposable(unsub)) except Exception: ... try: - unsubscribe = self.global_costmap.subscribe(self._on_global_costmap) - self.register_disposable(Disposable(unsubscribe)) + unsub = self.global_costmap.subscribe(self._on_global_costmap) + self.register_disposable(Disposable(unsub)) except Exception: ... @@ -205,6 +205,13 @@ def stop(self) -> None: if self._uvicorn_server: self._uvicorn_server.should_exit = True + if self.sio and self._broadcast_loop and not self._broadcast_loop.is_closed(): + + async def _disconnect_all() -> None: + await self.sio.disconnect() + + asyncio.run_coroutine_threadsafe(_disconnect_all(), self._broadcast_loop) + if self._broadcast_loop and not self._broadcast_loop.is_closed(): self._broadcast_loop.call_soon_threadsafe(self._broadcast_loop.stop) From 7ddcc148818d765598bb450e4aac267ae852c601 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 08:10:46 +0200 Subject: [PATCH 09/30] Keep MuJoCo deps scoped to sim --- pyproject.toml | 1 - uv.lock | 6 ------ 2 files changed, 7 deletions(-) diff --git a/pyproject.toml b/pyproject.toml index e2035c9de7..80ee4a8756 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -176,7 +176,6 @@ agents = [ web = [ "fastapi>=0.115.6", - "python-socketio>=5.11.0,<6", "sse-starlette>=2.2.1", "uvicorn>=0.34.0", "jinja2>=3.1.6", diff --git a/uv.lock b/uv.lock index 24c3db1a90..f78f21a945 100644 --- a/uv.lock +++ b/uv.lock @@ -1951,7 +1951,6 @@ all = [ { name = "pymavlink" }, { name = "pyrealsense2", marker = "sys_platform != 'darwin'" }, { name = "python-multipart" }, - { name = "python-socketio" }, { name = "pyturbojpeg" }, { name = "pyyaml" }, { name = "reactivex" }, @@ -2006,7 +2005,6 @@ base = [ { name = "langchain-text-splitters" }, { name = "ollama" }, { name = "openai" }, - { name = "python-socketio" }, { name = "rerun-sdk" }, { name = "sounddevice" }, { name = "soundfile" }, @@ -2130,7 +2128,6 @@ unitree = [ { name = "langchain-text-splitters" }, { name = "ollama" }, { name = "openai" }, - { name = "python-socketio" }, { name = "rerun-sdk" }, { name = "sounddevice" }, { name = "soundfile" }, @@ -2155,7 +2152,6 @@ unitree-dds = [ { name = "langchain-text-splitters" }, { name = "ollama" }, { name = "openai" }, - { name = "python-socketio" }, { name = "rerun-sdk" }, { name = "sounddevice" }, { name = "soundfile" }, @@ -2172,7 +2168,6 @@ web = [ { name = "fastapi" }, { name = "ffmpeg-python" }, { name = "jinja2" }, - { name = "python-socketio" }, { name = "soundfile" }, { name = "sse-starlette" }, { name = "uvicorn" }, @@ -2417,7 +2412,6 @@ requires-dist = [ { name = "pyrealsense2", marker = "sys_platform != 'darwin' and extra == 'manipulation'" }, { name = "python-dotenv" }, { name = "python-multipart", marker = "extra == 'misc'", specifier = ">=0.0.27" }, - { name = "python-socketio", marker = "extra == 'web'", specifier = ">=5.11.0,<6" }, { name = "pyturbojpeg", specifier = "==1.8.2" }, { name = "pyturbojpeg", marker = "extra == 'docker'" }, { name = "pyyaml", marker = "extra == 'manipulation'", specifier = ">=6.0" }, From fa9d57e51bf839a3644afcb924982526f4b99293 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 08:17:19 +0200 Subject: [PATCH 10/30] Declare Command Center Socket.IO dependency --- pyproject.toml | 1 + uv.lock | 6 ++++++ 2 files changed, 7 insertions(+) diff --git a/pyproject.toml b/pyproject.toml index 80ee4a8756..e2035c9de7 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -176,6 +176,7 @@ agents = [ web = [ "fastapi>=0.115.6", + "python-socketio>=5.11.0,<6", "sse-starlette>=2.2.1", "uvicorn>=0.34.0", "jinja2>=3.1.6", diff --git a/uv.lock b/uv.lock index f78f21a945..24c3db1a90 100644 --- a/uv.lock +++ b/uv.lock @@ -1951,6 +1951,7 @@ all = [ { name = "pymavlink" }, { name = "pyrealsense2", marker = "sys_platform != 'darwin'" }, { name = "python-multipart" }, + { name = "python-socketio" }, { name = "pyturbojpeg" }, { name = "pyyaml" }, { name = "reactivex" }, @@ -2005,6 +2006,7 @@ base = [ { name = "langchain-text-splitters" }, { name = "ollama" }, { name = "openai" }, + { name = "python-socketio" }, { name = "rerun-sdk" }, { name = "sounddevice" }, { name = "soundfile" }, @@ -2128,6 +2130,7 @@ unitree = [ { name = "langchain-text-splitters" }, { name = "ollama" }, { name = "openai" }, + { name = "python-socketio" }, { name = "rerun-sdk" }, { name = "sounddevice" }, { name = "soundfile" }, @@ -2152,6 +2155,7 @@ unitree-dds = [ { name = "langchain-text-splitters" }, { name = "ollama" }, { name = "openai" }, + { name = "python-socketio" }, { name = "rerun-sdk" }, { name = "sounddevice" }, { name = "soundfile" }, @@ -2168,6 +2172,7 @@ web = [ { name = "fastapi" }, { name = "ffmpeg-python" }, { name = "jinja2" }, + { name = "python-socketio" }, { name = "soundfile" }, { name = "sse-starlette" }, { name = "uvicorn" }, @@ -2412,6 +2417,7 @@ requires-dist = [ { name = "pyrealsense2", marker = "sys_platform != 'darwin' and extra == 'manipulation'" }, { name = "python-dotenv" }, { name = "python-multipart", marker = "extra == 'misc'", specifier = ">=0.0.27" }, + { name = "python-socketio", marker = "extra == 'web'", specifier = ">=5.11.0,<6" }, { name = "pyturbojpeg", specifier = "==1.8.2" }, { name = "pyturbojpeg", marker = "extra == 'docker'" }, { name = "pyyaml", marker = "extra == 'manipulation'", specifier = ">=6.0" }, From a6bb1e45dc027062b8d12b5aa0ee90a058a9689f Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 08:27:22 +0200 Subject: [PATCH 11/30] Rename MuJoCo target to G1 GROOT WBC --- dimos/robot/all_blueprints.py | 2 +- .../unitree/g1/blueprints/basic/g1_groot_wbc.py} | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) rename dimos/{simulation/mujoco_scene_playground.py => robot/unitree/g1/blueprints/basic/g1_groot_wbc.py} (98%) diff --git a/dimos/robot/all_blueprints.py b/dimos/robot/all_blueprints.py index cfae58530c..b3878e7a78 100644 --- a/dimos/robot/all_blueprints.py +++ b/dimos/robot/all_blueprints.py @@ -53,6 +53,7 @@ "drone-agentic": "dimos.robot.drone.blueprints.agentic.drone_agentic:drone_agentic", "drone-basic": "dimos.robot.drone.blueprints.basic.drone_basic:drone_basic", "dual-xarm6-planner": "dimos.manipulation.blueprints:dual_xarm6_planner", + "g1-groot-wbc": "dimos.robot.unitree.g1.blueprints.basic.g1_groot_wbc:g1_groot_wbc", "keyboard-teleop-openarm": "dimos.robot.manipulators.openarm.blueprints:keyboard_teleop_openarm", "keyboard-teleop-openarm-mock": "dimos.robot.manipulators.openarm.blueprints:keyboard_teleop_openarm_mock", "keyboard-teleop-piper": "dimos.robot.manipulators.piper.blueprints:keyboard_teleop_piper", @@ -62,7 +63,6 @@ "mid360-fastlio": "dimos.hardware.sensors.lidar.fastlio2.fastlio_blueprints:mid360_fastlio", "mid360-fastlio-voxels": "dimos.hardware.sensors.lidar.fastlio2.fastlio_blueprints:mid360_fastlio_voxels", "mid360-fastlio-voxels-native": "dimos.hardware.sensors.lidar.fastlio2.fastlio_blueprints:mid360_fastlio_voxels_native", - "mujoco-scene-playground": "dimos.simulation.mujoco_scene_playground:mujoco_scene_playground", "openarm-mock-planner-coordinator": "dimos.robot.manipulators.openarm.blueprints:openarm_mock_planner_coordinator", "openarm-planner-coordinator": "dimos.robot.manipulators.openarm.blueprints:openarm_planner_coordinator", "teleop-phone": "dimos.teleop.phone.blueprints:teleop_phone", diff --git a/dimos/simulation/mujoco_scene_playground.py b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py similarity index 98% rename from dimos/simulation/mujoco_scene_playground.py rename to dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py index ea55d2357d..f857907525 100644 --- a/dimos/simulation/mujoco_scene_playground.py +++ b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py @@ -12,7 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -"""MuJoCo scene playground with optional mesh collision.""" +"""G1 GROOT WBC target backed by MuJoCo during development.""" from __future__ import annotations @@ -136,7 +136,7 @@ def _command_center_blueprints() -> list[Blueprint]: exc, ) -mujoco_scene_playground = autoconnect( +g1_groot_wbc = autoconnect( MujocoSimModule.blueprint( address=_sim_mjcf_path, meshdir=_mjcf_meshdir, @@ -183,4 +183,4 @@ def _command_center_blueprints() -> list[Blueprint]: } ) -__all__ = ["mujoco_scene_playground"] +__all__ = ["g1_groot_wbc"] From a7c451411ebcca26e45e6f4d43cdc9a3848c7428 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 08:42:15 +0200 Subject: [PATCH 12/30] Move scene mesh tooling under MuJoCo --- dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py | 4 ++-- dimos/{mapping => simulation/mujoco}/mesh_scene.py | 0 dimos/{mapping => simulation/mujoco}/scene_mesh_to_mjcf.py | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) rename dimos/{mapping => simulation/mujoco}/mesh_scene.py (100%) rename dimos/{mapping => simulation/mujoco}/scene_mesh_to_mjcf.py (98%) diff --git a/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py index f857907525..a7f8d6974e 100644 --- a/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py +++ b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py @@ -114,8 +114,8 @@ def _command_center_blueprints() -> list[Blueprint]: _sim_mjcf_path = _mjcf_path if _scene_mesh_path and _scene_mesh_collision: try: - from dimos.mapping.mesh_scene import SceneMeshAlignment - from dimos.mapping.scene_mesh_to_mjcf import bake_scene_mjcf + from dimos.simulation.mujoco.mesh_scene import SceneMeshAlignment + from dimos.simulation.mujoco.scene_mesh_to_mjcf import bake_scene_mjcf _sim_mjcf_path = str( bake_scene_mjcf( diff --git a/dimos/mapping/mesh_scene.py b/dimos/simulation/mujoco/mesh_scene.py similarity index 100% rename from dimos/mapping/mesh_scene.py rename to dimos/simulation/mujoco/mesh_scene.py diff --git a/dimos/mapping/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py similarity index 98% rename from dimos/mapping/scene_mesh_to_mjcf.py rename to dimos/simulation/mujoco/scene_mesh_to_mjcf.py index 8caa961451..4dc90706ee 100644 --- a/dimos/mapping/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -25,7 +25,7 @@ import numpy as np import open3d as o3d # type: ignore[import-untyped] -from dimos.mapping.mesh_scene import SceneMeshAlignment, load_scene_prims +from dimos.simulation.mujoco.mesh_scene import SceneMeshAlignment, load_scene_prims from dimos.utils.logging_config import setup_logger logger = setup_logger() @@ -304,7 +304,7 @@ def cli_main() -> None: args.remove("--view") if len(args) < 2: print( - "usage: python -m dimos.mapping.scene_mesh_to_mjcf [scale] [--view]" + "usage: python -m dimos.simulation.mujoco.scene_mesh_to_mjcf [scale] [--view]" ) sys.exit(2) scene = Path(args[0]) From c5f612bd9eda9293a060e932add2ae5fd52597ec Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Tue, 12 May 2026 23:57:48 -0700 Subject: [PATCH 13/30] fix(mujoco): address PR bot review items --- dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py | 2 +- dimos/simulation/mujoco/mesh_scene.py | 2 ++ dimos/simulation/mujoco/scene_mesh_to_mjcf.py | 8 ++++++-- 3 files changed, 9 insertions(+), 3 deletions(-) diff --git a/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py index a7f8d6974e..48adcd9b67 100644 --- a/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py +++ b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py @@ -61,7 +61,7 @@ def _env_xyz(name: str, default: tuple[float, float, float]) -> tuple[float, flo def _command_center_blueprints() -> list[Blueprint]: - if os.environ.get("DIMOS_ENABLE_COMMAND_CENTER", "1") in {"", "0"}: + if not _env_bool("DIMOS_ENABLE_COMMAND_CENTER", True): return [] try: from dimos.web.websocket_vis.websocket_vis_module import WebsocketVisModule diff --git a/dimos/simulation/mujoco/mesh_scene.py b/dimos/simulation/mujoco/mesh_scene.py index e5db224567..587f1f4c62 100644 --- a/dimos/simulation/mujoco/mesh_scene.py +++ b/dimos/simulation/mujoco/mesh_scene.py @@ -556,6 +556,8 @@ def load_scene_prims( __all__ = [ "SceneMeshAlignment", + "ScenePrimMesh", "load_scene_mesh", + "load_scene_prims", "make_raycasting_scene", ] diff --git a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py index 4dc90706ee..764dccabae 100644 --- a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -154,9 +154,13 @@ def _cache_key( alignment: SceneMeshAlignment, meshdir: Path, ) -> str: + def _file_signature(path: Path) -> str: + stat = path.stat() + return f"{path}:{stat.st_size}:{stat.st_mtime_ns}" + h = hashlib.sha256() - h.update(scene_mesh_path.read_bytes()) - h.update(robot_mjcf_path.read_bytes()) + h.update(_file_signature(scene_mesh_path).encode()) + h.update(_file_signature(robot_mjcf_path).encode()) h.update(repr(sorted(asdict(alignment).items())).encode()) h.update(str(meshdir).encode()) return h.hexdigest()[:_CACHE_KEY_LEN] From 63b43198601783e0ae23404454fc8cf856ec5ee2 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 00:15:34 -0700 Subject: [PATCH 14/30] fix(mujoco): clean up mesh typing --- dimos/simulation/mujoco/mesh_scene.py | 16 ++++++++-------- dimos/simulation/mujoco/scene_mesh_to_mjcf.py | 3 ++- 2 files changed, 10 insertions(+), 9 deletions(-) diff --git a/dimos/simulation/mujoco/mesh_scene.py b/dimos/simulation/mujoco/mesh_scene.py index 587f1f4c62..1d706944dd 100644 --- a/dimos/simulation/mujoco/mesh_scene.py +++ b/dimos/simulation/mujoco/mesh_scene.py @@ -33,7 +33,7 @@ from typing import Any import numpy as np -import open3d as o3d +import open3d as o3d # type: ignore[import-untyped] @dataclass @@ -101,7 +101,7 @@ def _color_from_displaycolor( isn't authored with a value (Sketchfab USDZ exports typically declare the primvar but leave it empty — colors live on the bound material). """ - from pxr import UsdGeom + from pxr import UsdGeom # type: ignore[import-untyped] pv = UsdGeom.PrimvarsAPI(mesh.GetPrim()).GetPrimvar("displayColor") if not pv or not pv.HasValue(): @@ -144,7 +144,7 @@ def _color_from_material( Results are cached per material path so we don't re-walk the shader graph for every prim that shares a material. """ - from pxr import UsdShade + from pxr import UsdShade # type: ignore[import-untyped] mat_api = UsdShade.MaterialBindingAPI(prim) bound = mat_api.ComputeBoundMaterial()[0] @@ -161,7 +161,7 @@ def _color_from_material( def _resolve_diffuse_color(material: Any) -> np.ndarray | None: """Pull a literal ``diffuseColor`` out of a UsdShade material's surface shader.""" - from pxr import UsdShade + from pxr import UsdShade # type: ignore[import-untyped] surface = material.ComputeSurfaceSource("")[0] if not surface: @@ -193,7 +193,7 @@ def _load_usd_mesh(path: Path) -> o3d.geometry.TriangleMesh: exports without having to chase materials/textures. """ try: - from pxr import Usd, UsdGeom + from pxr import Usd, UsdGeom # type: ignore[import-untyped] except ImportError as e: raise ImportError("loading .usdz/.usd requires usd-core: `uv pip install usd-core`") from e @@ -309,7 +309,7 @@ def load_scene_mesh( # single concatenated mesh — peak stays under ~1 GB. import trimesh - scene_or_mesh = trimesh.load(str(path)) + scene_or_mesh: Any = trimesh.load(str(path)) if isinstance(scene_or_mesh, trimesh.Trimesh): verts_world = np.asarray(scene_or_mesh.vertices, dtype=np.float64) faces_world = np.asarray(scene_or_mesh.faces, dtype=np.int64) @@ -402,7 +402,7 @@ def _load_glb_prims(path: Path, alignment: SceneMeshAlignment) -> list[ScenePrim """ import trimesh - loaded = trimesh.load(str(path)) + loaded: Any = trimesh.load(str(path)) R = _world_rotation(alignment) T = np.asarray(alignment.translation, dtype=np.float64) s = float(alignment.scale) @@ -487,7 +487,7 @@ def load_scene_prims( ] try: - from pxr import Usd, UsdGeom + from pxr import Usd, UsdGeom # type: ignore[import-untyped] except ImportError as e: raise ImportError("loading .usdz/.usd requires usd-core: `uv pip install usd-core`") from e diff --git a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py index 764dccabae..f9f2c68a2f 100644 --- a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -326,6 +326,7 @@ def cli_main() -> None: if view: import mujoco.viewer # type: ignore[import-untyped] + viewer: Any = mujoco.viewer # ``launch`` runs MuJoCo's interactive viewer with its own # internal physics loop. Blocks until the user closes it. @@ -334,7 +335,7 @@ def cli_main() -> None: # (group 3 = our scene collision hulls, group 1 = robot # visual mesh, group 0 = robot collision mesh). print("\nlaunching MuJoCo viewer (press Esc / close window to exit)") - mujoco.viewer.launch(model) + viewer.launch(model) if __name__ == "__main__": From d84c88ff69c90256e9470afc3f07b10a1c8925bd Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 00:32:50 -0700 Subject: [PATCH 15/30] fix(mujoco): skip flat scene collision hulls --- dimos/simulation/mujoco/scene_mesh_to_mjcf.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py index f9f2c68a2f..6d044b639e 100644 --- a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -57,6 +57,7 @@ _DEGENERATE_EPS = 1e-3 _SHELL_VOLUME_M3 = 2.0 _CACHE_KEY_LEN = 12 +_CACHE_SCHEMA_VERSION = "rank3-hulls-v1" _VHACD_MAX_HULLS = 64 _VHACD_RESOLUTION = 200_000 _MIN_HULL_ASPECT_RATIO = 0.05 @@ -159,6 +160,7 @@ def _file_signature(path: Path) -> str: return f"{path}:{stat.st_size}:{stat.st_mtime_ns}" h = hashlib.sha256() + h.update(_CACHE_SCHEMA_VERSION.encode()) h.update(_file_signature(scene_mesh_path).encode()) h.update(_file_signature(robot_mjcf_path).encode()) h.update(repr(sorted(asdict(alignment).items())).encode()) @@ -256,6 +258,9 @@ def _valid_hull(v: np.ndarray, f: np.ndarray) -> bool: return False if min_ext < _MIN_HULL_EXTENT_M: return False + centered = v.astype(np.float64) - v.astype(np.float64).mean(axis=0) + if np.linalg.matrix_rank(centered, tol=_DEGENERATE_EPS) < 3: + return False try: from scipy.spatial import ConvexHull, QhullError From 8fa39b466d22b30b20f3ac8a527f6628cca294d6 Mon Sep 17 00:00:00 2001 From: "autofix-ci[bot]" <114827586+autofix-ci[bot]@users.noreply.github.com> Date: Wed, 13 May 2026 07:44:50 +0000 Subject: [PATCH 16/30] [autofix.ci] apply automated fixes --- dimos/simulation/mujoco/scene_mesh_to_mjcf.py | 1 + 1 file changed, 1 insertion(+) diff --git a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py index 6d044b639e..60a25d1444 100644 --- a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -331,6 +331,7 @@ def cli_main() -> None: if view: import mujoco.viewer # type: ignore[import-untyped] + viewer: Any = mujoco.viewer # ``launch`` runs MuJoCo's interactive viewer with its own From 4ff02675f0bad86f1f4bc6099c497d38eba12065 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 01:57:10 -0700 Subject: [PATCH 17/30] fix(mujoco): improve scene collision baking --- .../g1/blueprints/basic/g1_groot_wbc.py | 4 +- dimos/simulation/engines/mujoco_engine.py | 18 ++++ dimos/simulation/engines/mujoco_sim_module.py | 3 + dimos/simulation/mujoco/scene_mesh_to_mjcf.py | 95 +++++++++++++++++-- 4 files changed, 110 insertions(+), 10 deletions(-) diff --git a/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py index 48adcd9b67..f0b194bb3f 100644 --- a/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py +++ b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py @@ -144,8 +144,9 @@ def _command_center_blueprints() -> list[Blueprint]: dof=_dof, camera_name=os.environ.get("DIMOS_MUJOCO_CAMERA", "head_color"), enable_color=False, - enable_depth=True, + enable_depth=_enable_depth_cloud, enable_pointcloud=(not _disable_lidar) or _enable_depth_cloud, + pointcloud_fps=_env_float("DIMOS_POINTCLOUD_FPS", 2.0), lidar_camera_names=( [] if _disable_lidar @@ -156,6 +157,7 @@ def _command_center_blueprints() -> list[Blueprint]: lidar_voxel_size=_env_float("DIMOS_LIDAR_VOXEL_SIZE", 0.05), enable_kinematic_base_control=os.environ.get("DIMOS_KINEMATIC_BASE_CONTROL", "1") not in {"", "0"}, + enable_kinematic_joint_hold=_env_bool("DIMOS_MUJOCO_KINEMATIC_JOINT_HOLD", True), ), MovementManager.blueprint(), VoxelGridMapper.blueprint( diff --git a/dimos/simulation/engines/mujoco_engine.py b/dimos/simulation/engines/mujoco_engine.py index 8644021e2b..2be77f7a65 100644 --- a/dimos/simulation/engines/mujoco_engine.py +++ b/dimos/simulation/engines/mujoco_engine.py @@ -458,6 +458,24 @@ def hold_current_position(self) -> None: for i, mapping in enumerate(self._joint_mappings): self._joint_position_targets[i] = self._current_position(mapping) + def enforce_position_targets(self) -> None: + """Pin modeled joints to their current position targets. + + This is a development stub for stacks that do not yet run a real + whole-body controller. It leaves the floating base alone, but prevents + contact impulses from folding the articulated joints. + """ + with self._lock: + for i, mapping in enumerate(self._joint_mappings): + target = self._joint_position_targets[i] + if mapping.qpos_adr is not None: + self._data.qpos[mapping.qpos_adr] = target + self._joint_positions[i] = target + if mapping.dof_adr is not None: + self._data.qvel[mapping.dof_adr] = 0.0 + self._joint_velocities[i] = 0.0 + mujoco.mj_forward(self._model, self._data) + @property def has_root_freejoint(self) -> bool: return self._root_free_qpos_adr is not None diff --git a/dimos/simulation/engines/mujoco_sim_module.py b/dimos/simulation/engines/mujoco_sim_module.py index 50c052f796..080ea2e1df 100644 --- a/dimos/simulation/engines/mujoco_sim_module.py +++ b/dimos/simulation/engines/mujoco_sim_module.py @@ -110,6 +110,7 @@ class MujocoSimModuleConfig(ModuleConfig, DepthCameraConfig): lidar_camera_height: int = 360 lidar_voxel_size: float = 0.05 enable_kinematic_base_control: bool = False + enable_kinematic_joint_hold: bool = False class MujocoSimModule( @@ -403,6 +404,8 @@ def _apply_cmd_vel(self, engine: MujocoEngine) -> None: def _after_step(self, engine: MujocoEngine) -> None: self._apply_cmd_vel(engine) + if self.config.enable_kinematic_joint_hold: + engine.enforce_position_targets() self._publish_state(engine) def _publish_state(self, engine: MujocoEngine) -> None: diff --git a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py index 60a25d1444..76c168dbf2 100644 --- a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -54,14 +54,20 @@ ' ' ) +_BOX_GEOM_LINE = ( + ' ' +) _DEGENERATE_EPS = 1e-3 _SHELL_VOLUME_M3 = 2.0 _CACHE_KEY_LEN = 12 -_CACHE_SCHEMA_VERSION = "rank3-hulls-v1" +_CACHE_SCHEMA_VERSION = "thin-box-fallback-v1" _VHACD_MAX_HULLS = 64 _VHACD_RESOLUTION = 200_000 -_MIN_HULL_ASPECT_RATIO = 0.05 _MIN_HULL_EXTENT_M = 5e-3 +_FALLBACK_BOX_THICKNESS_M = 0.03 +_MIN_FALLBACK_BOX_EXTENT_M = 0.25 +_MIN_FALLBACK_BOX_AREA_M2 = 0.05 @dataclass @@ -72,6 +78,7 @@ class _BakeArtifacts: skipped_degenerate: int n_hulls: int n_decomposed: int + n_box_fallbacks: int def bake_scene_mjcf( @@ -128,14 +135,15 @@ def bake_scene_mjcf( logger.info(f"bake_scene_mjcf: {len(prims)} prims to bake") artifacts = _bake_collision_hulls(prims, cache_dir) - if not artifacts.asset_lines: + if not artifacts.asset_lines and not artifacts.geom_lines: raise RuntimeError( "bake_scene_mjcf: every hull came out degenerate; nothing left to collide against" ) logger.info( f"bake_scene_mjcf: baked {artifacts.n_hulls} convex hulls from {len(prims)} prims " f"({artifacts.total_tris} tris total), VHACD-decomposed {artifacts.n_decomposed} " - f"shell prims, skipped {artifacts.skipped_degenerate} degenerate hulls" + f"shell prims, added {artifacts.n_box_fallbacks} thin box fallbacks, " + f"skipped {artifacts.skipped_degenerate} degenerate hulls" ) _write_wrapper( @@ -181,6 +189,7 @@ def _bake_collision_hulls(prims: list[Any], cache_dir: Path) -> _BakeArtifacts: skipped_degenerate = 0 n_hulls = 0 n_decomposed = 0 + n_box_fallbacks = 0 logger.info(f"bake_scene_mjcf: per-prim convex-hulling {len(prims)} prims (one-time)") for prim in prims: tm = trimesh.Trimesh( @@ -191,7 +200,16 @@ def _bake_collision_hulls(prims: list[Any], cache_dir: Path) -> _BakeArtifacts: try: single_hull = tm.convex_hull except Exception as e: - logger.warning(f" convex_hull failed for {prim.name}: {e}; skipping") + box_line = _fallback_box_geom(f"{prim.name}_box", prim.vertices) + if box_line is None: + logger.warning(f" convex_hull failed for {prim.name}: {e}; skipping") + skipped_degenerate += 1 + else: + logger.warning( + f" convex_hull failed for {prim.name}: {e}; using thin box fallback" + ) + geom_lines.append(box_line) + n_box_fallbacks += 1 continue hulls, decomposed = _collision_hulls(tm, single_hull, prim.name) @@ -202,7 +220,12 @@ def _bake_collision_hulls(prims: list[Any], cache_dir: Path) -> _BakeArtifacts: v = np.asarray(hull.vertices, dtype=np.float32) f = np.asarray(hull.faces, dtype=np.int32) if not _valid_hull(v, f): - skipped_degenerate += 1 + box_line = _fallback_box_geom(f"{prim.name}_h{j:03d}_box", v) + if box_line is None: + skipped_degenerate += 1 + else: + geom_lines.append(box_line) + n_box_fallbacks += 1 continue asset_name = f"{prim.name}_h{j:03d}" @@ -221,6 +244,7 @@ def _bake_collision_hulls(prims: list[Any], cache_dir: Path) -> _BakeArtifacts: skipped_degenerate=skipped_degenerate, n_hulls=n_hulls, n_decomposed=n_decomposed, + n_box_fallbacks=n_box_fallbacks, ) @@ -253,9 +277,6 @@ def _valid_hull(v: np.ndarray, f: np.ndarray) -> bool: if (extent < _DEGENERATE_EPS).any(): return False min_ext = float(extent.min()) - max_ext = float(extent.max()) - if max_ext > 0 and (min_ext / max_ext) < _MIN_HULL_ASPECT_RATIO: - return False if min_ext < _MIN_HULL_EXTENT_M: return False centered = v.astype(np.float64) - v.astype(np.float64).mean(axis=0) @@ -270,6 +291,62 @@ def _valid_hull(v: np.ndarray, f: np.ndarray) -> bool: return True +def _fallback_box_geom(name: str, vertices: np.ndarray) -> str | None: + finite = vertices[np.isfinite(vertices).all(axis=1)].astype(np.float64) + if len(finite) < 3: + return None + aabb_extent = finite.max(axis=0) - finite.min(axis=0) + sorted_extents = np.sort(aabb_extent) + if sorted_extents[-1] < _MIN_FALLBACK_BOX_EXTENT_M: + return None + if sorted_extents[-1] * sorted_extents[-2] < _MIN_FALLBACK_BOX_AREA_M2: + return None + + center, rotation, extent = _oriented_box(finite) + extent = np.maximum(extent, _FALLBACK_BOX_THICKNESS_M) + half_size = 0.5 * extent + quat = _rotation_matrix_to_wxyz(rotation) + return _BOX_GEOM_LINE.format( + name=name, + pos=_fmt_vec(center), + quat=_fmt_vec(quat), + size=_fmt_vec(half_size), + ) + + +def _oriented_box(vertices: np.ndarray) -> tuple[np.ndarray, np.ndarray, np.ndarray]: + try: + import trimesh + + tm = trimesh.Trimesh(vertices=vertices, faces=np.empty((0, 3), dtype=np.int32)) + obb = tm.bounding_box_oriented + transform = np.asarray(obb.primitive.transform, dtype=np.float64) + extent = np.asarray(obb.primitive.extents, dtype=np.float64) + rotation = transform[:3, :3] + center = transform[:3, 3] + if np.linalg.det(rotation) < 0: + rotation[:, 0] *= -1.0 + if np.isfinite(center).all() and np.isfinite(rotation).all() and np.isfinite(extent).all(): + return center, rotation, np.abs(extent) + except Exception: + pass + + lo = vertices.min(axis=0) + hi = vertices.max(axis=0) + return (lo + hi) * 0.5, np.eye(3), hi - lo + + +def _rotation_matrix_to_wxyz(rotation: np.ndarray) -> np.ndarray: + from scipy.spatial.transform import Rotation + + xyzw = Rotation.from_matrix(rotation).as_quat() + return np.array([xyzw[3], xyzw[0], xyzw[1], xyzw[2]], dtype=np.float64) + + +def _fmt_vec(values: np.ndarray) -> str: + return " ".join(f"{float(v):.9g}" for v in values) + + def _write_hull_obj(obj_file: Path, vertices: np.ndarray, faces: np.ndarray) -> None: o3d_mesh = o3d.geometry.TriangleMesh() o3d_mesh.vertices = o3d.utility.Vector3dVector(vertices.astype(np.float64)) From 233697701ff0e1ddd09e5c0fc47d3adf15a4cd62 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 02:06:40 -0700 Subject: [PATCH 18/30] fix(mujoco): route g1 teleop directly --- dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py index f0b194bb3f..343f1e6788 100644 --- a/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py +++ b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py @@ -33,7 +33,6 @@ from dimos.msgs.nav_msgs.Path import Path as PathMsg from dimos.msgs.sensor_msgs.JointState import JointState from dimos.msgs.sensor_msgs.PointCloud2 import PointCloud2 -from dimos.navigation.movement_manager.movement_manager import MovementManager from dimos.navigation.replanning_a_star.module import ReplanningAStarPlanner from dimos.simulation.engines.mujoco_sim_module import MujocoSimModule @@ -159,7 +158,6 @@ def _command_center_blueprints() -> list[Blueprint]: not in {"", "0"}, enable_kinematic_joint_hold=_env_bool("DIMOS_MUJOCO_KINEMATIC_JOINT_HOLD", True), ), - MovementManager.blueprint(), VoxelGridMapper.blueprint( voxel_size=_env_float("DIMOS_GLOBAL_MAP_VOXEL_SIZE", 0.05), ), @@ -170,8 +168,8 @@ def _command_center_blueprints() -> list[Blueprint]: { ("joint_state", JointState): LCMTransport("/mujoco/joint_state", JointState), ("odom", PoseStamped): LCMTransport("/odom", PoseStamped), - ("tele_cmd_vel", Twist): LCMTransport("/tele_cmd_vel", Twist), - ("nav_cmd_vel", Twist): LCMTransport("/nav_cmd_vel", Twist), + ("tele_cmd_vel", Twist): LCMTransport("/cmd_vel", Twist), + ("nav_cmd_vel", Twist): LCMTransport("/cmd_vel", Twist), ("cmd_vel", Twist): LCMTransport("/cmd_vel", Twist), ("pointcloud", PointCloud2): LCMTransport("/lidar", PointCloud2), ("lidar", PointCloud2): LCMTransport("/lidar", PointCloud2), From a2fb7a21c34c36db99687a01fa7feb50fa6fc720 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 03:21:28 -0700 Subject: [PATCH 19/30] fix(mujoco): support visual scene passthrough Add an opt-in visual mesh passthrough for scene meshes and make VHACD more willing to decompose low-prim, high-component scenes. Note: scenes with no well-defined object hierarchy can still produce spotty convex decomposition because the source mesh may be material-batched instead of object-batched. --- .../g1/blueprints/basic/g1_groot_wbc.py | 2 + dimos/simulation/mujoco/scene_mesh_to_mjcf.py | 87 +++++++++++++++++-- 2 files changed, 81 insertions(+), 8 deletions(-) diff --git a/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py index 343f1e6788..a4a8f1a932 100644 --- a/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py +++ b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py @@ -102,6 +102,7 @@ def _command_center_blueprints() -> list[Blueprint]: _scene_mesh_rotation = _env_xyz("DIMOS_SCENE_MESH_ROTATION_ZYX_DEG", (0.0, 0.0, 0.0)) _scene_mesh_translation = _env_xyz("DIMOS_SCENE_MESH_TRANSLATION", (0.0, 0.0, 0.0)) _scene_mesh_collision = os.environ.get("DIMOS_SCENE_MESH_COLLISION", "1") not in {"", "0"} +_scene_mesh_visual = _env_bool("DIMOS_SCENE_MESH_VISUAL", False) _enable_depth_cloud = os.environ.get("DIMOS_ENABLE_DEPTH_CLOUD", "0").lower() in { "1", "true", @@ -127,6 +128,7 @@ def _command_center_blueprints() -> list[Blueprint]: y_up=_scene_mesh_y_up, ), meshdir=_mjcf_meshdir, + include_visual_mesh=_scene_mesh_visual, ) ) except Exception as exc: diff --git a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py index 76c168dbf2..c8bd55fedc 100644 --- a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -54,6 +54,10 @@ ' ' ) +_VISUAL_GEOM_LINE = ( + ' ' +) _BOX_GEOM_LINE = ( ' ' @@ -61,9 +65,11 @@ _DEGENERATE_EPS = 1e-3 _SHELL_VOLUME_M3 = 2.0 _CACHE_KEY_LEN = 12 -_CACHE_SCHEMA_VERSION = "thin-box-fallback-v1" +_CACHE_SCHEMA_VERSION = "visual-proxy-v1" _VHACD_MAX_HULLS = 64 _VHACD_RESOLUTION = 200_000 +_VHACD_MIN_COMPONENTS = 512 +_COMPONENT_VHACD_MAX_SCENE_PRIMS = 256 _MIN_HULL_EXTENT_M = 5e-3 _FALLBACK_BOX_THICKNESS_M = 0.03 _MIN_FALLBACK_BOX_EXTENT_M = 0.25 @@ -79,6 +85,7 @@ class _BakeArtifacts: n_hulls: int n_decomposed: int n_box_fallbacks: int + n_visuals: int def bake_scene_mjcf( @@ -87,6 +94,7 @@ def bake_scene_mjcf( alignment: SceneMeshAlignment | None = None, meshdir: str | Path | None = None, cache_root: Path | None = None, + include_visual_mesh: bool = False, ) -> Path: """Convert ``scene_mesh_path`` to OBJ and emit a wrapped MJCF. @@ -103,6 +111,9 @@ def bake_scene_mjcf( should pass this explicitly. cache_root: override for the cache directory (defaults to ``~/.cache/dimos/scene_meshes``). + include_visual_mesh: also add the original scene prim meshes as + non-colliding visual geoms. Useful for material-batched scenes + where convex collision proxies are too coarse to inspect. Returns: Path to the wrapper MJCF. Pass this to ``MujocoSimModule`` @@ -119,7 +130,13 @@ def bake_scene_mjcf( meshdir = Path(meshdir).expanduser().resolve() if meshdir else robot_mjcf_path.parent - cache_key = _cache_key(scene_mesh_path, robot_mjcf_path, align, meshdir) + cache_key = _cache_key( + scene_mesh_path, + robot_mjcf_path, + align, + meshdir, + include_visual_mesh=include_visual_mesh, + ) root = (cache_root or CACHE_DIR).expanduser() cache_dir = root / cache_key wrapper_path = cache_dir / "wrapper.xml" @@ -134,7 +151,11 @@ def bake_scene_mjcf( prims = load_scene_prims(scene_mesh_path, alignment=align) logger.info(f"bake_scene_mjcf: {len(prims)} prims to bake") - artifacts = _bake_collision_hulls(prims, cache_dir) + artifacts = _bake_collision_hulls( + prims, + cache_dir, + include_visual_mesh=include_visual_mesh, + ) if not artifacts.asset_lines and not artifacts.geom_lines: raise RuntimeError( "bake_scene_mjcf: every hull came out degenerate; nothing left to collide against" @@ -143,6 +164,7 @@ def bake_scene_mjcf( f"bake_scene_mjcf: baked {artifacts.n_hulls} convex hulls from {len(prims)} prims " f"({artifacts.total_tris} tris total), VHACD-decomposed {artifacts.n_decomposed} " f"shell prims, added {artifacts.n_box_fallbacks} thin box fallbacks, " + f"added {artifacts.n_visuals} visual passthrough meshes, " f"skipped {artifacts.skipped_degenerate} degenerate hulls" ) @@ -162,6 +184,8 @@ def _cache_key( robot_mjcf_path: Path, alignment: SceneMeshAlignment, meshdir: Path, + *, + include_visual_mesh: bool, ) -> str: def _file_signature(path: Path) -> str: stat = path.stat() @@ -173,6 +197,7 @@ def _file_signature(path: Path) -> str: h.update(_file_signature(robot_mjcf_path).encode()) h.update(repr(sorted(asdict(alignment).items())).encode()) h.update(str(meshdir).encode()) + h.update(str(include_visual_mesh).encode()) return h.hexdigest()[:_CACHE_KEY_LEN] @@ -180,7 +205,12 @@ def _cache_hit(wrapper_path: Path, cache_dir: Path) -> bool: return wrapper_path.exists() and any(cache_dir.glob("*.obj")) -def _bake_collision_hulls(prims: list[Any], cache_dir: Path) -> _BakeArtifacts: +def _bake_collision_hulls( + prims: list[Any], + cache_dir: Path, + *, + include_visual_mesh: bool = False, +) -> _BakeArtifacts: import trimesh asset_lines: list[str] = [] @@ -190,8 +220,20 @@ def _bake_collision_hulls(prims: list[Any], cache_dir: Path) -> _BakeArtifacts: n_hulls = 0 n_decomposed = 0 n_box_fallbacks = 0 + n_visuals = 0 + component_vhacd = len(prims) <= _COMPONENT_VHACD_MAX_SCENE_PRIMS logger.info(f"bake_scene_mjcf: per-prim convex-hulling {len(prims)} prims (one-time)") for prim in prims: + if include_visual_mesh: + asset_name = f"{prim.name}_visual" + obj_file = cache_dir / f"{asset_name}.obj" + _write_mesh_obj(obj_file, prim.vertices, prim.triangles) + asset_lines.append(_ASSET_LINE.format(name=asset_name, file=str(obj_file))) + geom_lines.append( + _VISUAL_GEOM_LINE.format(name=f"{asset_name}_geom", mesh=asset_name) + ) + n_visuals += 1 + tm = trimesh.Trimesh( vertices=prim.vertices.astype(np.float64), faces=prim.triangles, @@ -212,7 +254,12 @@ def _bake_collision_hulls(prims: list[Any], cache_dir: Path) -> _BakeArtifacts: n_box_fallbacks += 1 continue - hulls, decomposed = _collision_hulls(tm, single_hull, prim.name) + hulls, decomposed = _collision_hulls( + tm, + single_hull, + prim.name, + component_vhacd=component_vhacd, + ) if decomposed: n_decomposed += 1 @@ -245,11 +292,23 @@ def _bake_collision_hulls(prims: list[Any], cache_dir: Path) -> _BakeArtifacts: n_hulls=n_hulls, n_decomposed=n_decomposed, n_box_fallbacks=n_box_fallbacks, + n_visuals=n_visuals, ) -def _collision_hulls(tm: Any, single_hull: Any, prim_name: str) -> tuple[list[Any], bool]: - if float(single_hull.volume) <= _SHELL_VOLUME_M3: +def _collision_hulls( + tm: Any, + single_hull: Any, + prim_name: str, + *, + component_vhacd: bool, +) -> tuple[list[Any], bool]: + hull_volume = float(single_hull.volume) + component_count = _body_count(tm) + should_decompose = hull_volume > _SHELL_VOLUME_M3 or ( + component_vhacd and component_count >= _VHACD_MIN_COMPONENTS + ) + if not should_decompose: return [single_hull], False try: parts = tm.convex_decomposition( @@ -259,7 +318,8 @@ def _collision_hulls(tm: Any, single_hull: Any, prim_name: str) -> tuple[list[An hulls = parts if isinstance(parts, list) else [parts] logger.info( f" {prim_name}: VHACD decomposed " - f"({single_hull.volume:.1f} m³ shell -> {len(hulls)} sub-hulls)" + f"({hull_volume:.3g} m³ shell, {component_count} components -> " + f"{len(hulls)} sub-hulls)" ) return hulls, True except Exception as e: @@ -270,6 +330,13 @@ def _collision_hulls(tm: Any, single_hull: Any, prim_name: str) -> tuple[list[An return [single_hull], False +def _body_count(tm: Any) -> int: + try: + return int(tm.body_count) + except Exception: + return 1 + + def _valid_hull(v: np.ndarray, f: np.ndarray) -> bool: if len(v) < 4 or len(f) < 4: return False @@ -348,6 +415,10 @@ def _fmt_vec(values: np.ndarray) -> str: def _write_hull_obj(obj_file: Path, vertices: np.ndarray, faces: np.ndarray) -> None: + _write_mesh_obj(obj_file, vertices, faces) + + +def _write_mesh_obj(obj_file: Path, vertices: np.ndarray, faces: np.ndarray) -> None: o3d_mesh = o3d.geometry.TriangleMesh() o3d_mesh.vertices = o3d.utility.Vector3dVector(vertices.astype(np.float64)) o3d_mesh.triangles = o3d.utility.Vector3iVector(faces) From d9ea1ac9d344fe2daadc03514a875e2d1a899369 Mon Sep 17 00:00:00 2001 From: "autofix-ci[bot]" <114827586+autofix-ci[bot]@users.noreply.github.com> Date: Wed, 13 May 2026 10:25:44 +0000 Subject: [PATCH 20/30] [autofix.ci] apply automated fixes --- dimos/simulation/mujoco/scene_mesh_to_mjcf.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py index c8bd55fedc..96e05084d0 100644 --- a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -229,9 +229,7 @@ def _bake_collision_hulls( obj_file = cache_dir / f"{asset_name}.obj" _write_mesh_obj(obj_file, prim.vertices, prim.triangles) asset_lines.append(_ASSET_LINE.format(name=asset_name, file=str(obj_file))) - geom_lines.append( - _VISUAL_GEOM_LINE.format(name=f"{asset_name}_geom", mesh=asset_name) - ) + geom_lines.append(_VISUAL_GEOM_LINE.format(name=f"{asset_name}_geom", mesh=asset_name)) n_visuals += 1 tm = trimesh.Trimesh( From 7392de2a85d5e76b23313c74609baf358fe24e3e Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 17:02:27 -0700 Subject: [PATCH 21/30] fix(mujoco): address review feedback --- .../g1/blueprints/basic/g1_groot_wbc.py | 22 +++++-------------- dimos/simulation/engines/mujoco_engine.py | 3 ++- dimos/simulation/engines/mujoco_sim_module.py | 3 ++- dimos/simulation/mujoco/scene_mesh_to_mjcf.py | 6 ++--- pyproject.toml | 4 ++++ 5 files changed, 16 insertions(+), 22 deletions(-) diff --git a/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py index a4a8f1a932..768448d2dc 100644 --- a/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py +++ b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py @@ -92,24 +92,13 @@ def _command_center_blueprints() -> list[Blueprint]: "DIMOS_SCENE_MESH_SCALE", 0.05 if _scene_mesh_path_override else 2.0, ) -_scene_mesh_y_up = ( - os.environ.get( - "DIMOS_SCENE_MESH_Y_UP", - "1" if _scene_mesh_path_override else "0", - ) - != "0" -) +_scene_mesh_y_up = _env_bool("DIMOS_SCENE_MESH_Y_UP", bool(_scene_mesh_path_override)) _scene_mesh_rotation = _env_xyz("DIMOS_SCENE_MESH_ROTATION_ZYX_DEG", (0.0, 0.0, 0.0)) _scene_mesh_translation = _env_xyz("DIMOS_SCENE_MESH_TRANSLATION", (0.0, 0.0, 0.0)) -_scene_mesh_collision = os.environ.get("DIMOS_SCENE_MESH_COLLISION", "1") not in {"", "0"} +_scene_mesh_collision = _env_bool("DIMOS_SCENE_MESH_COLLISION", True) _scene_mesh_visual = _env_bool("DIMOS_SCENE_MESH_VISUAL", False) -_enable_depth_cloud = os.environ.get("DIMOS_ENABLE_DEPTH_CLOUD", "0").lower() in { - "1", - "true", - "yes", - "on", -} -_disable_lidar = os.environ.get("DIMOS_DISABLE_LIDAR", "0") not in {"", "0"} +_enable_depth_cloud = _env_bool("DIMOS_ENABLE_DEPTH_CLOUD", False) +_disable_lidar = _env_bool("DIMOS_DISABLE_LIDAR", False) _sim_mjcf_path = _mjcf_path if _scene_mesh_path and _scene_mesh_collision: @@ -156,8 +145,7 @@ def _command_center_blueprints() -> list[Blueprint]: lidar_camera_width=int(os.environ.get("DIMOS_LIDAR_CAMERA_WIDTH", "640")), lidar_camera_height=int(os.environ.get("DIMOS_LIDAR_CAMERA_HEIGHT", "360")), lidar_voxel_size=_env_float("DIMOS_LIDAR_VOXEL_SIZE", 0.05), - enable_kinematic_base_control=os.environ.get("DIMOS_KINEMATIC_BASE_CONTROL", "1") - not in {"", "0"}, + enable_kinematic_base_control=_env_bool("DIMOS_KINEMATIC_BASE_CONTROL", True), enable_kinematic_joint_hold=_env_bool("DIMOS_MUJOCO_KINEMATIC_JOINT_HOLD", True), ), VoxelGridMapper.blueprint( diff --git a/dimos/simulation/engines/mujoco_engine.py b/dimos/simulation/engines/mujoco_engine.py index 2be77f7a65..f94f877819 100644 --- a/dimos/simulation/engines/mujoco_engine.py +++ b/dimos/simulation/engines/mujoco_engine.py @@ -107,8 +107,9 @@ def __init__( self._control_frequency = 1.0 / timestep if timestep > 0.0 else 100.0 self._root_free_qpos_adr: int | None = None self._root_free_qvel_adr: int | None = None + free_joint = int(mujoco.mjtJoint.mjJNT_FREE) # type: ignore[attr-defined] for joint_id in range(self._model.njnt): - if self._model.jnt_type[joint_id] == mujoco.mjtJoint.mjJNT_FREE: + if self._model.jnt_type[joint_id] == free_joint: self._root_free_qpos_adr = int(self._model.jnt_qposadr[joint_id]) self._root_free_qvel_adr = int(self._model.jnt_dofadr[joint_id]) break diff --git a/dimos/simulation/engines/mujoco_sim_module.py b/dimos/simulation/engines/mujoco_sim_module.py index 080ea2e1df..37b0f99be8 100644 --- a/dimos/simulation/engines/mujoco_sim_module.py +++ b/dimos/simulation/engines/mujoco_sim_module.py @@ -254,8 +254,9 @@ def _make_camera_configs(self) -> list[CameraConfig]: ) lidar_scene_option = mujoco.MjvOption() + geomgroup = lidar_scene_option.geomgroup # type: ignore[attr-defined] for group_id, enabled in enumerate(_LIDAR_GEOM_GROUPS): - lidar_scene_option.geomgroup[group_id] = enabled + geomgroup[group_id] = enabled for lidar_name in self.config.lidar_camera_names: if lidar_name == self.config.camera_name and self._primary_camera_needed: continue diff --git a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py index 96e05084d0..25ceb64c86 100644 --- a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -141,7 +141,7 @@ def bake_scene_mjcf( cache_dir = root / cache_key wrapper_path = cache_dir / "wrapper.xml" - if _cache_hit(wrapper_path, cache_dir): + if _cache_hit(wrapper_path): logger.info(f"bake_scene_mjcf: cache hit at {cache_dir}") return wrapper_path @@ -201,8 +201,8 @@ def _file_signature(path: Path) -> str: return h.hexdigest()[:_CACHE_KEY_LEN] -def _cache_hit(wrapper_path: Path, cache_dir: Path) -> bool: - return wrapper_path.exists() and any(cache_dir.glob("*.obj")) +def _cache_hit(wrapper_path: Path) -> bool: + return wrapper_path.exists() def _bake_collision_hulls( diff --git a/pyproject.toml b/pyproject.toml index e2035c9de7..fe9ebbbe18 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -490,6 +490,8 @@ module = [ "mujoco_playground.*", "nav_msgs.*", "open_clip", + "open3d", + "open3d.*", "pinocchio", "piper_sdk.*", "plotext", @@ -504,6 +506,8 @@ module = [ "pydrake.*", "pyzed", "pyzed.*", + "pxr", + "pxr.*", "rclpy.*", "sam2.*", "scipy", From 011a08af5c142d0beb0c22724aaf01c6fb54a9c9 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 17:26:28 -0700 Subject: [PATCH 22/30] fix(mujoco): localize optional import ignores --- dimos/simulation/engines/mujoco_sim_module.py | 2 +- dimos/simulation/mujoco/mesh_scene.py | 10 +++++----- pyproject.toml | 4 ---- 3 files changed, 6 insertions(+), 10 deletions(-) diff --git a/dimos/simulation/engines/mujoco_sim_module.py b/dimos/simulation/engines/mujoco_sim_module.py index 37b0f99be8..57450f3cc1 100644 --- a/dimos/simulation/engines/mujoco_sim_module.py +++ b/dimos/simulation/engines/mujoco_sim_module.py @@ -34,7 +34,7 @@ import mujoco import numpy as np -import open3d as o3d +import open3d as o3d # type: ignore[import-untyped] from pydantic import Field import reactivex as rx from reactivex.disposable import Disposable diff --git a/dimos/simulation/mujoco/mesh_scene.py b/dimos/simulation/mujoco/mesh_scene.py index 1d706944dd..dc15adff68 100644 --- a/dimos/simulation/mujoco/mesh_scene.py +++ b/dimos/simulation/mujoco/mesh_scene.py @@ -101,7 +101,7 @@ def _color_from_displaycolor( isn't authored with a value (Sketchfab USDZ exports typically declare the primvar but leave it empty — colors live on the bound material). """ - from pxr import UsdGeom # type: ignore[import-untyped] + from pxr import UsdGeom # type: ignore[import-not-found, import-untyped] pv = UsdGeom.PrimvarsAPI(mesh.GetPrim()).GetPrimvar("displayColor") if not pv or not pv.HasValue(): @@ -144,7 +144,7 @@ def _color_from_material( Results are cached per material path so we don't re-walk the shader graph for every prim that shares a material. """ - from pxr import UsdShade # type: ignore[import-untyped] + from pxr import UsdShade # type: ignore[import-not-found, import-untyped] mat_api = UsdShade.MaterialBindingAPI(prim) bound = mat_api.ComputeBoundMaterial()[0] @@ -161,7 +161,7 @@ def _color_from_material( def _resolve_diffuse_color(material: Any) -> np.ndarray | None: """Pull a literal ``diffuseColor`` out of a UsdShade material's surface shader.""" - from pxr import UsdShade # type: ignore[import-untyped] + from pxr import UsdShade # type: ignore[import-not-found, import-untyped] surface = material.ComputeSurfaceSource("")[0] if not surface: @@ -193,7 +193,7 @@ def _load_usd_mesh(path: Path) -> o3d.geometry.TriangleMesh: exports without having to chase materials/textures. """ try: - from pxr import Usd, UsdGeom # type: ignore[import-untyped] + from pxr import Usd, UsdGeom # type: ignore[import-not-found, import-untyped] except ImportError as e: raise ImportError("loading .usdz/.usd requires usd-core: `uv pip install usd-core`") from e @@ -487,7 +487,7 @@ def load_scene_prims( ] try: - from pxr import Usd, UsdGeom # type: ignore[import-untyped] + from pxr import Usd, UsdGeom # type: ignore[import-not-found, import-untyped] except ImportError as e: raise ImportError("loading .usdz/.usd requires usd-core: `uv pip install usd-core`") from e diff --git a/pyproject.toml b/pyproject.toml index fe9ebbbe18..e2035c9de7 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -490,8 +490,6 @@ module = [ "mujoco_playground.*", "nav_msgs.*", "open_clip", - "open3d", - "open3d.*", "pinocchio", "piper_sdk.*", "plotext", @@ -506,8 +504,6 @@ module = [ "pydrake.*", "pyzed", "pyzed.*", - "pxr", - "pxr.*", "rclpy.*", "sam2.*", "scipy", From ab88915a6ddc1096d4c5c63b1dd584c9d9fd1ffe Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 18:36:35 -0700 Subject: [PATCH 23/30] fix(mujoco): include vhacdx in sim extra --- pyproject.toml | 1 + uv.lock | 57 ++++++++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 58 insertions(+) diff --git a/pyproject.toml b/pyproject.toml index e2035c9de7..1bd2a78e1a 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -256,6 +256,7 @@ sim = [ "pygame>=2.6.1", "trimesh", "usd-core>=24.0", + "vhacdx", ] navigation = [ diff --git a/uv.lock b/uv.lock index 24c3db1a90..4e53de9e5b 100644 --- a/uv.lock +++ b/uv.lock @@ -1981,6 +1981,7 @@ all = [ { name = "unitree-webrtc-connect-leshy" }, { name = "usd-core" }, { name = "uvicorn" }, + { name = "vhacdx" }, { name = "xacro" }, { name = "xarm-python-sdk" }, { name = "xformers", marker = "platform_machine == 'x86_64'" }, @@ -2113,6 +2114,7 @@ sim = [ { name = "pygame" }, { name = "trimesh" }, { name = "usd-core" }, + { name = "vhacdx" }, ] unitree = [ { name = "anthropic" }, @@ -2461,6 +2463,7 @@ requires-dist = [ { name = "unitree-webrtc-connect-leshy", marker = "extra == 'unitree'", specifier = ">=2.0.7" }, { name = "usd-core", marker = "extra == 'sim'", specifier = ">=24.0" }, { name = "uvicorn", marker = "extra == 'web'", specifier = ">=0.34.0" }, + { name = "vhacdx", marker = "extra == 'sim'" }, { name = "xacro", marker = "extra == 'manipulation'" }, { name = "xarm-python-sdk", marker = "extra == 'manipulation'", specifier = ">=1.17.0" }, { name = "xarm-python-sdk", marker = "extra == 'misc'", specifier = ">=1.17.0" }, @@ -11132,6 +11135,60 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/e4/16/c1fd27e9549f3c4baf1dc9c20c456cd2f822dbf8de9f463824b0c0357e06/uvloop-0.22.1-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:6cde23eeda1a25c75b2e07d39970f3374105d5eafbaab2a4482be82f272d5a5e", size = 4296730, upload-time = "2025-10-16T22:17:00.744Z" }, ] +[[package]] +name = "vhacdx" +version = "0.0.10" +source = { registry = "https://pypi.org/simple" } +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'" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/15/e3/d2abc3dc4c1cb216c2efdc70b36f80efeb1bdbd7d420a676ddc9d9d980e1/vhacdx-0.0.10.tar.gz", hash = "sha256:fcc23201e319d79fe25e064847efc254bd39ac30af28cc761409e1f9142dd033", size = 58125, upload-time = "2025-12-02T20:58:45.358Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/c4/f4/da308d86daaa9c636851357cbd928715d47963beecd525b3749d2d5c9537/vhacdx-0.0.10-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:4bc7be82fab608cb7231e95a0a10700be1e9422a36b21e7d49c782a598c8d37c", size = 222760, upload-time = "2025-12-02T20:57:30.778Z" }, + { url = "https://files.pythonhosted.org/packages/e0/8a/e3462a43ec6712b74d921e4af9d5a2998752378c5554bde9a594dbb0cf0c/vhacdx-0.0.10-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:4b63d1c5ad0e64c300a3a9d9404f4778df367b8c545639dfb932db4b76704ff3", size = 208812, upload-time = "2025-12-02T20:57:33.486Z" }, + { url = "https://files.pythonhosted.org/packages/fb/d1/b717275adb108431f1404193542fab7ecf4c5bae221f1552bbd570fe0e5d/vhacdx-0.0.10-cp310-cp310-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f9bcf3fe1c555598e41348108b55a0fc67534e7fef2367452c301014518c1476", size = 236999, upload-time = "2025-12-02T20:57:34.971Z" }, + { url = "https://files.pythonhosted.org/packages/bf/84/97e2305f6bd4a4de3d40bb234c38282cbcf2fa30653ff5ae4f7df9d8f3ec/vhacdx-0.0.10-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9506ca89289da63e5a3d1ac97aa7413aece47d65cbaa4b0c409469555add0e06", size = 250035, upload-time = "2025-12-02T20:57:36.037Z" }, + { url = "https://files.pythonhosted.org/packages/9d/66/eb1d8d64742b9e73557e075cea6ee7e4976dd89b84c7d3197ca3621d5a85/vhacdx-0.0.10-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:06faf9caa0abceddd5fa505e4299e2ebf14bc26c58a1e521013717cbf37bea61", size = 1224134, upload-time = "2025-12-02T20:57:37.217Z" }, + { url = "https://files.pythonhosted.org/packages/47/db/e829b21b071db94f45079c4ace2f967c684f08b10ea285919a95e9d5fe21/vhacdx-0.0.10-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:3a6b43b42290697e2bd04087977d1e3841d287c528e414c765581ecec62e66f6", size = 1284300, upload-time = "2025-12-02T20:57:38.78Z" }, + { url = "https://files.pythonhosted.org/packages/ff/aa/b401565542b927ce3e0a6d5e72acef79343a449ee1a7ad94a5c7266bab26/vhacdx-0.0.10-cp310-cp310-win_amd64.whl", hash = "sha256:27eb3b293ccef1332d477346d564bb4c474bb451e9b753e3ce9cac01cbb90a0c", size = 193069, upload-time = "2025-12-02T20:57:40.318Z" }, + { url = "https://files.pythonhosted.org/packages/b7/2c/d49df6fec3294cef3c8c88c54784162bd8350c427fecd9b16335772b760f/vhacdx-0.0.10-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:8584f33ed020b6cce678b8febcf84af22bced617ef31c85bf31fd7e2b4bba9fe", size = 224113, upload-time = "2025-12-02T20:57:41.59Z" }, + { url = "https://files.pythonhosted.org/packages/68/1d/bd2456baa6b16977c106adc2386b6e7a34c3e57ade6aeeab68bb61ceb16f/vhacdx-0.0.10-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:a9b63cdb5f34dfee386b64a01f7e1571ef0c2555244ea3d83a09d78273123bce", size = 210118, upload-time = "2025-12-02T20:57:42.749Z" }, + { url = "https://files.pythonhosted.org/packages/49/ab/15adb78489b51c2a898642755be727ecd7c3de37cac6e434ce420b8ce27c/vhacdx-0.0.10-cp311-cp311-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:915eab6c19fdf63ab256855331db546575284786a480aa2d67437db0e86b0d17", size = 238276, upload-time = "2025-12-02T20:57:43.95Z" }, + { url = "https://files.pythonhosted.org/packages/a6/f1/464c761dbe24f58d6fc354bf51729342981fb7a621e170e0d3512fadbec8/vhacdx-0.0.10-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6e335bb9af540e6867ff051166a399075823fdd8fc1fc27e9530995cc1bda1eb", size = 251383, upload-time = "2025-12-02T20:57:45.246Z" }, + { url = "https://files.pythonhosted.org/packages/b2/22/c7b4117c5431189a6a019e8fc2cf590df3ab196c38b4b7c3622292205d9b/vhacdx-0.0.10-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:c3ddbaa38eb65c3aec9b0e39a822223474c931c0e18d3e93a3a499870ffa45ad", size = 1225200, upload-time = "2025-12-02T20:57:46.639Z" }, + { url = "https://files.pythonhosted.org/packages/6c/62/c679ad28ce7854771913255e1abc588b3643c2147fb5c51a8553224aa1dd/vhacdx-0.0.10-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:d398fcc13e330ed1fd2540a7d572aeca0be9621411def78e10c7ea4132f959ee", size = 1285935, upload-time = "2025-12-02T20:57:48.51Z" }, + { url = "https://files.pythonhosted.org/packages/de/c8/a8260b780e4578d7ef19b70343f9717f74ff48f9950138c96c78f209ec01/vhacdx-0.0.10-cp311-cp311-win_amd64.whl", hash = "sha256:c9665a3ef887babcac8b5822f01288e8f06b4a949fadbbe1861670b358f111ee", size = 194137, upload-time = "2025-12-02T20:57:50.207Z" }, + { url = "https://files.pythonhosted.org/packages/cf/9c/66375e65634c80f6efb46e81915126bf3e55dc9d6615217590cbc8316d2e/vhacdx-0.0.10-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:7dd17d697d6d4d7cf66f1e947e0530041913981e05f7025236bec28a350b1a33", size = 224998, upload-time = "2025-12-02T20:57:51.639Z" }, + { url = "https://files.pythonhosted.org/packages/4e/e3/fc2644d3e7d0b2b52e2f681eb2878c0e1b9cafc53946f66736d0f01e237c/vhacdx-0.0.10-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:189ded39b709436cb732cdf694d4cf22e877aefb97e2ab2b55bf7ada9c030f93", size = 211130, upload-time = "2025-12-02T20:57:53.018Z" }, + { url = "https://files.pythonhosted.org/packages/e3/93/0b0f1977f5b3c2e1bbea5ef85e37a808ff73f1b7daf42950c57090e90dc7/vhacdx-0.0.10-cp312-cp312-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f3b03d35ab56a93beee338175dbe0b87552353e5dfb3ff37467e88f56cedf7cc", size = 239661, upload-time = "2025-12-02T20:57:54.144Z" }, + { url = "https://files.pythonhosted.org/packages/94/98/d2a6aeb1c6570a1fc1be29ee03db795f643ab03c6df7635522f23796b39d/vhacdx-0.0.10-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:ea8c54ed193fa0db0248928fbf5d438b3872d615a506889d5b89fc6467d6411a", size = 252938, upload-time = "2025-12-02T20:57:55.275Z" }, + { url = "https://files.pythonhosted.org/packages/94/2e/1e678efc161a0d7fe1806f5e037ce11cc5964db7e08ccfc220ef63951863/vhacdx-0.0.10-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:a5c898104140c72e4dc789e6125812671eee5e412916e83eff24a6148248ff5e", size = 1226696, upload-time = "2025-12-02T20:57:56.438Z" }, + { url = "https://files.pythonhosted.org/packages/90/5b/b302a0420a241c4910f4870eb9f39e6ada59858db441cc35bda511c17982/vhacdx-0.0.10-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:abdd0ba17786e578206594731df15c90e2751b6884220c8673124f47fd7ac620", size = 1287794, upload-time = "2025-12-02T20:57:57.694Z" }, + { url = "https://files.pythonhosted.org/packages/73/e9/f9729603ac75047a257f1b4ddac60cbde72b0abfd49ffed305751ba630a2/vhacdx-0.0.10-cp312-cp312-win_amd64.whl", hash = "sha256:79e7db59b4042295b21b79d55ba486a9a480550f696d466f158a30ed920dd0ec", size = 195033, upload-time = "2025-12-02T20:57:58.95Z" }, + { url = "https://files.pythonhosted.org/packages/0e/54/c2fc08d9324bbd92735caf9207cbabada3a8dd9d270d6e46ca69eb7f883d/vhacdx-0.0.10-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:0599bc2a96de8fc9aeff460b3e88b8572e84ae95b8fc6c9888ef4b92023c22d5", size = 225014, upload-time = "2025-12-02T20:58:00.938Z" }, + { url = "https://files.pythonhosted.org/packages/3b/9e/42adb642a12915acc9cb2bfab21710a6aabf045c26967ba0ff0e08a872d0/vhacdx-0.0.10-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:dc648829a1e973f34ee11393a4f334ab55e3e0e9c4b9f6d6349af966fdf1895a", size = 211127, upload-time = "2025-12-02T20:58:02.107Z" }, + { url = "https://files.pythonhosted.org/packages/51/3d/63e090cd966817b89643d7e52e13df45043b22a42c7fbf702866bdd75bc0/vhacdx-0.0.10-cp313-cp313-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:74c03f7315a434ec83cd0bff1e6bce6af4c01df61d677f48f3ffb36800606ee7", size = 239471, upload-time = "2025-12-02T20:58:03.173Z" }, + { url = "https://files.pythonhosted.org/packages/b8/b4/07ab1c828bae0eb5c72cd9a4cbe8b0376d374509be3c7055e1a399bf85c3/vhacdx-0.0.10-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:1fcd02acc3733ec3a0a0d28ca7f526d4c56f14a3ceb4b12fce45acf72c09054a", size = 253019, upload-time = "2025-12-02T20:58:04.318Z" }, + { url = "https://files.pythonhosted.org/packages/05/cb/bc8a8858b300d2c092da11096ae0586ece446b4c41cb26620bf00d1d8232/vhacdx-0.0.10-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:4b9f8a80ca4c54d7fa76419a2ebd9e9386cd177dc4d2b97f2208ac57c9a7e8aa", size = 1226933, upload-time = "2025-12-02T20:58:05.907Z" }, + { url = "https://files.pythonhosted.org/packages/15/52/213230883874615f1661903bce1ace5013d03b34696efce8d53c662a3358/vhacdx-0.0.10-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:847bd43e82afb439dd3fa972618d786d0b98d8ef04a8e8a6381f6945204d2505", size = 1288871, upload-time = "2025-12-02T20:58:07.432Z" }, + { url = "https://files.pythonhosted.org/packages/32/25/f0e6806824f88d47ab8bc1c9bf6f11634fd7b382d635d0696825f3b5672f/vhacdx-0.0.10-cp313-cp313-win_amd64.whl", hash = "sha256:ab300c5f3fe4e54f99af92f9ea27c977b09df5f59190b0a3e025161110f71ce7", size = 195091, upload-time = "2025-12-02T20:58:08.783Z" }, + { url = "https://files.pythonhosted.org/packages/b7/b8/5137c048728fddd3315a79c94ba8663f3707f9268af9af15b15e1ef3cd85/vhacdx-0.0.10-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:147030c7683be4f21a3cdfb202b121c01716694b61ddad794345fcd9fa43d0ec", size = 225247, upload-time = "2025-12-02T20:58:09.918Z" }, + { url = "https://files.pythonhosted.org/packages/1b/08/5c731863db402e9878380f68be8722fabbcaf8cfe8d06237aaf15f116d95/vhacdx-0.0.10-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:069eb4381917b790921a33d4cc6ed07f7ed5362474232110baf8dd3dadcd768d", size = 211339, upload-time = "2025-12-02T20:58:10.951Z" }, + { url = "https://files.pythonhosted.org/packages/04/3a/e93ce9b653a9f435c530df8d5ad68a80b8bdc2b8518abc225fef9e7f349a/vhacdx-0.0.10-cp314-cp314-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:7702892008b1150619c1f66a62ef88d1cb8f92b09d9c39a0bfb87d147f1c5ae2", size = 239974, upload-time = "2025-12-02T20:58:12.101Z" }, + { url = "https://files.pythonhosted.org/packages/77/dc/ef34f97a65385bc1f8ed4718fa5f7d96313e299e76761f1b69efaf597797/vhacdx-0.0.10-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:b4d550dfc377471b36f11065fc12cfbbd1750d63b10a336644bfdcbf27aa8382", size = 253245, upload-time = "2025-12-02T20:58:13.303Z" }, + { url = "https://files.pythonhosted.org/packages/f4/6c/57051066bd0589b7fe68c32061821180f520b6a7ef4efa072b755dde63d3/vhacdx-0.0.10-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:edce8f0ff516a111b6f1d644782a1d496b3e9e34ff4ce09849c9b8071627bca5", size = 1227432, upload-time = "2025-12-02T20:58:14.73Z" }, + { url = "https://files.pythonhosted.org/packages/1d/49/3488f2bd991027bd86f072cf776935c80b4e630bd3bc43c3289bc6eeeba0/vhacdx-0.0.10-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:4c463abbdce73d5d0b94eab2c9f43f2b55a4d0e788d87af659cc78029b960bf9", size = 1289126, upload-time = "2025-12-02T20:58:16.009Z" }, + { url = "https://files.pythonhosted.org/packages/77/56/2f4506382a1133bf441cba2010017064e8f7af940d100141799d7e867e58/vhacdx-0.0.10-cp314-cp314-win_amd64.whl", hash = "sha256:b93c834f2bf1fa6630da5d3f77e94ea8e542fca31e385244a7ec905a32155549", size = 198706, upload-time = "2025-12-02T20:58:17.378Z" }, + { url = "https://files.pythonhosted.org/packages/db/f6/4fabfe65f3123abda09adc416a396caf8c2ad1b29c34a5178ec71754a163/vhacdx-0.0.10-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:4c0f1bafc53e156472b0367533c2d3ec7a96b676b6d57aa92dd3e37519331b07", size = 228276, upload-time = "2025-12-02T20:58:18.545Z" }, + { url = "https://files.pythonhosted.org/packages/dc/70/bdc742628adcf9966cea81be7a651300bc399b492d10a763781af6d27041/vhacdx-0.0.10-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:b0f8643dcb1f0774320fc1389ead0d0da4536e4c0fecfd4c8133baec0b6fa556", size = 214287, upload-time = "2025-12-02T20:58:19.696Z" }, + { url = "https://files.pythonhosted.org/packages/84/6a/f2e37ad333d3f671e1d59ba76bb61edc5520146539d52ee29e555becb4ac/vhacdx-0.0.10-cp314-cp314t-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:4547f3e55eb935d163d89c10ffdcadf8797c3b435a9dc82be4e0e27b1e3abff0", size = 240923, upload-time = "2025-12-02T20:58:21.105Z" }, + { url = "https://files.pythonhosted.org/packages/5b/7a/f0325cd7ece95dbbc10d0c3f6d241d47beb3b99ae4dafe2e450082cd7bd9/vhacdx-0.0.10-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:ee09c4f2b6385546001b5e8609f428417fac147cfd3ea020fbc7dec0f11c489b", size = 254257, upload-time = "2025-12-02T20:58:22.176Z" }, + { url = "https://files.pythonhosted.org/packages/ac/56/53347b910351eb4cf32a797e177f18b8d82b1ef4e4325607254cfe88ad2a/vhacdx-0.0.10-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:8b94d198e4716f9220985523f374617432ef5530910f3730051f3e7fcba71798", size = 1228434, upload-time = "2025-12-02T20:58:23.302Z" }, + { url = "https://files.pythonhosted.org/packages/be/f5/f86c63da38b0446ef6652e8e72b84451e440418eaac0f554737e159ae36e/vhacdx-0.0.10-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:39c6d31ed27e3f33e9411927e1567ba37a18ba7ce9295efd1b24414b7313b503", size = 1288854, upload-time = "2025-12-02T20:58:24.46Z" }, + { url = "https://files.pythonhosted.org/packages/0c/d1/b30dec954a24b41358297a3fbe7c30d8e2e818831f552cb34c904baa04e4/vhacdx-0.0.10-cp314-cp314t-win_amd64.whl", hash = "sha256:fc6a613082ec522a020e4f6a09f39ed42546de9aebe99548aa84938b1440871c", size = 204896, upload-time = "2025-12-02T20:58:25.825Z" }, +] + [[package]] name = "virtualenv" version = "20.36.1" From cc076a784a932843c96ff95abdb8e70a5c66d337 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 13 May 2026 22:30:02 -0700 Subject: [PATCH 24/30] feat(mujoco): per-prim collision dispatcher + sidecar + .mjb cache Layers a CollisionSpec dispatcher onto the existing scene_mesh_to_mjcf pipeline. Per prim, decide_for_prim picks one of three modes: - "primitive": single MuJoCo box/sphere/cylinder/capsule via PCA OBB + fill-ratio fit (>= 0.85). Walls, floors, columns, doors get a single geom each instead of dozens of CoACD hulls. - "hulls": single convex hull for small/near-convex prims; CoACD decomposition for genuine concave shells (stairs, planters, organic furniture). - "skip": no collision (sidecar-tagged decoration: lamps, signs). Each hull goes through the existing _valid_hull check (rank-3 + scipy Qt) and falls back to _fallback_box_geom when a hull is degenerate -- preserves the prior conservative behaviour. A sidecar `.collision.json` (auto-discovered next to the source) overrides per-pattern via fnmatch over USD prim paths. Without a sidecar the bake auto-fits primitives + falls back to CoACD. Other fixes carried over from the standalone bake: - before in the wrapper template so the robot's relative meshdir resolves through MuJoCo's last-compiler-wins rule (otherwise pelvis.STL goes missing). - inertia="shell" on every mesh asset -- robust to non-watertight visual meshes (zero-volume road tiles, ceiling panels). - Dummy on dimos_scene to bypass MuJoCo's auto inertia computation from geom volumes (the body is static). - _write_visual_obj substitutes the convex hull when the original mesh isn't watertight (UE exports floor/roof slabs hidden-face- culled, which look see-through in the viewer otherwise). Performance: - ProcessPoolExecutor (fork on macOS) parallelises the per-prim loop across all cores; ~5x speedup, mall bake fits in ~6 min. - load_or_bake() entry point: three-tier cache (.mjb -> wrapper.xml -> full bake) so subsequent launches load in ~1 s instead of recompiling. Mall numbers (5,248 prims): 65k geoms / 9 min compile -> 15k geoms / 33 s compile / ~1 s second-launch via .mjb. --- dimos/simulation/mujoco/collision_spec.py | 686 +++++++++++++++ dimos/simulation/mujoco/scene_mesh_to_mjcf.py | 798 ++++++++++++++---- pyproject.toml | 1 + uv.lock | 18 + 4 files changed, 1318 insertions(+), 185 deletions(-) create mode 100644 dimos/simulation/mujoco/collision_spec.py diff --git a/dimos/simulation/mujoco/collision_spec.py b/dimos/simulation/mujoco/collision_spec.py new file mode 100644 index 0000000000..9fa394feb1 --- /dev/null +++ b/dimos/simulation/mujoco/collision_spec.py @@ -0,0 +1,686 @@ +# 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. + +"""Per-prim collision-shape decision-making for ``bake_scene_mjcf``. + +The bake's job is to turn each USD/glTF/OBJ prim into one or more MuJoCo +````s. This module separates the *decision* (what shape to emit) +from the *emission* (the OBJ/MJCF writing). Three layers cooperate: + +1. **Generic geometric heuristics** — applied to every prim regardless of + source. Tiny-prim skip, aspect-ratio box override, near-convex check. + Safe defaults; no scene-specific knowledge. + +2. **Primitive auto-fit** — try OBB box / Ritter sphere / PCA cylinder / + PCA capsule. Accept the best fit if + ``hull_volume / primitive_volume >= fill_threshold``. Geometric only. + +3. **Sidecar overrides** — a JSON file (``.collision.json`` next + to the source mesh, or explicit path) with ``fnmatch`` patterns over + USD prim paths. Lets users skip lamps, force cylinders on pillars, + tune CoACD per pattern. Whoever produces this file (a human, a + future UE-side extractor, an LLM…) doesn't matter to the bake — the + sidecar is the contract. + +The dispatcher ``emit_for_prim()`` walks: sidecar override → generic +heuristics → primitive auto-fit → CoACD fallback, and returns a list +of ``GeomEmission`` describing every ```` the wrapper should +include for the prim. +""" + +from __future__ import annotations + +from dataclasses import dataclass, field +import fnmatch +import json +import logging +from pathlib import Path +from typing import Literal + +import numpy as np +from scipy.spatial import ConvexHull, QhullError # type: ignore[import-untyped] + +logger = logging.getLogger(__name__) + + +# --------------------------------------------------------------------------- # +# Sidecar spec dataclasses # +# --------------------------------------------------------------------------- # + + +@dataclass +class CollisionSpec: + """User-facing collision configuration loaded from ``.collision.json``. + + Patterns in ``prim_overrides`` are matched with ``fnmatch`` (Unix-shell + globs) against the USD prim path of each prim — e.g. ``/Root/SM_Pillar_*``. + First-match wins; iteration order of the dict is preserved (Python 3.7+). + + Each override value is a dict with at minimum ``"type"``: + + - ``"box"`` / ``"sphere"`` / ``"cylinder"`` / ``"capsule"`` / ``"plane"``: + force the corresponding primitive. Auto-fit picks the parameters + unless explicit ``"size"`` / ``"pos"`` / ``"quat"`` is provided. + - ``"hull"``: force single convex hull, no CoACD. + - ``"decompose"``: force CoACD even if auto-fit would have accepted a + primitive. Optional ``"max_hulls"`` overrides ``coacd_max_hulls``. + - ``"skip"``: emit no collision geom. Visual mesh still drawn. + - ``"auto"``: same as the global default (useful to scope a pattern + back to default behaviour inside a wider override). + + Optional override keys: + + - ``"friction"``: list ``[slide, spin, roll]``. + - ``"max_hulls"``: per-pattern CoACD cap. + """ + + #: Fallback policy when no pattern matches. ``"auto"`` runs the full + #: heuristics→primitive→CoACD pipeline. ``"hull"`` always emits one + #: convex hull. ``"skip"`` emits nothing (visual only). + default: Literal["auto", "hull", "skip"] = "auto" + + #: A primitive is accepted in auto-fit if + #: ``hull_volume / primitive_volume >= fill_threshold``. Higher = + #: stricter (more prims fall through to CoACD). + fill_threshold: float = 0.85 + + #: Prims whose largest extent is below this (metres) emit no geom. + #: Catches trim/fasteners that the robot can't meaningfully contact. + tiny_prim_extent_m: float = 0.03 + + #: If one axis is ``>= aspect_ratio_box`` times the smaller two, the + #: prim is forced to a box even if auto-fit fill ratio is borderline. + #: Catches wall panels, floor slabs, doors. + aspect_ratio_box: float = 20.0 + + #: If mesh's hull is this close to its actual mesh volume, use one + #: hull and skip CoACD entirely (mesh is already near-convex). + near_convex_threshold: float = 0.9 + + #: CoACD concavity threshold (URLab default). Lower = finer + #: decomposition (more sub-hulls). + coacd_threshold: float = 0.05 + + #: Hard cap on hulls per CoACD invocation. -1 = unlimited. + coacd_max_hulls: int = 64 + + #: Only run decomposition when the prim's single-hull volume exceeds + #: this (m³). Smaller furniture-scale prims use one hull regardless. + shell_volume_m3: float = 2.0 + + #: ``USD-path-glob -> override-dict``. See class docstring. + prim_overrides: dict[str, dict] = field(default_factory=dict) + + @classmethod + def from_json(cls, path: Path | str) -> CollisionSpec: + """Load a sidecar. Unknown keys are ignored to keep the format forwards-compatible.""" + path = Path(path) + raw = json.loads(path.read_text()) + known = { + "default", + "fill_threshold", + "tiny_prim_extent_m", + "aspect_ratio_box", + "near_convex_threshold", + "coacd_threshold", + "coacd_max_hulls", + "shell_volume_m3", + "prim_overrides", + } + kwargs = {k: v for k, v in raw.items() if k in known} + # Ignore "$schema" and any future top-level keys silently. + return cls(**kwargs) + + @classmethod + def auto_discover(cls, scene_path: Path | str) -> CollisionSpec: + """Return the sidecar next to ``scene_path`` if it exists, else defaults.""" + scene_path = Path(scene_path) + sidecar = scene_path.with_suffix(".collision.json") + if sidecar.exists(): + logger.info(f"loading collision sidecar: {sidecar}") + return cls.from_json(sidecar) + return cls() + + def resolve(self, prim_path: str) -> dict: + """Find the matching override for ``prim_path`` (USD path). + + Returns a dict with at least ``"type"``. Falls back to + ``{"type": self.default}`` when no pattern matches. + """ + for pattern, override in self.prim_overrides.items(): + if fnmatch.fnmatchcase(prim_path, pattern): + # Pattern's "auto" defers to global default. + if override.get("type") == "auto": + return {**override, "type": self.default} + return override + return {"type": self.default} + + +# --------------------------------------------------------------------------- # +# Emission record # +# --------------------------------------------------------------------------- # + + +@dataclass +class GeomEmission: + """One MuJoCo ```` to emit, in dimos world frame. + + Either ``mesh_path`` is set (mesh-type geom — also emits a + ```` asset) or the primitive parameters (``size``, ``pos``, + ``quat``) are set. + """ + + name: str + purpose: Literal["collision", "visual"] + kind: Literal["mesh", "box", "sphere", "cylinder", "capsule", "plane"] + + #: For ``kind="mesh"``: absolute path to the OBJ. + mesh_path: Path | None = None + + #: Primitive size (semantics depend on ``kind``): + #: * box → (hx, hy, hz) (half-extents) + #: * sphere → (r,) + #: * cylinder→ (r, half_height) + #: * capsule → (r, half_height) (caps extend beyond half_height) + #: * plane → (hx, hy, _grid_spacing) — last is cosmetic only + size: tuple[float, ...] | None = None + + #: World-frame position of the primitive centre. ``None`` for meshes + #: (their geometry is already in world frame). + pos: tuple[float, float, float] | None = None + + #: World-frame orientation (wxyz, MuJoCo convention). ``None`` → + #: identity. Not used for meshes. + quat: tuple[float, float, float, float] | None = None + + #: Optional friction override (slide, spin, roll). + friction: tuple[float, float, float] | None = None + + +# --------------------------------------------------------------------------- # +# Math helpers # +# --------------------------------------------------------------------------- # + + +def _matrix_to_quat_wxyz(R: np.ndarray) -> tuple[float, float, float, float]: + """3x3 right-handed rotation → quaternion ``(w, x, y, z)``. + + Standard Shepperd's method; avoids the singularity at ``trace == -1``. + """ + R = np.asarray(R, dtype=np.float64) + tr = R[0, 0] + R[1, 1] + R[2, 2] + if tr > 0: + s = 0.5 / np.sqrt(tr + 1.0) + w = 0.25 / s + x = (R[2, 1] - R[1, 2]) * s + y = (R[0, 2] - R[2, 0]) * s + z = (R[1, 0] - R[0, 1]) * s + elif (R[0, 0] > R[1, 1]) and (R[0, 0] > R[2, 2]): + s = 2.0 * np.sqrt(1.0 + R[0, 0] - R[1, 1] - R[2, 2]) + w = (R[2, 1] - R[1, 2]) / s + x = 0.25 * s + y = (R[0, 1] + R[1, 0]) / s + z = (R[0, 2] + R[2, 0]) / s + elif R[1, 1] > R[2, 2]: + s = 2.0 * np.sqrt(1.0 + R[1, 1] - R[0, 0] - R[2, 2]) + w = (R[0, 2] - R[2, 0]) / s + x = (R[0, 1] + R[1, 0]) / s + y = 0.25 * s + z = (R[1, 2] + R[2, 1]) / s + else: + s = 2.0 * np.sqrt(1.0 + R[2, 2] - R[0, 0] - R[1, 1]) + w = (R[1, 0] - R[0, 1]) / s + x = (R[0, 2] + R[2, 0]) / s + y = (R[1, 2] + R[2, 1]) / s + z = 0.25 * s + return (float(w), float(x), float(y), float(z)) + + +def _quat_z_to(axis: np.ndarray) -> tuple[float, float, float, float]: + """Quaternion that rotates ``+Z`` onto ``axis`` (unit vector). + + Used for cylinder/capsule placement — MuJoCo's primitive long-axis + is local +Z; we orient by aligning Z to the prim's PCA principal + direction. + """ + z = np.array([0.0, 0.0, 1.0]) + a = axis / (np.linalg.norm(axis) + 1e-12) + d = float(np.dot(z, a)) + if d > 0.99999: + return (1.0, 0.0, 0.0, 0.0) + if d < -0.99999: + # 180° about any axis perpendicular to Z; use X. + return (0.0, 1.0, 0.0, 0.0) + cross = np.cross(z, a) + s = float(np.sqrt(2.0 * (1.0 + d))) + w = s * 0.5 + xyz = cross / s + return (w, float(xyz[0]), float(xyz[1]), float(xyz[2])) + + +# --------------------------------------------------------------------------- # +# Primitive fits # +# --------------------------------------------------------------------------- # + + +#: Lower bound on any primitive's half-extent / radius. MuJoCo rejects +#: a ```` with any size component <= 0, but truly flat prims (road +#: tiles, ceiling panels) can come out of the OBB / cylinder fit with one +#: axis at exactly 0. Clamping to 1 mm yields a valid geom that's still +#: physically reasonable as a thin slab. +_MIN_SIZE_M = 1e-3 + + +def _fit_aabb_box(vertices: np.ndarray) -> dict: + """Axis-aligned bounding box. Identity quat.""" + mn, mx = vertices.min(0), vertices.max(0) + half_ext = np.maximum((mx - mn) / 2.0, _MIN_SIZE_M) + center = (mx + mn) / 2.0 + return { + "type": "box", + "size": tuple(map(float, half_ext)), + "pos": tuple(map(float, center)), + "quat": (1.0, 0.0, 0.0, 0.0), + "volume": float(np.prod(2.0 * half_ext)), + } + + +def _fit_obb_box(vertices: np.ndarray) -> dict: + """Oriented bounding box via PCA. Tighter than AABB when the prim + is rotated relative to world axes (most UE props are world-aligned, + so OBB ≈ AABB, but rotated assets benefit).""" + centroid = vertices.mean(0) + centered = vertices - centroid + cov = np.cov(centered.T) + _, evecs = np.linalg.eigh(cov) + # Ensure right-handed. + if np.linalg.det(evecs) < 0: + evecs[:, 0] = -evecs[:, 0] + local = centered @ evecs + mn, mx = local.min(0), local.max(0) + half_ext = np.maximum((mx - mn) / 2.0, _MIN_SIZE_M) + local_center = (mx + mn) / 2.0 + world_center = centroid + evecs @ local_center + return { + "type": "box", + "size": tuple(map(float, half_ext)), + "pos": tuple(map(float, world_center)), + "quat": _matrix_to_quat_wxyz(evecs), + "volume": float(np.prod(2.0 * half_ext)), + } + + +def _fit_sphere(vertices: np.ndarray) -> dict: + """Centroid + farthest-vertex. Looser than Welzl/Ritter but fine for + fill-ratio comparison.""" + centroid = vertices.mean(0) + r = max(float(np.linalg.norm(vertices - centroid, axis=1).max()), _MIN_SIZE_M) + return { + "type": "sphere", + "size": (r,), + "pos": tuple(map(float, centroid)), + "quat": (1.0, 0.0, 0.0, 0.0), + "volume": float((4.0 / 3.0) * np.pi * r**3), + } + + +def _fit_cylinder(vertices: np.ndarray) -> dict: + """Cylinder along PCA principal axis.""" + centroid = vertices.mean(0) + centered = vertices - centroid + cov = np.cov(centered.T) + evals, evecs = np.linalg.eigh(cov) + axis = evecs[:, -1] # largest variance + proj = centered @ axis + half_h = max(float((proj.max() - proj.min()) / 2.0), _MIN_SIZE_M) + centre_along = float((proj.max() + proj.min()) / 2.0) + pos = centroid + axis * centre_along + # radius = max perp distance from axis line + perp = centered - np.outer(centered @ axis, axis) + r = max(float(np.linalg.norm(perp, axis=1).max()), _MIN_SIZE_M) + return { + "type": "cylinder", + "size": (r, half_h), + "pos": tuple(map(float, pos)), + "quat": _quat_z_to(axis), + "volume": float(np.pi * r * r * 2.0 * half_h), + } + + +def _fit_capsule(vertices: np.ndarray) -> dict: + """Capsule along PCA principal axis. MuJoCo capsule half-height is + the *cylindrical* portion only; total length = 2*(half_h + r).""" + cyl = _fit_cylinder(vertices) + r, h = cyl["size"] + new_h = max(0.0, h - r) + vol = float(np.pi * r * r * 2.0 * new_h) + float((4.0 / 3.0) * np.pi * r**3) + return { + "type": "capsule", + "size": (r, new_h), + "pos": cyl["pos"], + "quat": cyl["quat"], + "volume": vol, + } + + +def _hull_volume(vertices: np.ndarray) -> float | None: + """Convex-hull volume in m³, or ``None`` if qhull rejects the points.""" + try: + return float(ConvexHull(vertices).volume) + except (QhullError, ValueError): + return None + + +def _mesh_volume(vertices: np.ndarray, triangles: np.ndarray) -> float: + """Signed mesh volume (Gauss / divergence theorem on triangle fans). + + Closed meshes return a positive number; for non-closed inputs the + absolute value is a coarse estimate.""" + v0 = vertices[triangles[:, 0]] + v1 = vertices[triangles[:, 1]] + v2 = vertices[triangles[:, 2]] + return float(abs(np.sum(np.einsum("ij,ij->i", v0, np.cross(v1, v2))) / 6.0)) + + +def _best_primitive_fit( + vertices: np.ndarray, + hull_vol: float, + candidates: tuple[str, ...] = ("box", "cylinder", "sphere", "capsule"), +) -> dict | None: + """Try every primitive in ``candidates``; return the one with the + highest fill ratio. Returns ``None`` if no fit succeeds (e.g. < 4 + points).""" + fitters = { + "box": _fit_obb_box, + "sphere": _fit_sphere, + "cylinder": _fit_cylinder, + "capsule": _fit_capsule, + } + fits: list[dict] = [] + for kind in candidates: + try: + f = fitters[kind](vertices) + if f["volume"] <= 0: + continue + f["fill_ratio"] = hull_vol / f["volume"] + fits.append(f) + except Exception as e: + logger.debug(f" primitive fit {kind} failed: {e}") + if not fits: + return None + return max(fits, key=lambda f: f["fill_ratio"]) + + +# --------------------------------------------------------------------------- # +# Generic geometric heuristics # +# --------------------------------------------------------------------------- # + + +def _is_tiny(extent: np.ndarray, threshold_m: float) -> bool: + return bool(extent.max() < threshold_m) + + +def _is_slab(extent: np.ndarray, aspect_ratio: float) -> bool: + """Wall / floor / door / panel — one axis is much smaller than the + other two (or one much larger than the other two — covers beams).""" + sorted_ext = np.sort(extent) + if sorted_ext[0] < 1e-6: + return True + return bool((sorted_ext[2] / sorted_ext[0]) >= aspect_ratio) + + +# --------------------------------------------------------------------------- # +# Dispatcher: per-prim decision # +# --------------------------------------------------------------------------- # + + +@dataclass +class PrimDecision: + """What the dispatcher decided for one prim. Consumed by the bake + which materialises ``GeomEmission`` records and writes OBJs.""" + + #: ``"skip"`` (no collision), ``"primitive"`` (one ```` with + #: kind ∈ {box, sphere, cylinder, capsule, plane}), or ``"hulls"`` + #: (one or more mesh ````s from convex-hull decomposition). + mode: Literal["skip", "primitive", "hulls"] + + #: For ``"primitive"``: the fit dict (``type``, ``size``, ``pos``, + #: ``quat``, ``volume``, ``fill_ratio``). + primitive: dict | None = None + + #: For ``"hulls"``: list of ``(vertices, triangles)`` ready to write. + hulls: list[tuple[np.ndarray, np.ndarray]] = field(default_factory=list) + + #: For diagnostics: which rule fired. + reason: str = "" + + #: Optional friction override from sidecar. + friction: tuple[float, float, float] | None = None + + +def decide_for_prim( + vertices: np.ndarray, + triangles: np.ndarray, + prim_path: str, + spec: CollisionSpec, +) -> PrimDecision: + """Resolve sidecar + heuristics + auto-fit for a single prim. + + Pure function — does no I/O. The caller (bake) materialises the + decision: writes hull OBJs to disk, emits MJCF lines. + + Args: + vertices: ``(N, 3)`` float, world-frame after ``SceneMeshAlignment``. + triangles: ``(M, 3)`` int vertex indices. + prim_path: USD-style prim path used as sidecar key. + spec: parsed sidecar. + """ + extent = vertices.max(0) - vertices.min(0) + override = spec.resolve(prim_path) + kind = override.get("type", spec.default) + friction = override.get("friction") + if friction is not None: + friction = tuple(float(x) for x in friction) + + # 0. Explicit "skip" — short-circuit. + if kind == "skip": + return PrimDecision(mode="skip", reason="sidecar:skip", friction=friction) + + # 1. Tiny-prim guard (applies to "auto" path; explicit overrides win). + if kind in ("auto",) and _is_tiny(extent, spec.tiny_prim_extent_m): + return PrimDecision(mode="skip", reason="tiny-prim", friction=friction) + + # 2. Explicit primitive in sidecar — fit if size/pos not provided. + if kind in ("box", "sphere", "cylinder", "capsule", "plane"): + fit = _resolve_explicit_primitive(vertices, kind, override) + fit["fill_ratio"] = float("nan") # unknown — user asserted this shape + return PrimDecision( + mode="primitive", primitive=fit, reason=f"sidecar:{kind}", friction=friction + ) + + # 3. Explicit hull / decompose paths. + if kind == "hull": + return PrimDecision( + mode="hulls", + hulls=[(vertices, triangles)], # signal: single-hull, no decomp + reason="sidecar:hull", + friction=friction, + ) + if kind == "decompose": + max_h = int(override.get("max_hulls", spec.coacd_max_hulls)) + hulls = _coacd_decompose(vertices, triangles, spec.coacd_threshold, max_h) + return PrimDecision( + mode="hulls", + hulls=hulls, + reason="sidecar:decompose", + friction=friction, + ) + + # 4. From here on: kind == "auto". Generic heuristics first. + + # 4a. Aspect-ratio: slab/beam → force OBB box (fill ratio may be + # marginal because of moulding/profile, but a box collision is + # the right physical answer for walls and slabs). + if _is_slab(extent, spec.aspect_ratio_box): + fit = _fit_obb_box(vertices) + fit["fill_ratio"] = float("nan") + return PrimDecision( + mode="primitive", primitive=fit, reason="aspect-ratio:slab", friction=friction + ) + + # 4b. Need hull volume for the rest. + hull_vol = _hull_volume(vertices) + if hull_vol is None: + return PrimDecision(mode="skip", reason="degenerate (qhull rejected)", friction=friction) + + # 4c. Try primitive auto-fit. + fit = _best_primitive_fit(vertices, hull_vol) + if fit is not None and 0.0 < fit["fill_ratio"] <= 1.5: + # fill_ratio > 1 happens for non-closed hulls; cap to keep this + # finite when reporting. Accept if within tolerance. + if fit["fill_ratio"] >= spec.fill_threshold: + return PrimDecision( + mode="primitive", + primitive=fit, + reason=f"auto:{fit['type']}({fit['fill_ratio']:.2f})", + friction=friction, + ) + + # 4d. Near-convex shortcut: skip CoACD, single hull. + mesh_vol = _mesh_volume(vertices, triangles) + if hull_vol > 0 and mesh_vol / hull_vol > spec.near_convex_threshold: + return PrimDecision( + mode="hulls", + hulls=[(vertices, triangles)], + reason=f"near-convex({mesh_vol / hull_vol:.2f})", + friction=friction, + ) + + # 4e. Small concave prim → single hull (matches today's behaviour + # for furniture-scale things; faster than CoACD). + if hull_vol < spec.shell_volume_m3: + return PrimDecision( + mode="hulls", + hulls=[(vertices, triangles)], + reason="small-shell:single-hull", + friction=friction, + ) + + # 4f. Large concave shell → CoACD. + hulls = _coacd_decompose(vertices, triangles, spec.coacd_threshold, spec.coacd_max_hulls) + return PrimDecision( + mode="hulls", + hulls=hulls, + reason=f"coacd:{len(hulls)}", + friction=friction, + ) + + +# --------------------------------------------------------------------------- # +# Helpers used by the dispatcher # +# --------------------------------------------------------------------------- # + + +def _resolve_explicit_primitive( + vertices: np.ndarray, + kind: str, + override: dict, +) -> dict: + """Build a primitive fit dict from a sidecar override. + + If the override supplies ``size`` (and optionally ``pos`` / ``quat``), + those win. Otherwise we auto-fit the requested primitive and use + those params. ``plane`` is special-cased — we always derive from + the prim's xy footprint at its min z. + """ + if kind == "plane": + mn = vertices.min(0) + mx = vertices.max(0) + return { + "type": "plane", + "size": (float((mx[0] - mn[0]) / 2.0), float((mx[1] - mn[1]) / 2.0), 0.5), + "pos": ( + float((mx[0] + mn[0]) / 2.0), + float((mx[1] + mn[1]) / 2.0), + float(mn[2]), + ), + "quat": (1.0, 0.0, 0.0, 0.0), + "volume": 0.0, + } + + fitters = { + "box": _fit_obb_box, + "sphere": _fit_sphere, + "cylinder": _fit_cylinder, + "capsule": _fit_capsule, + } + fit = fitters[kind](vertices) + # Apply explicit overrides if provided. + if "size" in override: + fit["size"] = tuple(float(x) for x in override["size"]) + if "pos" in override: + fit["pos"] = tuple(float(x) for x in override["pos"]) + if "quat" in override: + fit["quat"] = tuple(float(x) for x in override["quat"]) + return fit + + +def _coacd_decompose( + vertices: np.ndarray, + triangles: np.ndarray, + threshold: float, + max_hulls: int, +) -> list[tuple[np.ndarray, np.ndarray]]: + """Run CoACD on a single prim, return list of ``(verts, tris)`` hulls. + + CoACD is imported lazily — it ships its own C library and we don't + want every import of ``collision_spec`` to pay that cost. + """ + import coacd # type: ignore[import-untyped] + + # CoACD's C lib prints a lot per invocation; quiet it once per process. + if not getattr(_coacd_decompose, "_silenced", False): + coacd.set_log_level("error") + _coacd_decompose._silenced = True # type: ignore[attr-defined] + + mesh = coacd.Mesh(vertices.astype(np.float64), triangles.astype(np.int32)) + # CoACD's MCTS defaults (mcts_iterations=150, resolution=2000) are tuned + # for offline asset prep — minutes per shell on a multi-thousand-prim + # scene. We dial both down ~5x; the resulting hulls are slightly + # noisier but the bake finishes in minutes, not hours. For a one-off + # final bake users can override via the sidecar (future work) or call + # ``bake_scene_mjcf`` directly with a custom ``CollisionSpec``. + parts = coacd.run_coacd( + mesh, + threshold=threshold, + max_convex_hull=max_hulls, + resolution=500, + mcts_iterations=30, + mcts_nodes=10, + ) + out: list[tuple[np.ndarray, np.ndarray]] = [] + for v, t in parts: + v = np.asarray(v, dtype=np.float32) + t = np.asarray(t, dtype=np.int32) + if len(v) >= 4 and len(t) >= 1: + out.append((v, t)) + return out + + +__all__ = [ + "CollisionSpec", + "GeomEmission", + "PrimDecision", + "decide_for_prim", +] diff --git a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py index 25ceb64c86..fe1477cb7e 100644 --- a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -12,19 +12,68 @@ # See the License for the specific language governing permissions and # limitations under the License. -"""Bake a scene mesh into an MJCF wrapper around a robot MJCF.""" +"""Bake a scene mesh into an MJCF wrapper around a robot MJCF. + +The bake walks every prim returned by :func:`load_scene_prims` and asks +:func:`dimos.simulation.mujoco.collision_spec.decide_for_prim` what to +emit for it. The dispatcher returns one of three modes: + +- ``"primitive"`` -- a single MuJoCo primitive ```` (box / sphere / + cylinder / capsule / plane). Used when the prim is approximately + prismatic (auto-fit) or when a sidecar override forces it. +- ``"hulls"`` -- one or more mesh ````s. Either a single convex + hull (small / near-convex prims) or a CoACD decomposition (genuine + concave shells: stairs, planters). +- ``"skip"`` -- no collision geom at all. Used for sidecar-tagged + decoration (lamps, signs) and prims smaller than a threshold. + +Hulls produced by either path are validated with :func:`_valid_hull` +(matrix-rank coplanarity check + scipy ``Qt`` qhull pre-flight); when a +hull is invalid we fall back to a thin OBB box via +:func:`_fallback_box_geom` rather than dropping the geometry, so the +robot doesn't sink through holes. + +When ``include_visual_mesh=True`` the bake additionally writes the +prim's original triangles as a non-colliding visual geom (group 2, +``contype=0 conaffinity=0``). UE's USD exporter culls hidden faces on +static meshes (a floor slab ships with only top + bottom face pairs, +no sides) -- we route visual writes through :func:`_write_visual_obj`, +which substitutes the prim's convex hull when it isn't watertight, so +the viewer renders solid geometry instead of see-through slabs. + +Per-prim work is fanned across processes via ``ProcessPoolExecutor`` +(fork on macOS) since each prim's decision is independent and CoACD +calls dominate wall time. + +Output is cached at ``~/.cache/dimos/scene_meshes//`` keyed on +the SHA256 of (source mesh, robot MJCF, alignment, meshdir, sidecar +spec, visual flag, schema version). :func:`load_or_bake` is the +recommended entry point -- it handles a three-tier cache: + + 1. ``compiled.mjb`` exists -> load directly (~1 s) + 2. ``wrapper.xml`` + OBJs exist -> compile XML, save ``.mjb`` + 3. Nothing exists -> full bake, then compile + save ``.mjb`` +""" from __future__ import annotations +import argparse +from concurrent.futures import ProcessPoolExecutor, as_completed from dataclasses import asdict, dataclass import hashlib +import multiprocessing +import os from pathlib import Path -import sys +import time from typing import Any import numpy as np import open3d as o3d # type: ignore[import-untyped] +from dimos.simulation.mujoco.collision_spec import ( + CollisionSpec, + decide_for_prim, +) from dimos.simulation.mujoco.mesh_scene import SceneMeshAlignment, load_scene_prims from dimos.utils.logging_config import setup_logger @@ -34,58 +83,103 @@ CACHE_DIR = Path.home() / ".cache" / "dimos" / "scene_meshes" +# ```` comes BEFORE ```` so the wrapper's absolute +# meshdir is the *last* compiler block in the merged spec -- MuJoCo's +# "last compiler wins" rule then routes the robot MJCF's +# ```` entries to ``/X.STL``. If +# the order is reversed the robot's own ```` +# overrides the absolute path with a relative one that resolves against +# the wrapper's cache directory and the include's meshes can't be found. +# +# The dummy ```` on dimos_scene bypasses MuJoCo's auto- +# computation of body inertia from geom volumes -- the body is static +# (no joint) so the values don't affect physics, but without this any +# zero-volume visual mesh (road tiles, ceiling panels, flat slabs) +# triggers ``Error: mesh volume is too small`` at compile time. _WRAPPER_TEMPLATE = """\ - + {asset_meshes} + {scene_geoms} """ -_ASSET_LINE = ' ' -_GEOM_LINE = ( +# ``inertia="shell"`` makes MuJoCo compute mesh inertia from surface +# area instead of enclosed volume -- robust to non-watertight visual +# meshes from art tools. Safe for closed CoACD hulls too, so we apply +# it universally for one fewer code path. +_ASSET_LINE = ' ' + +# Collision (group 3) -- actually collides. rgba alpha < 1 lets the +# user toggle visibility independently of the visual mesh. +_COL_MESH_LINE = ( ' ' + 'contype="1" conaffinity="1" group="3" rgba="0.5 0.6 1.0 0.35"{friction}/>' +) +_COL_BOX_LINE = ( + ' ' ) +_COL_SPHERE_LINE = ( + ' ' +) +_COL_CYL_LINE = ( + ' ' +) +_COL_CAP_LINE = ( + ' ' +) +_COL_PLANE_LINE = ( + ' ' +) + +# Visual (group 2) -- drawn, doesn't collide. _VISUAL_GEOM_LINE = ( ' ' -) -_BOX_GEOM_LINE = ( - ' ' + 'contype="0" conaffinity="0" group="2" rgba="0.65 0.65 0.65 1"/>' ) + + +# Constants kept from the prior implementation -- conservative +# fallback thresholds for hull validity / box-fallback geometry. _DEGENERATE_EPS = 1e-3 -_SHELL_VOLUME_M3 = 2.0 -_CACHE_KEY_LEN = 12 -_CACHE_SCHEMA_VERSION = "visual-proxy-v1" -_VHACD_MAX_HULLS = 64 -_VHACD_RESOLUTION = 200_000 -_VHACD_MIN_COMPONENTS = 512 -_COMPONENT_VHACD_MAX_SCENE_PRIMS = 256 _MIN_HULL_EXTENT_M = 5e-3 _FALLBACK_BOX_THICKNESS_M = 0.03 _MIN_FALLBACK_BOX_EXTENT_M = 0.25 _MIN_FALLBACK_BOX_AREA_M2 = 0.05 +_CACHE_KEY_LEN = 12 +# Bump when the bake pipeline's output format changes so old caches +# invalidate on the next call. Increment for any change that could +# affect MJCF emission (new geom kinds, rewritten visual policy, etc.). +_CACHE_SCHEMA_VERSION = "dispatcher-v2" + @dataclass class _BakeArtifacts: + """Aggregated stats + emission lines from one bake.""" + asset_lines: list[str] geom_lines: list[str] - total_tris: int - skipped_degenerate: int - n_hulls: int - n_decomposed: int + n_primitive: int + n_hulls_total: int n_box_fallbacks: int + n_skipped: int n_visuals: int + n_degenerate_dropped: int + decision_reasons: dict[str, int] def bake_scene_mjcf( @@ -94,34 +188,44 @@ def bake_scene_mjcf( alignment: SceneMeshAlignment | None = None, meshdir: str | Path | None = None, cache_root: Path | None = None, + collision_spec: CollisionSpec | None = None, include_visual_mesh: bool = False, ) -> Path: - """Convert ``scene_mesh_path`` to OBJ and emit a wrapped MJCF. + """Convert ``scene_mesh_path`` to OBJs + MJCF wrapper around the robot. Args: - scene_mesh_path: ``.usdz`` / ``.glb`` / ``.obj`` etc.; anything - ``mesh_scene.load_scene_mesh`` accepts. + scene_mesh_path: ``.usdz`` / ``.usda`` / ``.glb`` / ``.obj`` / + etc. Anything ``mesh_scene.load_scene_prims`` accepts. robot_mjcf_path: the base robot MJCF the wrapper will ````. alignment: scale / translation / rotation / y-up swap to bake - into the OBJ before MuJoCo sees it. - meshdir: directory MuJoCo should resolve unqualified mesh - filenames against. ``None`` uses the robot MJCF's parent - directory. Blueprints for robot assets stored elsewhere - should pass this explicitly. - cache_root: override for the cache directory (defaults to + into world frame before any geom is emitted. + meshdir: directory MuJoCo resolves the *robot's* unqualified + mesh filenames against. Defaults to ``robot_mjcf_path.parent``. + Override when the robot ships its assets in a sibling + ``assets/`` folder (typical for menagerie robots). + cache_root: override the cache root (defaults to ``~/.cache/dimos/scene_meshes``). - include_visual_mesh: also add the original scene prim meshes as - non-colliding visual geoms. Useful for material-batched scenes - where convex collision proxies are too coarse to inspect. + collision_spec: per-prim policy. ``None`` auto-discovers a + sidecar ``.collision.json`` next to the source, or + falls back to ``CollisionSpec()`` defaults (auto-fit + primitives, CoACD on large concave shells). + include_visual_mesh: also emit a non-colliding visual geom for + every prim showing its original triangles. The viewer + renders these instead of the collision hulls -- much nicer + for visual debugging, but doubles disk usage. When ``True`` + non-watertight prim meshes are substituted with their convex + hull so they don't appear see-through. Returns: - Path to the wrapper MJCF. Pass this to ``MujocoSimModule`` - instead of the raw robot MJCF. + Path to the wrapper MJCF. Pass to ``MujocoSimModule`` instead of + the raw robot MJCF, or use :func:`load_or_bake` to also get an + ``.mjb`` cache. """ scene_mesh_path = Path(scene_mesh_path).expanduser().resolve() robot_mjcf_path = Path(robot_mjcf_path).expanduser().resolve() align = alignment or SceneMeshAlignment() + spec = collision_spec or CollisionSpec.auto_discover(scene_mesh_path) if not scene_mesh_path.exists(): raise FileNotFoundError(f"scene mesh not found: {scene_mesh_path}") @@ -135,6 +239,7 @@ def bake_scene_mjcf( robot_mjcf_path, align, meshdir, + spec=spec, include_visual_mesh=include_visual_mesh, ) root = (cache_root or CACHE_DIR).expanduser() @@ -147,26 +252,34 @@ def bake_scene_mjcf( cache_dir.mkdir(parents=True, exist_ok=True) - logger.info(f"bake_scene_mjcf: loading + aligning {scene_mesh_path} (per-prim)") + logger.info(f"bake_scene_mjcf: loading + aligning {scene_mesh_path}") prims = load_scene_prims(scene_mesh_path, alignment=align) - logger.info(f"bake_scene_mjcf: {len(prims)} prims to bake") + logger.info(f"bake_scene_mjcf: {len(prims)} prims to process") - artifacts = _bake_collision_hulls( + artifacts = _bake_prims( prims, cache_dir, + spec=spec, include_visual_mesh=include_visual_mesh, ) - if not artifacts.asset_lines and not artifacts.geom_lines: + if not artifacts.geom_lines: raise RuntimeError( - "bake_scene_mjcf: every hull came out degenerate; nothing left to collide against" + "bake_scene_mjcf: every prim got skipped or produced only " + "degenerate hulls; nothing left to collide against. Check " + "the source mesh and alignment." ) + logger.info( - f"bake_scene_mjcf: baked {artifacts.n_hulls} convex hulls from {len(prims)} prims " - f"({artifacts.total_tris} tris total), VHACD-decomposed {artifacts.n_decomposed} " - f"shell prims, added {artifacts.n_box_fallbacks} thin box fallbacks, " - f"added {artifacts.n_visuals} visual passthrough meshes, " - f"skipped {artifacts.skipped_degenerate} degenerate hulls" + f"bake_scene_mjcf: {artifacts.n_primitive} primitive geoms, " + f"{artifacts.n_hulls_total} hull geoms, " + f"{artifacts.n_box_fallbacks} box fallbacks, " + f"{artifacts.n_visuals} visual passthrough meshes, " + f"{artifacts.n_skipped} skipped, " + f"{artifacts.n_degenerate_dropped} degenerate hulls dropped" ) + # Top-10 decision reasons -- useful when tuning a sidecar. + for reason, n in sorted(artifacts.decision_reasons.items(), key=lambda kv: -kv[1])[:10]: + logger.info(f" reason {reason:32s} {n}") _write_wrapper( wrapper_path=wrapper_path, @@ -179,17 +292,122 @@ def bake_scene_mjcf( return wrapper_path +def load_or_bake( + scene_mesh_path: str | Path, + robot_mjcf_path: str | Path, + alignment: SceneMeshAlignment | None = None, + meshdir: str | Path | None = None, + cache_root: Path | None = None, + collision_spec: CollisionSpec | None = None, + include_visual_mesh: bool = False, + rebake: bool = False, +) -> tuple[Any, Path]: + """Three-tier cache: ``.mjb`` -> ``wrapper.xml`` -> full bake. + + Returns ``(MjModel, wrapper_path)``. + + 1. If ``compiled.mjb`` exists in the bake's cache dir -> load it + directly (~1 s for a 5k-prim mall). + 2. Else if ``wrapper.xml`` exists -> compile XML, save the ``.mjb`` + beside it, return the model. + 3. Else -> run the full bake, compile the resulting wrapper, save + ``.mjb``, return the model. + + Set ``rebake=True`` to force step 3 even when caches exist. + + The cache key incorporates source-mesh signature, robot MJCF, + alignment, sidecar spec and the schema version -- change any of + those and a fresh cache directory is created automatically (the + old one stays on disk until you clean it). + """ + import mujoco # type: ignore[import-untyped] + + if not rebake: + # Compute the cache key without baking, so we can probe for an + # existing .mjb / wrapper.xml without doing any work. + sp = Path(scene_mesh_path).expanduser().resolve() + rp = Path(robot_mjcf_path).expanduser().resolve() + al = alignment or SceneMeshAlignment() + sd = collision_spec or CollisionSpec.auto_discover(sp) + md = Path(meshdir).expanduser().resolve() if meshdir else rp.parent + key = _cache_key(sp, rp, al, md, spec=sd, include_visual_mesh=include_visual_mesh) + root = (cache_root or CACHE_DIR).expanduser() + cache_dir = root / key + mjb = cache_dir / "compiled.mjb" + wrapper = cache_dir / "wrapper.xml" + + if mjb.exists(): + logger.info(f"load_or_bake: loading compiled binary {mjb}") + t0 = time.time() + model = mujoco.MjModel.from_binary_path(str(mjb)) + logger.info( + f" loaded in {time.time() - t0:.1f}s " + f"(nbody={model.nbody} ngeom={model.ngeom} nmesh={model.nmesh})" + ) + return model, wrapper + + if wrapper.exists() and any(cache_dir.glob("*.obj")): + logger.info(f"load_or_bake: wrapper cached, compiling XML -> .mjb at {wrapper}") + t0 = time.time() + model = mujoco.MjModel.from_xml_path(str(wrapper)) + logger.info( + f" compiled in {time.time() - t0:.1f}s " + f"(nbody={model.nbody} ngeom={model.ngeom} nmesh={model.nmesh})" + ) + mujoco.mj_saveModel(model, str(mjb)) + logger.info(f" saved compiled binary: {mjb} ({mjb.stat().st_size / 1e6:.1f} MB)") + return model, wrapper + + # Full bake path. + wrapper = bake_scene_mjcf( + scene_mesh_path=scene_mesh_path, + robot_mjcf_path=robot_mjcf_path, + alignment=alignment, + meshdir=meshdir, + cache_root=cache_root, + collision_spec=collision_spec, + include_visual_mesh=include_visual_mesh, + ) + logger.info(f"load_or_bake: compiling baked wrapper {wrapper}") + t0 = time.time() + model = mujoco.MjModel.from_xml_path(str(wrapper)) + logger.info( + f" compiled in {time.time() - t0:.1f}s " + f"(nbody={model.nbody} ngeom={model.ngeom} nmesh={model.nmesh})" + ) + mjb = wrapper.with_name("compiled.mjb") + mujoco.mj_saveModel(model, str(mjb)) + logger.info(f" saved compiled binary: {mjb} ({mjb.stat().st_size / 1e6:.1f} MB)") + return model, wrapper + + +# --------------------------------------------------------------------------- # +# Cache key # +# --------------------------------------------------------------------------- # + + def _cache_key( scene_mesh_path: Path, robot_mjcf_path: Path, alignment: SceneMeshAlignment, meshdir: Path, *, + spec: CollisionSpec, include_visual_mesh: bool, ) -> str: + """SHA256-12 over every input that affects bake output. + + Source-mesh signature is ``(path, size, mtime_ns)`` -- much faster + than reading the whole file (a mall scene's USDA + Assets is a few + hundred MB) and reliably invalidates when the artist re-exports. + Sidecar spec is hashed by its JSON encoding so any field change + (new override pattern, tuned threshold) invalidates correctly. + """ + import json + def _file_signature(path: Path) -> str: - stat = path.stat() - return f"{path}:{stat.st_size}:{stat.st_mtime_ns}" + st = path.stat() + return f"{path}:{st.st_size}:{st.st_mtime_ns}" h = hashlib.sha256() h.update(_CACHE_SCHEMA_VERSION.encode()) @@ -197,7 +415,8 @@ def _file_signature(path: Path) -> str: h.update(_file_signature(robot_mjcf_path).encode()) h.update(repr(sorted(asdict(alignment).items())).encode()) h.update(str(meshdir).encode()) - h.update(str(include_visual_mesh).encode()) + h.update(json.dumps(asdict(spec), sort_keys=True).encode()) + h.update(b"visual=" + (b"1" if include_visual_mesh else b"0")) return h.hexdigest()[:_CACHE_KEY_LEN] @@ -205,150 +424,246 @@ def _cache_hit(wrapper_path: Path) -> bool: return wrapper_path.exists() -def _bake_collision_hulls( - prims: list[Any], - cache_dir: Path, - *, - include_visual_mesh: bool = False, -) -> _BakeArtifacts: - import trimesh +# --------------------------------------------------------------------------- # +# Per-prim worker (parallel-safe) # +# --------------------------------------------------------------------------- # + + +def _process_one_prim( + args: tuple[object, Path, CollisionSpec, bool], +) -> tuple[list[str], list[str], str, str, dict[str, int]]: + """Worker entry-point -- must be picklable. + + Takes ``(prim, cache_dir, spec, include_visual_mesh)`` and returns + ``(asset_lines, geom_lines, decision_mode, decision_reason, counters)`` + where ``counters`` carries small int deltas the parent aggregates + (``hulls``, ``box_fallbacks``, ``visuals``, ``degenerate``). + + No shared state -- the only side effects are OBJ writes into + ``cache_dir`` (each prim has a unique name, no contention). + """ + prim, cache_dir, spec, include_visual_mesh = args + v = np.asarray(prim.vertices, dtype=np.float64) + t = np.asarray(prim.triangles) + if len(v) < 3 or len(t) < 1: + return ( + [], + [], + "skip", + "empty-prim", + {"hulls": 0, "box_fallbacks": 0, "visuals": 0, "degenerate": 0}, + ) + + decision = decide_for_prim(vertices=v, triangles=t, prim_path=prim.name, spec=spec) asset_lines: list[str] = [] geom_lines: list[str] = [] - total_tris = 0 - skipped_degenerate = 0 - n_hulls = 0 - n_decomposed = 0 - n_box_fallbacks = 0 - n_visuals = 0 - component_vhacd = len(prims) <= _COMPONENT_VHACD_MAX_SCENE_PRIMS - logger.info(f"bake_scene_mjcf: per-prim convex-hulling {len(prims)} prims (one-time)") - for prim in prims: - if include_visual_mesh: - asset_name = f"{prim.name}_visual" - obj_file = cache_dir / f"{asset_name}.obj" - _write_mesh_obj(obj_file, prim.vertices, prim.triangles) - asset_lines.append(_ASSET_LINE.format(name=asset_name, file=str(obj_file))) - geom_lines.append(_VISUAL_GEOM_LINE.format(name=f"{asset_name}_geom", mesh=asset_name)) - n_visuals += 1 - - tm = trimesh.Trimesh( - vertices=prim.vertices.astype(np.float64), - faces=prim.triangles, - process=False, - ) + counters = {"hulls": 0, "box_fallbacks": 0, "visuals": 0, "degenerate": 0} + + # Visual passthrough (always before the collision branch -- even + # ``skip`` prims can have a visual). + if include_visual_mesh: + vis_name = f"{prim.name}_visual" + vis_path = cache_dir / f"{vis_name}.obj" try: - single_hull = tm.convex_hull - except Exception as e: - box_line = _fallback_box_geom(f"{prim.name}_box", prim.vertices) + _write_visual_obj(vis_path, v, t.astype(np.int32)) + asset_lines.append(_ASSET_LINE.format(name=vis_name, file=str(vis_path))) + geom_lines.append(_VISUAL_GEOM_LINE.format(name=f"{vis_name}_geom", mesh=vis_name)) + counters["visuals"] = 1 + except Exception: + pass + + friction_attr = "" + if decision.friction is not None: + friction_attr = f' friction="{_fmt_vec(np.asarray(decision.friction))}"' + + if decision.mode == "skip": + return asset_lines, geom_lines, "skip", decision.reason, counters + + if decision.mode == "primitive": + prim_geom = _emit_primitive_geom(prim.name, decision.primitive, friction_attr) + if prim_geom is not None: + geom_lines.append(prim_geom) + return asset_lines, geom_lines, "primitive", decision.reason, counters + + # mode == "hulls". Each hull goes through _valid_hull; invalid + # ones get a fallback OBB box (avoids dropping collision entirely + # at locations where a hull happened to be degenerate). + for j, (hv, ht) in enumerate(decision.hulls): + v_arr = np.asarray(hv, dtype=np.float32) + f_arr = np.asarray(ht, dtype=np.int32) + if not _valid_hull(v_arr, f_arr): + box_line = _fallback_box_geom(f"{prim.name}_h{j:03d}_box", v_arr, friction_attr) if box_line is None: - logger.warning(f" convex_hull failed for {prim.name}: {e}; skipping") - skipped_degenerate += 1 + counters["degenerate"] += 1 else: - logger.warning( - f" convex_hull failed for {prim.name}: {e}; using thin box fallback" - ) geom_lines.append(box_line) - n_box_fallbacks += 1 + counters["box_fallbacks"] += 1 continue - hulls, decomposed = _collision_hulls( - tm, - single_hull, - prim.name, - component_vhacd=component_vhacd, + asset_name = f"{prim.name}_h{j:03d}" + obj_file = cache_dir / f"{asset_name}.obj" + _write_hull_obj(obj_file, v_arr, f_arr) + asset_lines.append(_ASSET_LINE.format(name=asset_name, file=str(obj_file))) + geom_lines.append( + _COL_MESH_LINE.format( + name=f"{asset_name}_geom", mesh=asset_name, friction=friction_attr + ) ) - if decomposed: - n_decomposed += 1 - - for j, hull in enumerate(hulls): - v = np.asarray(hull.vertices, dtype=np.float32) - f = np.asarray(hull.faces, dtype=np.int32) - if not _valid_hull(v, f): - box_line = _fallback_box_geom(f"{prim.name}_h{j:03d}_box", v) - if box_line is None: - skipped_degenerate += 1 - else: - geom_lines.append(box_line) - n_box_fallbacks += 1 - continue - - asset_name = f"{prim.name}_h{j:03d}" - obj_file = cache_dir / f"{asset_name}.obj" - _write_hull_obj(obj_file, v, f) - - total_tris += len(f) - n_hulls += 1 - asset_lines.append(_ASSET_LINE.format(name=asset_name, file=str(obj_file))) - geom_lines.append(_GEOM_LINE.format(name=f"{asset_name}_geom", mesh=asset_name)) + counters["hulls"] += 1 + + return asset_lines, geom_lines, "hulls", decision.reason, counters + + +def _bake_prims( + prims: list[Any], + cache_dir: Path, + *, + spec: CollisionSpec, + include_visual_mesh: bool, +) -> _BakeArtifacts: + """Fan per-prim work across cores; aggregate the resulting MJCF lines. + + Uses ``fork`` (not macOS's default ``spawn``) so worker processes + inherit the parent's already-imported modules -- otherwise each + worker re-imports the script that called ``bake_scene_mjcf`` and + recurses if it lacks an ``if __name__ == "__main__"`` guard. Fork + is safe here because we haven't touched any thread-holding C + library before this point (Open3D's OBJ writer only runs inside + workers; ``pxr.Usd`` is single-threaded and finishes its work in + ``load_scene_prims`` before fork). + """ + asset_lines: list[str] = [] + geom_lines: list[str] = [] + n_primitive = 0 + n_hulls_total = 0 + n_box_fallbacks = 0 + n_skipped = 0 + n_visuals = 0 + n_degenerate = 0 + reasons: dict[str, int] = {} + + n_workers = max(1, (os.cpu_count() or 4) - 1) + logger.info(f"_bake_prims: fanning {len(prims)} prims across {n_workers} workers (fork)") + + work_items = [(prim, cache_dir, spec, include_visual_mesh) for prim in prims] + mp_ctx = multiprocessing.get_context("fork") + + t0 = time.time() + with ProcessPoolExecutor(max_workers=n_workers, mp_context=mp_ctx) as ex: + futures = [ex.submit(_process_one_prim, item) for item in work_items] + done = 0 + for fut in as_completed(futures): + a_lines, g_lines, mode, reason, counters = fut.result() + asset_lines.extend(a_lines) + geom_lines.extend(g_lines) + reasons[reason] = reasons.get(reason, 0) + 1 + if mode == "primitive": + n_primitive += 1 + elif mode == "skip": + n_skipped += 1 + n_hulls_total += counters["hulls"] + n_box_fallbacks += counters["box_fallbacks"] + n_visuals += counters["visuals"] + n_degenerate += counters["degenerate"] + done += 1 + if done % 250 == 0 or done == len(prims): + elapsed = time.time() - t0 + eta = elapsed * (len(prims) - done) / max(done, 1) + logger.info( + f" prim {done}/{len(prims)} " + f"({100 * done / len(prims):.0f}%) " + f"elapsed={elapsed:.0f}s eta={eta:.0f}s " + f"hulls_so_far={n_hulls_total}" + ) return _BakeArtifacts( asset_lines=asset_lines, geom_lines=geom_lines, - total_tris=total_tris, - skipped_degenerate=skipped_degenerate, - n_hulls=n_hulls, - n_decomposed=n_decomposed, + n_primitive=n_primitive, + n_hulls_total=n_hulls_total, n_box_fallbacks=n_box_fallbacks, + n_skipped=n_skipped, n_visuals=n_visuals, + n_degenerate_dropped=n_degenerate, + decision_reasons=reasons, ) -def _collision_hulls( - tm: Any, - single_hull: Any, - prim_name: str, - *, - component_vhacd: bool, -) -> tuple[list[Any], bool]: - hull_volume = float(single_hull.volume) - component_count = _body_count(tm) - should_decompose = hull_volume > _SHELL_VOLUME_M3 or ( - component_vhacd and component_count >= _VHACD_MIN_COMPONENTS +# --------------------------------------------------------------------------- # +# Geom emission helpers # +# --------------------------------------------------------------------------- # + + +def _emit_primitive_geom(prim_name: str, fit: dict | None, friction_attr: str) -> str | None: + """Render one ``PrimDecision.primitive`` dict to MJCF text. + + Returns ``None`` if ``fit`` is missing required fields (defensive -- + ``decide_for_prim`` should always populate them, but a malformed + sidecar override could slip through). + """ + if fit is None: + return None + kind = fit.get("type") + pos = _fmt_vec(np.asarray(fit["pos"])) + size = _fmt_vec(np.asarray(fit["size"])) + quat = ( + _fmt_vec(np.asarray(fit["quat"])) + if "quat" in fit and fit["quat"] is not None + else "1 0 0 0" ) - if not should_decompose: - return [single_hull], False - try: - parts = tm.convex_decomposition( - maxConvexHulls=_VHACD_MAX_HULLS, - resolution=_VHACD_RESOLUTION, + name = f"{prim_name}_col" + if kind == "box": + return _COL_BOX_LINE.format( + name=name, pos=pos, quat=quat, size=size, friction=friction_attr ) - hulls = parts if isinstance(parts, list) else [parts] - logger.info( - f" {prim_name}: VHACD decomposed " - f"({hull_volume:.3g} m³ shell, {component_count} components -> " - f"{len(hulls)} sub-hulls)" + if kind == "sphere": + return _COL_SPHERE_LINE.format(name=name, pos=pos, size=size, friction=friction_attr) + if kind == "cylinder": + return _COL_CYL_LINE.format( + name=name, pos=pos, quat=quat, size=size, friction=friction_attr ) - return hulls, True - except Exception as e: - logger.warning( - f" VHACD failed for {prim_name}: {e}; using single hull " - "(large rooms may collide as a solid shell)" + if kind == "capsule": + return _COL_CAP_LINE.format( + name=name, pos=pos, quat=quat, size=size, friction=friction_attr ) - return [single_hull], False + if kind == "plane": + return _COL_PLANE_LINE.format( + name=name, pos=pos, quat=quat, size=size, friction=friction_attr + ) + return None -def _body_count(tm: Any) -> int: - try: - return int(tm.body_count) - except Exception: - return 1 +# --------------------------------------------------------------------------- # +# Hull validity & box fallback (preserved from prior implementation) # +# --------------------------------------------------------------------------- # def _valid_hull(v: np.ndarray, f: np.ndarray) -> bool: + """Reject hulls that MuJoCo's qhull would choke on at compile time. + + Four layers: + 1. trivial -- < 4 vertices or < 4 faces. + 2. extent -- all-axis ``> 5 mm`` (matches MuJoCo's mj_loadXML + coplanarity tolerance for ~100mm-wide hulls). + 3. rank -- centred vertex matrix must have rank 3 (catches + coplanar hulls the extent check misses, e.g. a T-shaped + hull whose XY extent is large but Z is zero). + 4. scipy ConvexHull pre-flight with ``Qt`` -- same options + MuJoCo uses; if scipy can't build it, mj_loadXML can't either. + """ if len(v) < 4 or len(f) < 4: return False extent = v.max(axis=0) - v.min(axis=0) if (extent < _DEGENERATE_EPS).any(): return False - min_ext = float(extent.min()) - if min_ext < _MIN_HULL_EXTENT_M: + if float(extent.min()) < _MIN_HULL_EXTENT_M: return False centered = v.astype(np.float64) - v.astype(np.float64).mean(axis=0) if np.linalg.matrix_rank(centered, tol=_DEGENERATE_EPS) < 3: return False try: - from scipy.spatial import ConvexHull, QhullError + from scipy.spatial import ConvexHull, QhullError # type: ignore[import-untyped] ConvexHull(v, qhull_options="Qt") except (QhullError, ValueError): @@ -356,7 +671,15 @@ def _valid_hull(v: np.ndarray, f: np.ndarray) -> bool: return True -def _fallback_box_geom(name: str, vertices: np.ndarray) -> str | None: +def _fallback_box_geom(name: str, vertices: np.ndarray, friction_attr: str = "") -> str | None: + """Emit a thin OBB box geom for vertices that can't form a valid hull. + + The thickness floor (``_FALLBACK_BOX_THICKNESS_M = 3 cm``) keeps the + box thick enough that the robot can stand on it without falling + through. Returns ``None`` for prims too small to bother (< 25 cm + largest extent or < 0.05 m^2 face area) -- those fall through to + the degenerate counter. + """ finite = vertices[np.isfinite(vertices).all(axis=1)].astype(np.float64) if len(finite) < 3: return None @@ -371,17 +694,25 @@ def _fallback_box_geom(name: str, vertices: np.ndarray) -> str | None: extent = np.maximum(extent, _FALLBACK_BOX_THICKNESS_M) half_size = 0.5 * extent quat = _rotation_matrix_to_wxyz(rotation) - return _BOX_GEOM_LINE.format( + return _COL_BOX_LINE.format( name=name, pos=_fmt_vec(center), quat=_fmt_vec(quat), size=_fmt_vec(half_size), + friction=friction_attr, ) -def _oriented_box(vertices: np.ndarray) -> tuple[np.ndarray, np.ndarray, np.ndarray]: +def _oriented_box( + vertices: np.ndarray, +) -> tuple[np.ndarray, np.ndarray, np.ndarray]: + """OBB via trimesh's ``bounding_box_oriented``. + + Falls back to AABB if trimesh's OBB fitter produces non-finite + output or the prim has < 3 vertices. + """ try: - import trimesh + import trimesh # type: ignore[import-untyped] tm = trimesh.Trimesh(vertices=vertices, faces=np.empty((0, 3), dtype=np.int32)) obb = tm.bounding_box_oriented @@ -402,7 +733,8 @@ def _oriented_box(vertices: np.ndarray) -> tuple[np.ndarray, np.ndarray, np.ndar def _rotation_matrix_to_wxyz(rotation: np.ndarray) -> np.ndarray: - from scipy.spatial.transform import Rotation + """3x3 rotation -> ``(w, x, y, z)`` quaternion.""" + from scipy.spatial.transform import Rotation # type: ignore[import-untyped] xyzw = Rotation.from_matrix(rotation).as_quat() return np.array([xyzw[3], xyzw[0], xyzw[1], xyzw[2]], dtype=np.float64) @@ -412,7 +744,48 @@ def _fmt_vec(values: np.ndarray) -> str: return " ".join(f"{float(v):.9g}" for v in values) +# --------------------------------------------------------------------------- # +# OBJ I/O # +# --------------------------------------------------------------------------- # + + def _write_hull_obj(obj_file: Path, vertices: np.ndarray, faces: np.ndarray) -> None: + """Write a CoACD/single-hull mesh. No watertight check -- hulls are + closed by construction.""" + _write_mesh_obj(obj_file, vertices, faces) + + +def _write_visual_obj(obj_file: Path, vertices: np.ndarray, faces: np.ndarray) -> None: + """Write a *renderable* OBJ -- closed under all viewing angles. + + UE's static-mesh exporter culls hidden faces (a floor slab ships + with only top + bottom face pairs, no sides), so writing the + artist's geometry verbatim produces meshes that appear see-through + in MuJoCo's viewer from any oblique angle. We check + ``trimesh.is_watertight`` and, if not, substitute the prim's + convex hull (which is always closed). + + For non-prismatic prims (chairs, plants) the hull is a coarse + visual approximation; for the most common offenders (floor / roof + / wall / ceiling slabs that are box-shaped to begin with) the hull + matches the original exactly. Watertight prims (full furniture + meshes from UE) keep their original geometry. + """ + import trimesh # type: ignore[import-untyped] + + tm = trimesh.Trimesh( + vertices=np.asarray(vertices, dtype=np.float64), + faces=np.asarray(faces, dtype=np.int32), + process=False, + ) + if not tm.is_watertight: + try: + hull = tm.convex_hull + if len(hull.vertices) >= 4 and len(hull.faces) >= 4: + vertices = np.asarray(hull.vertices, dtype=np.float64) + faces = np.asarray(hull.faces, dtype=np.int32) + except Exception: + pass # fall back to original; visual may look hollow _write_mesh_obj(obj_file, vertices, faces) @@ -430,6 +803,11 @@ def _write_mesh_obj(obj_file: Path, vertices: np.ndarray, faces: np.ndarray) -> raise RuntimeError(f"open3d failed to write OBJ: {obj_file}") +# --------------------------------------------------------------------------- # +# Wrapper writer + CLI # +# --------------------------------------------------------------------------- # + + def _write_wrapper( *, wrapper_path: Path, @@ -447,45 +825,95 @@ def _write_wrapper( scene_geoms="\n".join(geom_lines), ) wrapper_path.write_text(wrapper_xml) - logger.info(f"bake_scene_mjcf: wrote wrapper {wrapper_path}") + logger.info(f"_write_wrapper: wrote {wrapper_path}") def cli_main() -> None: - """Bake a wrapper, verify it loads, optionally open MuJoCo's native viewer.""" - args = list(sys.argv[1:]) - view = False - if "--view" in args: - view = True - args.remove("--view") - if len(args) < 2: - print( - "usage: python -m dimos.simulation.mujoco.scene_mesh_to_mjcf [scale] [--view]" - ) - sys.exit(2) - scene = Path(args[0]) - robot = Path(args[1]) - scale = float(args[2]) if len(args) >= 3 else 0.05 - align = SceneMeshAlignment(scale=scale) - wrapper = bake_scene_mjcf(scene, robot, alignment=align) - print(f"wrapper: {wrapper}") + """``python -m dimos.simulation.mujoco.scene_mesh_to_mjcf [opts]``. - import mujoco # type: ignore[import-untyped] + Bake (or load from cache), optionally launch the MuJoCo viewer. + """ + p = argparse.ArgumentParser( + prog="python -m dimos.simulation.mujoco.scene_mesh_to_mjcf", + description="Bake a USD/GLB/OBJ scene into an MJCF wrapping a robot MJCF.", + ) + p.add_argument("scene", type=Path, help="scene mesh path (.usda, .usdz, .glb, ...)") + p.add_argument("robot", type=Path, help="robot MJCF path") + p.add_argument( + "--scale", + type=float, + default=1.0, + help="multiplicative scale (use 0.01 for UE / centimeter sources). Default 1.0.", + ) + p.add_argument( + "--no-y-up", + action="store_true", + help="source is already Z-up (UE exports with metersPerUnit=0.01 and " + "upAxis=Z). Default assumes Y-up source (Blender, glTF, Apple USDZ).", + ) + p.add_argument( + "--collision-spec", + type=Path, + default=None, + help="path to a collision-spec sidecar JSON. Default auto-discovers " + "``.collision.json`` next to the source.", + ) + p.add_argument( + "--meshdir", + type=Path, + default=None, + help="override meshdir for the robot's relative " + "lookups. Default: robot MJCF's parent directory.", + ) + p.add_argument( + "--visual", + action="store_true", + help="emit visual passthrough meshes (group 2). Off by default -- " + "saves disk and render cost, but the MuJoCo viewer only shows " + "collision shapes without it.", + ) + p.add_argument( + "--rebake", + action="store_true", + help="ignore cached .mjb and wrapper.xml; do a full re-bake.", + ) + p.add_argument( + "--view", + action="store_true", + help="launch the MuJoCo native viewer after baking (blocks).", + ) + args = p.parse_args() - model = mujoco.MjModel.from_xml_path(str(wrapper)) + align = SceneMeshAlignment(scale=args.scale, y_up=not args.no_y_up) + spec = ( + CollisionSpec.from_json(args.collision_spec) + if args.collision_spec is not None + else CollisionSpec.auto_discover(args.scene) + ) + + model, wrapper = load_or_bake( + scene_mesh_path=args.scene, + robot_mjcf_path=args.robot, + alignment=align, + meshdir=args.meshdir, + collision_spec=spec, + include_visual_mesh=args.visual, + rebake=args.rebake, + ) + print(f"wrapper: {wrapper}") print(f"loaded: {model.nbody} bodies, {model.ngeom} geoms, {model.nmesh} meshes") print(f"joints: {model.njnt}, dof: {model.nv}") - if view: + if args.view: import mujoco.viewer # type: ignore[import-untyped] viewer: Any = mujoco.viewer - # ``launch`` runs MuJoCo's interactive viewer with its own # internal physics loop. Blocks until the user closes it. # Press F1 in the viewer for the keyboard cheatsheet; ``Tab`` # toggles the rendering panel where you can switch geom groups - # (group 3 = our scene collision hulls, group 1 = robot - # visual mesh, group 0 = robot collision mesh). + # (group 3 = scene collision, group 2 = visual passthrough, + # group 1 = robot visual, group 0 = robot collision). print("\nlaunching MuJoCo viewer (press Esc / close window to exit)") viewer.launch(model) @@ -494,4 +922,4 @@ def cli_main() -> None: cli_main() -__all__ = ["bake_scene_mjcf"] +__all__ = ["bake_scene_mjcf", "load_or_bake"] diff --git a/pyproject.toml b/pyproject.toml index 2b96620b00..e4b345128f 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -257,6 +257,7 @@ sim = [ "trimesh", "usd-core>=24.0", "vhacdx", + "coacd>=1.0.11", # CoACD decomposer for scene_mesh_to_mjcf bake ] navigation = [ diff --git a/uv.lock b/uv.lock index 4e53de9e5b..d367f57ebc 100644 --- a/uv.lock +++ b/uv.lock @@ -1138,6 +1138,21 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/56/f3/4da9d5c5308ef2019ab65a8a9f519ac95004446902d01e859f9ac6b8cdd6/cmeel_zlib-1.3.1-0-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:1e36ac8dccca22ff1f6e4df428ae5597f6288d9e6f85b08c9b767dc63e90fb55", size = 285662, upload-time = "2025-02-11T12:20:37.298Z" }, ] +[[package]] +name = "coacd" +version = "1.0.11" +source = { registry = "https://pypi.org/simple" } +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'" }, +] +wheels = [ + { url = "https://files.pythonhosted.org/packages/1d/3b/434beab9e1754ca0ae3a619b383243dd85aa65d03a4dc7333c8296c97a92/coacd-1.0.11-cp39-abi3-macosx_11_0_arm64.whl", hash = "sha256:adbc58259a721cc5ede24cc8c2671a95e75a8a52dc1ee4d953d80d236b192da9", size = 3299264, upload-time = "2026-05-04T19:23:36.183Z" }, + { url = "https://files.pythonhosted.org/packages/cb/a7/06f63baa29198f681ba60848e3271cc625eddd61cd4e59071f56ffce9362/coacd-1.0.11-cp39-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e376fadb22790444c7253f0cee9104a1af01ec965488c1318e84e3b2dbf1e2a3", size = 2573832, upload-time = "2026-05-04T19:23:38.008Z" }, + { url = "https://files.pythonhosted.org/packages/0e/b4/057c78f7b16b87871cfcecc6febe70522e77a2a33f8788960377152c224d/coacd-1.0.11-cp39-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a60f700a52e5b40462e508c14bb756cd63ce7e6a95ff72ae0b1592be1dbb0106", size = 2640170, upload-time = "2026-05-04T19:23:39.322Z" }, + { url = "https://files.pythonhosted.org/packages/00/83/c50472ce98175fddd86d4aba861fea89f30350a5487880b3a81d34915a85/coacd-1.0.11-cp39-abi3-win_amd64.whl", hash = "sha256:4de22f70d1a3fa8c44698c8006a223fe5fb0ee84b76adecf3726cf2003e9145f", size = 1465079, upload-time = "2026-05-04T19:23:41.604Z" }, +] + [[package]] name = "coal" version = "3.0.2" @@ -1890,6 +1905,7 @@ all = [ { name = "anthropic" }, { name = "catkin-pkg" }, { name = "cerebras-cloud-sdk" }, + { name = "coacd" }, { name = "ctransformers" }, { name = "ctransformers", extra = ["cuda"], marker = "sys_platform != 'darwin'" }, { name = "cupy-cuda12x", marker = "platform_machine == 'x86_64'" }, @@ -2109,6 +2125,7 @@ psql = [ { name = "psycopg2-binary" }, ] sim = [ + { name = "coacd" }, { name = "mujoco" }, { name = "playground" }, { name = "pygame" }, @@ -2332,6 +2349,7 @@ requires-dist = [ { name = "bleak", specifier = ">=3.0.2" }, { name = "catkin-pkg", marker = "extra == 'misc'" }, { name = "cerebras-cloud-sdk", marker = "extra == 'misc'" }, + { name = "coacd", marker = "extra == 'sim'", specifier = ">=1.0.11" }, { name = "colorlog", specifier = "==6.9.0" }, { name = "cryptography", specifier = ">=46.0.5" }, { name = "ctransformers", marker = "extra == 'cpu'", specifier = "==0.2.27" }, From 2759e2bc2b411acfd8fb5b9576e18a9a8f416bf6 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 14 May 2026 02:06:52 -0700 Subject: [PATCH 25/30] Improve MuJoCo scene bake cache --- .../g1/blueprints/basic/g1_groot_wbc.py | 41 +++-- dimos/simulation/engines/mujoco_engine.py | 99 ++++++++-- dimos/simulation/mujoco/collision_spec.py | 167 ++++++++++++++++- dimos/simulation/mujoco/scene_mesh_to_mjcf.py | 169 ++++++++++++++---- .../simulation/mujoco/test_collision_spec.py | 130 ++++++++++++++ dimos/simulation/utils/xml_parser.py | 2 +- 6 files changed, 534 insertions(+), 74 deletions(-) create mode 100644 dimos/simulation/mujoco/test_collision_spec.py diff --git a/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py index 768448d2dc..c7e26b9915 100644 --- a/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py +++ b/dimos/robot/unitree/g1/blueprints/basic/g1_groot_wbc.py @@ -77,12 +77,13 @@ def _command_center_blueprints() -> list[Blueprint]: ] -_default_mjcf = Path("data/mujoco_sim/g1_gear_wbc.xml") -_default_scene_mesh = Path("data/dimos_office_mesh/dimos_office_mesh.glb") +_repo_root = Path(__file__).resolve().parents[6] +_default_mjcf = _repo_root / "data/mujoco_sim/g1_gear_wbc.xml" +_default_scene_mesh = _repo_root / "data/dimos_office_mesh/dimos_office_mesh.glb" _mjcf_path = os.environ.get("DIMOS_MJCF_PATH") or str(_default_mjcf) _mjcf_meshdir = os.environ.get("DIMOS_MJCF_MESHDIR") -if _mjcf_meshdir is None and Path(_mjcf_path) == _default_mjcf: - _mjcf_meshdir = "data/g1_urdf/meshes" +if _mjcf_meshdir is None and Path(_mjcf_path).expanduser().resolve() == _default_mjcf: + _mjcf_meshdir = str(_repo_root / "data/g1_urdf/meshes") _dof = int(os.environ.get("DIMOS_MUJOCO_DOF", "29")) _scene_mesh_path_override = os.environ.get("DIMOS_SCENE_MESH_PATH") or None _scene_mesh_path = _scene_mesh_path_override or ( @@ -97,6 +98,7 @@ def _command_center_blueprints() -> list[Blueprint]: _scene_mesh_translation = _env_xyz("DIMOS_SCENE_MESH_TRANSLATION", (0.0, 0.0, 0.0)) _scene_mesh_collision = _env_bool("DIMOS_SCENE_MESH_COLLISION", True) _scene_mesh_visual = _env_bool("DIMOS_SCENE_MESH_VISUAL", False) +_scene_mesh_bake = _env_bool("DIMOS_SCENE_MESH_BAKE", False) _enable_depth_cloud = _env_bool("DIMOS_ENABLE_DEPTH_CLOUD", False) _disable_lidar = _env_bool("DIMOS_DISABLE_LIDAR", False) @@ -104,22 +106,23 @@ def _command_center_blueprints() -> list[Blueprint]: if _scene_mesh_path and _scene_mesh_collision: try: from dimos.simulation.mujoco.mesh_scene import SceneMeshAlignment - from dimos.simulation.mujoco.scene_mesh_to_mjcf import bake_scene_mjcf - - _sim_mjcf_path = str( - bake_scene_mjcf( - scene_mesh_path=_scene_mesh_path, - robot_mjcf_path=_mjcf_path, - alignment=SceneMeshAlignment( - scale=_scene_mesh_scale, - rotation_zyx_deg=_scene_mesh_rotation, - translation=_scene_mesh_translation, - y_up=_scene_mesh_y_up, - ), - meshdir=_mjcf_meshdir, - include_visual_mesh=_scene_mesh_visual, - ) + from dimos.simulation.mujoco.scene_mesh_to_mjcf import load_or_bake + + _, _scene_wrapper = load_or_bake( + scene_mesh_path=_scene_mesh_path, + robot_mjcf_path=_mjcf_path, + alignment=SceneMeshAlignment( + scale=_scene_mesh_scale, + rotation_zyx_deg=_scene_mesh_rotation, + translation=_scene_mesh_translation, + y_up=_scene_mesh_y_up, + ), + meshdir=_mjcf_meshdir, + include_visual_mesh=_scene_mesh_visual, + rebake=_scene_mesh_bake, ) + _scene_mjb_path = _scene_wrapper.with_name("compiled.mjb") + _sim_mjcf_path = str(_scene_mjb_path if _scene_mjb_path.exists() else _scene_wrapper) except Exception as exc: logging.getLogger(__name__).warning( "Failed to bake scene mesh into MuJoCo; lidar will only see the base MJCF: %s", diff --git a/dimos/simulation/engines/mujoco_engine.py b/dimos/simulation/engines/mujoco_engine.py index f94f877819..4d1b44f1e0 100644 --- a/dimos/simulation/engines/mujoco_engine.py +++ b/dimos/simulation/engines/mujoco_engine.py @@ -107,6 +107,8 @@ def __init__( self._control_frequency = 1.0 / timestep if timestep > 0.0 else 100.0 self._root_free_qpos_adr: int | None = None self._root_free_qvel_adr: int | None = None + self._root_kinematic_pose: tuple[float, float, float] | None = None + self._scene_body_ids = self._collect_body_ids("dimos_scene") free_joint = int(mujoco.mjtJoint.mjJNT_FREE) # type: ignore[attr-defined] for joint_id in range(self._model.njnt): if self._model.jnt_type[joint_id] == free_joint: @@ -143,10 +145,13 @@ def _resolve_xml_path(self, config_path: Path) -> Path: resolved = config_path.expanduser() xml_path = resolved / "scene.xml" if resolved.is_dir() else resolved if not xml_path.exists(): - raise FileNotFoundError(f"MuJoCo XML not found: {xml_path}") + raise FileNotFoundError(f"MuJoCo model not found: {xml_path}") return xml_path def _load_model(self, xml_path: Path, *, meshdir: str | Path | None) -> mujoco.MjModel: + if xml_path.suffix.lower() == ".mjb": + return mujoco.MjModel.from_binary_path(str(xml_path)) + if meshdir is None: return mujoco.MjModel.from_xml_path(str(xml_path)) @@ -174,6 +179,46 @@ def _current_position(self, mapping: JointMapping) -> float: return float(self._data.actuator_length[mapping.actuator_id]) return 0.0 + def _collect_body_ids(self, root_name: str) -> set[int]: + root_id = mujoco.mj_name2id(self._model, mujoco.mjtObj.mjOBJ_BODY, root_name) + if root_id < 0: + return set() + body_ids = {root_id} + changed = True + while changed: + changed = False + for body_id in range(self._model.nbody): + parent_id = int(self._model.body_parentid[body_id]) + if parent_id in body_ids and body_id not in body_ids: + body_ids.add(body_id) + changed = True + return body_ids + + def _is_scene_geom(self, geom_id: int) -> bool: + if geom_id < 0 or not self._scene_body_ids: + return False + return int(self._model.geom_bodyid[geom_id]) in self._scene_body_ids + + def _has_blocking_scene_contact(self) -> bool: + """Return true for non-floor contacts between robot and baked scene.""" + if not self._scene_body_ids: + return False + for contact_idx in range(self._data.ncon): + contact = self._data.contact[contact_idx] + geom1 = int(contact.geom1) + geom2 = int(contact.geom2) + geom1_is_scene = self._is_scene_geom(geom1) + geom2_is_scene = self._is_scene_geom(geom2) + if geom1_is_scene == geom2_is_scene: + continue + if float(contact.dist) > 1e-4: + continue + normal = contact.frame[:3] + if abs(float(normal[2])) > 0.75: + continue + return True + return False + def _apply_control(self) -> None: with self._lock: if self._command_mode == "effort": @@ -489,7 +534,13 @@ def apply_root_twist( *, fixed_z: float | None = None, ) -> bool: - """Integrate planar velocity onto the first freejoint root.""" + """Integrate planar velocity onto the first freejoint root. + + The root is treated as kinematic once this method is used: we + maintain an internal desired x/y/yaw and write it back every tick. + That prevents contact impulses or gravity settling from slowly + walking the floating base when the commanded twist is zero. + """ qpos_adr = self._root_free_qpos_adr if qpos_adr is None: return False @@ -497,24 +548,48 @@ def apply_root_twist( dt = 1.0 / self._control_frequency with self._lock: qpos = self._data.qpos - qw, qx, qy, qz = qpos[qpos_adr + 3 : qpos_adr + 7] - yaw = math.atan2( - 2.0 * (qw * qz + qx * qy), - 1.0 - 2.0 * (qy * qy + qz * qz), - ) + if self._root_kinematic_pose is None: + qw, qx, qy, qz = qpos[qpos_adr + 3 : qpos_adr + 7] + yaw = math.atan2( + 2.0 * (qw * qz + qx * qy), + 1.0 - 2.0 * (qy * qy + qz * qz), + ) + self._root_kinematic_pose = ( + float(qpos[qpos_adr]), + float(qpos[qpos_adr + 1]), + yaw, + ) - qpos[qpos_adr] += (math.cos(yaw) * linear_x - math.sin(yaw) * linear_y) * dt - qpos[qpos_adr + 1] += (math.sin(yaw) * linear_x + math.cos(yaw) * linear_y) * dt + old_x, old_y, old_yaw = self._root_kinematic_pose + new_x = old_x + (math.cos(old_yaw) * linear_x - math.sin(old_yaw) * linear_y) * dt + new_y = old_y + (math.sin(old_yaw) * linear_x + math.cos(old_yaw) * linear_y) * dt + new_yaw = old_yaw + angular_z * dt + + qpos[qpos_adr] = new_x + qpos[qpos_adr + 1] = new_y if fixed_z is not None: qpos[qpos_adr + 2] = fixed_z - yaw += angular_z * dt qpos[qpos_adr + 3 : qpos_adr + 7] = [ - math.cos(yaw * 0.5), + math.cos(new_yaw * 0.5), 0.0, 0.0, - math.sin(yaw * 0.5), + math.sin(new_yaw * 0.5), ] + mujoco.mj_forward(self._model, self._data) + + if self._has_blocking_scene_contact(): + qpos[qpos_adr] = old_x + qpos[qpos_adr + 1] = old_y + qpos[qpos_adr + 3 : qpos_adr + 7] = [ + math.cos(old_yaw * 0.5), + 0.0, + 0.0, + math.sin(old_yaw * 0.5), + ] + mujoco.mj_forward(self._model, self._data) + else: + self._root_kinematic_pose = (new_x, new_y, new_yaw) qvel_adr = self._root_free_qvel_adr if qvel_adr is not None: diff --git a/dimos/simulation/mujoco/collision_spec.py b/dimos/simulation/mujoco/collision_spec.py index 9fa394feb1..96050461d4 100644 --- a/dimos/simulation/mujoco/collision_spec.py +++ b/dimos/simulation/mujoco/collision_spec.py @@ -119,6 +119,17 @@ class CollisionSpec: #: this (m³). Smaller furniture-scale prims use one hull regardless. shell_volume_m3: float = 2.0 + #: Preserve large non-rectangular sheet footprints with thin triangle + #: prisms. This helps moderate indoor scenes with angular floors, but + #: is disabled by ``bake_scene_mjcf`` for very large scenes unless + #: explicitly overridden. + enable_sheet_prisms: bool = True + + #: Scene-level guard used by ``bake_scene_mjcf``. Above this many + #: source prims, sheet prisms can explode the geom count; use sidecar + #: overrides for specific floors instead. + sheet_prism_max_scene_prims: int = 2500 + #: ``USD-path-glob -> override-dict``. See class docstring. prim_overrides: dict[str, dict] = field(default_factory=dict) @@ -136,6 +147,8 @@ def from_json(cls, path: Path | str) -> CollisionSpec: "coacd_threshold", "coacd_max_hulls", "shell_volume_m3", + "enable_sheet_prisms", + "sheet_prism_max_scene_prims", "prim_overrides", } kwargs = {k: v for k, v in raw.items() if k in known} @@ -280,6 +293,12 @@ def _quat_z_to(axis: np.ndarray) -> tuple[float, float, float, float]: #: axis at exactly 0. Clamping to 1 mm yields a valid geom that's still #: physically reasonable as a thin slab. _MIN_SIZE_M = 1e-3 +_SHEET_PRISM_THICKNESS_M = 0.03 +_SHEET_BOX_FILL_MIN = 0.85 +_SHEET_BOX_FILL_MAX = 1.15 +_HORIZONTAL_BOX_MAX_THICKNESS_M = 0.05 +_SHEET_PRISM_MIN_FOOTPRINT_AREA_M2 = 2.0 +_SHEET_PRISM_MAX_TRIANGLES = 1024 def _fit_aabb_box(vertices: np.ndarray) -> dict: @@ -363,7 +382,7 @@ def _fit_capsule(vertices: np.ndarray) -> dict: the *cylindrical* portion only; total length = 2*(half_h + r).""" cyl = _fit_cylinder(vertices) r, h = cyl["size"] - new_h = max(0.0, h - r) + new_h = max(float(h - r), _MIN_SIZE_M) vol = float(np.pi * r * r * 2.0 * new_h) + float((4.0 / 3.0) * np.pi * r**3) return { "type": "capsule", @@ -440,6 +459,120 @@ def _is_slab(extent: np.ndarray, aspect_ratio: float) -> bool: return bool((sorted_ext[2] / sorted_ext[0]) >= aspect_ratio) +def _sheet_footprint_stats( + vertices: np.ndarray, + triangles: np.ndarray, + thin_axis: int, +) -> tuple[float, float] | None: + """Return ``(projected_aabb_area, projected_triangle_fill)`` for a sheet.""" + axes = [i for i in range(3) if i != thin_axis] + projected = vertices[:, axes] + span = projected.max(axis=0) - projected.min(axis=0) + box_area = float(span[0] * span[1]) + if box_area < 1e-9: + return None + + tri = projected[triangles] + edge_a = tri[:, 1] - tri[:, 0] + edge_b = tri[:, 2] - tri[:, 0] + area = 0.5 * np.abs(edge_a[:, 0] * edge_b[:, 1] - edge_a[:, 1] * edge_b[:, 0]).sum() + fill = float(area / box_area) + return box_area, fill + + +def _is_boxlike_sheet( + vertices: np.ndarray, + triangles: np.ndarray, + thin_axis: int, +) -> bool: + """Whether a thin mesh roughly fills its projected bounding rectangle. + + A single primitive box is only acceptable when the source sheet's + projected triangle area is close to the projected AABB area. Low + ratios mean an L-shape / beam strip / holes; high ratios usually mean + overlapping, folded, or angled sheets inside one prim. + """ + stats = _sheet_footprint_stats(vertices, triangles, thin_axis) + if stats is None: + return False + _, fill = stats + return _SHEET_BOX_FILL_MIN <= fill <= _SHEET_BOX_FILL_MAX + + +def _should_emit_triangle_prisms( + vertices: np.ndarray, + triangles: np.ndarray, + thin_axis: int, +) -> bool: + """Use exact-ish triangle prisms only for large horizontal sheets. + + This avoids placing huge slabs over angular floors and roof strips, + without exploding tiny decorative meshes into thousands of geoms. + """ + if thin_axis != 2: + return False + if len(triangles) > _SHEET_PRISM_MAX_TRIANGLES: + return False + stats = _sheet_footprint_stats(vertices, triangles, thin_axis) + if stats is None: + return False + footprint_area, _ = stats + return footprint_area >= _SHEET_PRISM_MIN_FOOTPRINT_AREA_M2 + + +def _thin_sheet_hulls( + vertices: np.ndarray, + triangles: np.ndarray, + thickness: float = _SHEET_PRISM_THICKNESS_M, +) -> list[tuple[np.ndarray, np.ndarray]]: + """Represent a thin non-rectangular sheet as convex triangle prisms.""" + hulls: list[tuple[np.ndarray, np.ndarray]] = [] + faces = np.asarray( + [ + [0, 1, 2], + [5, 4, 3], + [0, 3, 4], + [0, 4, 1], + [1, 4, 5], + [1, 5, 2], + [2, 5, 3], + [2, 3, 0], + ], + dtype=np.int32, + ) + + for tri_idx in triangles: + tri = vertices[tri_idx].astype(np.float64) + if not np.isfinite(tri).all(): + continue + normal = np.cross(tri[1] - tri[0], tri[2] - tri[0]) + norm = float(np.linalg.norm(normal)) + if norm < 1e-9: + continue + offset = normal / norm * (thickness * 0.5) + prism = np.vstack((tri + offset, tri - offset)).astype(np.float32) + hulls.append((prism, faces)) + + return hulls + + +def _is_flat_horizontal_box(extent: np.ndarray, thin_axis: int) -> bool: + """Thin in world Z, broad in world X/Y, and flat enough to box safely. + + PCA boxes are unstable for nearly flat floors/ceilings: any small + triangulation asymmetry can rotate the OBB basis and turn a walkable + surface into a shallow ramp. For world-horizontal slabs, the AABB is + the physically safer collision approximation. + """ + if thin_axis != 2: + return False + xy_min = float(min(extent[0], extent[1])) + z_extent = float(extent[2]) + if xy_min < 1e-6: + return False + return z_extent <= _HORIZONTAL_BOX_MAX_THICKNESS_M + + # --------------------------------------------------------------------------- # # Dispatcher: per-prim decision # # --------------------------------------------------------------------------- # @@ -529,15 +662,35 @@ def decide_for_prim( # 4. From here on: kind == "auto". Generic heuristics first. - # 4a. Aspect-ratio: slab/beam → force OBB box (fill ratio may be + # 4a. Aspect-ratio: slab/beam → force box (fill ratio may be # marginal because of moulding/profile, but a box collision is - # the right physical answer for walls and slabs). + # the right physical answer for walls and slabs). Non-rectangular + # sheets are emitted as triangle prisms so we don't fill holes or + # angular roof/floor outlines with one huge invisible slab. if _is_slab(extent, spec.aspect_ratio_box): - fit = _fit_obb_box(vertices) + thin_axis = int(np.argmin(extent)) + if ( + spec.enable_sheet_prisms + and not _is_boxlike_sheet(vertices, triangles, thin_axis) + and _should_emit_triangle_prisms(vertices, triangles, thin_axis) + ): + hulls = _thin_sheet_hulls(vertices, triangles) + if hulls: + return PrimDecision( + mode="hulls", + hulls=hulls, + reason=f"thin-sheet:triangle-prisms({len(hulls)})", + friction=friction, + ) + + if _is_flat_horizontal_box(extent, thin_axis): + fit = _fit_aabb_box(vertices) + reason = "aspect-ratio:horizontal-slab" + else: + fit = _fit_obb_box(vertices) + reason = "aspect-ratio:slab" fit["fill_ratio"] = float("nan") - return PrimDecision( - mode="primitive", primitive=fit, reason="aspect-ratio:slab", friction=friction - ) + return PrimDecision(mode="primitive", primitive=fit, reason=reason, friction=friction) # 4b. Need hull volume for the rest. hull_vol = _hull_volume(vertices) diff --git a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py index fe1477cb7e..a3b45f7783 100644 --- a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -41,9 +41,11 @@ which substitutes the prim's convex hull when it isn't watertight, so the viewer renders solid geometry instead of see-through slabs. -Per-prim work is fanned across processes via ``ProcessPoolExecutor`` -(fork on macOS) since each prim's decision is independent and CoACD -calls dominate wall time. +Per-prim work is fanned across worker processes since each prim's +decision is independent and CoACD calls dominate wall time. Standalone +CLI bakes use forked processes; in an already-threaded DimOS runtime we +use ``forkserver`` so workers do not inherit the parent process's active +threads. Output is cached at ``~/.cache/dimos/scene_meshes//`` keyed on the SHA256 of (source mesh, robot MJCF, alignment, meshdir, sidecar @@ -59,7 +61,7 @@ import argparse from concurrent.futures import ProcessPoolExecutor, as_completed -from dataclasses import asdict, dataclass +from dataclasses import asdict, dataclass, replace import hashlib import multiprocessing import os @@ -100,6 +102,10 @@ + + + + {asset_meshes} @@ -164,7 +170,9 @@ # Bump when the bake pipeline's output format changes so old caches # invalidate on the next call. Increment for any change that could # affect MJCF emission (new geom kinds, rewritten visual policy, etc.). -_CACHE_SCHEMA_VERSION = "dispatcher-v2" +# This is only a local cache salt; it is not a persisted file format +# contract and old cache directories can safely stay on disk. +_CACHE_SCHEMA_VERSION = "dispatcher-v7" @dataclass @@ -182,6 +190,15 @@ class _BakeArtifacts: decision_reasons: dict[str, int] +def _resolve_existing_file(path: str | Path, label: str) -> Path: + resolved = Path(path).expanduser().resolve() + if not resolved.exists(): + raise FileNotFoundError(f"{label} not found: {resolved}") + if not resolved.is_file(): + raise ValueError(f"{label} must be a file, got: {resolved}") + return resolved + + def bake_scene_mjcf( scene_mesh_path: str | Path, robot_mjcf_path: str | Path, @@ -190,6 +207,7 @@ def bake_scene_mjcf( cache_root: Path | None = None, collision_spec: CollisionSpec | None = None, include_visual_mesh: bool = False, + rebake: bool = False, ) -> Path: """Convert ``scene_mesh_path`` to OBJs + MJCF wrapper around the robot. @@ -216,22 +234,19 @@ def bake_scene_mjcf( for visual debugging, but doubles disk usage. When ``True`` non-watertight prim meshes are substituted with their convex hull so they don't appear see-through. + rebake: ignore an existing ``wrapper.xml`` in the computed cache + directory and regenerate the scene collision geometry. Returns: Path to the wrapper MJCF. Pass to ``MujocoSimModule`` instead of the raw robot MJCF, or use :func:`load_or_bake` to also get an ``.mjb`` cache. """ - scene_mesh_path = Path(scene_mesh_path).expanduser().resolve() - robot_mjcf_path = Path(robot_mjcf_path).expanduser().resolve() + scene_mesh_path = _resolve_existing_file(scene_mesh_path, "scene mesh") + robot_mjcf_path = _resolve_existing_file(robot_mjcf_path, "robot MJCF") align = alignment or SceneMeshAlignment() spec = collision_spec or CollisionSpec.auto_discover(scene_mesh_path) - if not scene_mesh_path.exists(): - raise FileNotFoundError(f"scene mesh not found: {scene_mesh_path}") - if not robot_mjcf_path.exists(): - raise FileNotFoundError(f"robot MJCF not found: {robot_mjcf_path}") - meshdir = Path(meshdir).expanduser().resolve() if meshdir else robot_mjcf_path.parent cache_key = _cache_key( @@ -246,7 +261,7 @@ def bake_scene_mjcf( cache_dir = root / cache_key wrapper_path = cache_dir / "wrapper.xml" - if _cache_hit(wrapper_path): + if not rebake and _cache_hit(wrapper_path): logger.info(f"bake_scene_mjcf: cache hit at {cache_dir}") return wrapper_path @@ -255,6 +270,13 @@ def bake_scene_mjcf( logger.info(f"bake_scene_mjcf: loading + aligning {scene_mesh_path}") prims = load_scene_prims(scene_mesh_path, alignment=align) logger.info(f"bake_scene_mjcf: {len(prims)} prims to process") + if spec.enable_sheet_prisms and len(prims) > spec.sheet_prism_max_scene_prims: + logger.info( + "bake_scene_mjcf: disabling thin-sheet triangle prisms for " + f"{len(prims)}-prim scene; use a collision sidecar to opt in" + ) + spec = replace(spec, enable_sheet_prisms=False) + scene_center, scene_extent = _scene_bounds(prims) artifacts = _bake_prims( prims, @@ -288,6 +310,8 @@ def bake_scene_mjcf( robot_mjcf_path=robot_mjcf_path, asset_lines=artifacts.asset_lines, geom_lines=artifacts.geom_lines, + statistic_center=scene_center, + statistic_extent=scene_extent, ) return wrapper_path @@ -322,11 +346,14 @@ def load_or_bake( """ import mujoco # type: ignore[import-untyped] + scene_mesh_path = _resolve_existing_file(scene_mesh_path, "scene mesh") + robot_mjcf_path = _resolve_existing_file(robot_mjcf_path, "robot MJCF") + if not rebake: # Compute the cache key without baking, so we can probe for an # existing .mjb / wrapper.xml without doing any work. - sp = Path(scene_mesh_path).expanduser().resolve() - rp = Path(robot_mjcf_path).expanduser().resolve() + sp = scene_mesh_path + rp = robot_mjcf_path al = alignment or SceneMeshAlignment() sd = collision_spec or CollisionSpec.auto_discover(sp) md = Path(meshdir).expanduser().resolve() if meshdir else rp.parent @@ -336,7 +363,13 @@ def load_or_bake( mjb = cache_dir / "compiled.mjb" wrapper = cache_dir / "wrapper.xml" - if mjb.exists(): + wrapper_is_current = _cache_hit(wrapper) + + if ( + mjb.exists() + and wrapper_is_current + and mjb.stat().st_mtime_ns >= wrapper.stat().st_mtime_ns + ): logger.info(f"load_or_bake: loading compiled binary {mjb}") t0 = time.time() model = mujoco.MjModel.from_binary_path(str(mjb)) @@ -346,7 +379,7 @@ def load_or_bake( ) return model, wrapper - if wrapper.exists() and any(cache_dir.glob("*.obj")): + if wrapper_is_current and any(cache_dir.glob("*.obj")): logger.info(f"load_or_bake: wrapper cached, compiling XML -> .mjb at {wrapper}") t0 = time.time() model = mujoco.MjModel.from_xml_path(str(wrapper)) @@ -367,6 +400,7 @@ def load_or_bake( cache_root=cache_root, collision_spec=collision_spec, include_visual_mesh=include_visual_mesh, + rebake=rebake, ) logger.info(f"load_or_bake: compiling baked wrapper {wrapper}") t0 = time.time() @@ -421,7 +455,13 @@ def _file_signature(path: Path) -> str: def _cache_hit(wrapper_path: Path) -> bool: - return wrapper_path.exists() + if not wrapper_path.exists(): + return False + try: + text = wrapper_path.read_text() + except OSError: + return False + return " 1: + n_workers = min(n_workers, 8) + start_method = ( + "forkserver" if "forkserver" in multiprocessing.get_all_start_methods() else "spawn" + ) + else: + start_method = "fork" + logger.info( + f"_bake_prims: fanning {len(prims)} prims across " + f"{n_workers} workers ({start_method})" + ) t0 = time.time() - with ProcessPoolExecutor(max_workers=n_workers, mp_context=mp_ctx) as ex: + mp_ctx = multiprocessing.get_context(start_method) + executor = ProcessPoolExecutor(max_workers=n_workers, mp_context=mp_ctx) + + progress_every = 25 if len(prims) <= 500 else 250 + with executor as ex: futures = [ex.submit(_process_one_prim, item) for item in work_items] done = 0 for fut in as_completed(futures): @@ -567,7 +616,7 @@ def _bake_prims( n_visuals += counters["visuals"] n_degenerate += counters["degenerate"] done += 1 - if done % 250 == 0 or done == len(prims): + if done % progress_every == 0 or done == len(prims): elapsed = time.time() - t0 eta = elapsed * (len(prims) - done) / max(done, 1) logger.info( @@ -590,6 +639,13 @@ def _bake_prims( ) +def _native_thread_count() -> int: + try: + return len(os.listdir("/proc/self/task")) + except OSError: + return 1 + + # --------------------------------------------------------------------------- # # Geom emission helpers # # --------------------------------------------------------------------------- # @@ -744,6 +800,37 @@ def _fmt_vec(values: np.ndarray) -> str: return " ".join(f"{float(v):.9g}" for v in values) +def _scene_bounds(prims: list[Any]) -> tuple[np.ndarray, float]: + """Return a viewer-friendly center and extent for the aligned scene. + + MuJoCo's viewer uses ``statistic.center`` / ``statistic.extent`` for + camera framing and clipping. The included robot MJCF's defaults are + much too small for baked building-scale scenes, so wrappers need to + advertise the scene bounds explicitly. + """ + mins: list[np.ndarray] = [] + maxs: list[np.ndarray] = [] + for prim in prims: + vertices = np.asarray(prim.vertices, dtype=np.float64) + if vertices.ndim != 2 or vertices.shape[1] != 3 or len(vertices) == 0: + continue + finite = vertices[np.isfinite(vertices).all(axis=1)] + if len(finite) == 0: + continue + mins.append(finite.min(axis=0)) + maxs.append(finite.max(axis=0)) + + if not mins: + return np.zeros(3, dtype=np.float64), 1.0 + + scene_min = np.min(np.vstack(mins), axis=0) + scene_max = np.max(np.vstack(maxs), axis=0) + center = (scene_min + scene_max) * 0.5 + diagonal = scene_max - scene_min + extent = max(float(np.linalg.norm(diagonal) * 0.5 * 1.1), 1.0) + return center, extent + + # --------------------------------------------------------------------------- # # OBJ I/O # # --------------------------------------------------------------------------- # @@ -816,11 +903,17 @@ def _write_wrapper( robot_mjcf_path: Path, asset_lines: list[str], geom_lines: list[str], + statistic_center: np.ndarray, + statistic_extent: float, ) -> None: + visual_zfar = max(float(statistic_extent) * 20.0, 10000.0) wrapper_xml = _WRAPPER_TEMPLATE.format( model_name=f"robot_with_scene_{cache_key}", meshdir=str(meshdir), robot_mjcf_abs=str(robot_mjcf_path), + statistic_center=_fmt_vec(statistic_center), + statistic_extent=f"{float(statistic_extent):.9g}", + visual_zfar=f"{visual_zfar:.9g}", asset_meshes="\n".join(asset_lines), scene_geoms="\n".join(geom_lines), ) @@ -884,16 +977,22 @@ def cli_main() -> None: ) args = p.parse_args() + try: + scene_path = _resolve_existing_file(args.scene, "scene mesh") + robot_path = _resolve_existing_file(args.robot, "robot MJCF") + except (FileNotFoundError, ValueError) as exc: + p.error(str(exc)) + align = SceneMeshAlignment(scale=args.scale, y_up=not args.no_y_up) spec = ( CollisionSpec.from_json(args.collision_spec) if args.collision_spec is not None - else CollisionSpec.auto_discover(args.scene) + else CollisionSpec.auto_discover(scene_path) ) model, wrapper = load_or_bake( - scene_mesh_path=args.scene, - robot_mjcf_path=args.robot, + scene_mesh_path=scene_path, + robot_mjcf_path=robot_path, alignment=align, meshdir=args.meshdir, collision_spec=spec, diff --git a/dimos/simulation/mujoco/test_collision_spec.py b/dimos/simulation/mujoco/test_collision_spec.py new file mode 100644 index 0000000000..0bf46478c0 --- /dev/null +++ b/dimos/simulation/mujoco/test_collision_spec.py @@ -0,0 +1,130 @@ +# 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 dimos.simulation.mujoco.collision_spec import CollisionSpec, decide_for_prim + + +def test_rectangular_flat_sheet_stays_single_horizontal_box() -> None: + vertices = np.asarray( + [ + [0.0, 0.0, 0.0], + [2.0, 0.0, 0.0], + [2.0, 2.0, 0.0], + [0.0, 2.0, 0.0], + ], + dtype=np.float64, + ) + triangles = np.asarray([[0, 1, 2], [0, 2, 3]], dtype=np.int32) + + decision = decide_for_prim(vertices, triangles, "flat_rect", CollisionSpec()) + + assert decision.mode == "primitive" + assert decision.reason == "aspect-ratio:horizontal-slab" + assert decision.primitive is not None + assert decision.primitive["quat"] == (1.0, 0.0, 0.0, 0.0) + + +def test_large_non_rectangular_flat_sheet_uses_triangle_prisms() -> None: + vertices = np.asarray( + [ + [0.0, 0.0, 0.0], + [2.0, 0.0, 0.0], + [2.0, 1.0, 0.0], + [0.0, 1.0, 0.0], + [1.0, 1.0, 0.0], + [1.0, 2.0, 0.0], + [0.0, 2.0, 0.0], + ], + dtype=np.float64, + ) + triangles = np.asarray( + [ + [0, 1, 2], + [0, 2, 3], + [3, 4, 5], + [3, 5, 6], + ], + dtype=np.int32, + ) + + decision = decide_for_prim(vertices, triangles, "flat_l_shape", CollisionSpec()) + + assert decision.mode == "hulls" + assert decision.reason == "thin-sheet:triangle-prisms(4)" + assert len(decision.hulls) == 4 + + +def test_sheet_prisms_can_be_disabled() -> None: + vertices = np.asarray( + [ + [0.0, 0.0, 0.0], + [2.0, 0.0, 0.0], + [2.0, 1.0, 0.0], + [0.0, 1.0, 0.0], + [1.0, 1.0, 0.0], + [1.0, 2.0, 0.0], + [0.0, 2.0, 0.0], + ], + dtype=np.float64, + ) + triangles = np.asarray( + [ + [0, 1, 2], + [0, 2, 3], + [3, 4, 5], + [3, 5, 6], + ], + dtype=np.int32, + ) + + decision = decide_for_prim( + vertices, + triangles, + "flat_l_shape", + CollisionSpec(enable_sheet_prisms=False), + ) + + assert decision.mode == "primitive" + assert decision.reason == "aspect-ratio:horizontal-slab" + + +def test_small_non_rectangular_flat_sheet_stays_single_horizontal_box() -> None: + vertices = np.asarray( + [ + [0.0, 0.0, 0.0], + [1.0, 0.0, 0.0], + [1.0, 0.5, 0.0], + [0.0, 0.5, 0.0], + [0.5, 0.5, 0.0], + [0.5, 1.0, 0.0], + [0.0, 1.0, 0.0], + ], + dtype=np.float64, + ) + triangles = np.asarray( + [ + [0, 1, 2], + [0, 2, 3], + [3, 4, 5], + [3, 5, 6], + ], + dtype=np.int32, + ) + + decision = decide_for_prim(vertices, triangles, "small_flat_l_shape", CollisionSpec()) + + assert decision.mode == "primitive" + assert decision.reason == "aspect-ratio:horizontal-slab" diff --git a/dimos/simulation/utils/xml_parser.py b/dimos/simulation/utils/xml_parser.py index 052657ea95..3a4362cf4e 100644 --- a/dimos/simulation/utils/xml_parser.py +++ b/dimos/simulation/utils/xml_parser.py @@ -45,7 +45,7 @@ class _ActuatorSpec: def build_joint_mappings(xml_path: Path, model: mujoco.MjModel) -> list[JointMapping]: - specs = _parse_actuator_specs(xml_path) + specs = _parse_actuator_specs(xml_path) if xml_path.suffix.lower() != ".mjb" else [] if specs: return _build_joint_mappings_from_specs(specs, model) if int(model.nu) > 0: From 35ba04a79d667e69c0f0d5f6acac5378293032e5 Mon Sep 17 00:00:00 2001 From: "autofix-ci[bot]" <114827586+autofix-ci[bot]@users.noreply.github.com> Date: Thu, 14 May 2026 09:07:37 +0000 Subject: [PATCH 26/30] [autofix.ci] apply automated fixes --- dimos/simulation/mujoco/scene_mesh_to_mjcf.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py index a3b45f7783..2b34801471 100644 --- a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -590,8 +590,7 @@ def _bake_prims( else: start_method = "fork" logger.info( - f"_bake_prims: fanning {len(prims)} prims across " - f"{n_workers} workers ({start_method})" + f"_bake_prims: fanning {len(prims)} prims across {n_workers} workers ({start_method})" ) t0 = time.time() From cb98e845b27c7976ebaa2ae120ca7452a472ce55 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 14 May 2026 02:51:18 -0700 Subject: [PATCH 27/30] Fix MuJoCo scene type checks --- dimos/simulation/engines/mujoco_engine.py | 12 ++++- dimos/simulation/mujoco/collision_spec.py | 47 ++++++++++--------- dimos/simulation/mujoco/scene_mesh_to_mjcf.py | 35 ++++++++++---- 3 files changed, 62 insertions(+), 32 deletions(-) diff --git a/dimos/simulation/engines/mujoco_engine.py b/dimos/simulation/engines/mujoco_engine.py index 4d1b44f1e0..c8027ed091 100644 --- a/dimos/simulation/engines/mujoco_engine.py +++ b/dimos/simulation/engines/mujoco_engine.py @@ -22,7 +22,7 @@ from pathlib import Path import threading import time -from typing import TYPE_CHECKING +from typing import TYPE_CHECKING, cast import xml.etree.ElementTree as ET import mujoco @@ -150,7 +150,7 @@ def _resolve_xml_path(self, config_path: Path) -> Path: def _load_model(self, xml_path: Path, *, meshdir: str | Path | None) -> mujoco.MjModel: if xml_path.suffix.lower() == ".mjb": - return mujoco.MjModel.from_binary_path(str(xml_path)) + return self._load_binary_model(xml_path) if meshdir is None: return mujoco.MjModel.from_xml_path(str(xml_path)) @@ -167,6 +167,14 @@ def _load_model(self, xml_path: Path, *, meshdir: str | Path | None) -> mujoco.M include.set("file", str((xml_path.parent / include_file).resolve())) return mujoco.MjModel.from_xml_string(ET.tostring(root, encoding="unicode")) + @staticmethod + def _load_binary_model(model_path: Path) -> mujoco.MjModel: + load_binary_model = cast( + Callable[[str], mujoco.MjModel], + getattr(mujoco.MjModel, "from_binary_path"), + ) + return load_binary_model(str(model_path)) + def _current_position(self, mapping: JointMapping) -> float: if mapping.joint_id is not None and mapping.qpos_adr is not None: return float(self._data.qpos[mapping.qpos_adr]) diff --git a/dimos/simulation/mujoco/collision_spec.py b/dimos/simulation/mujoco/collision_spec.py index 96050461d4..1b04c222d8 100644 --- a/dimos/simulation/mujoco/collision_spec.py +++ b/dimos/simulation/mujoco/collision_spec.py @@ -41,17 +41,22 @@ from __future__ import annotations +from typing import Any, Literal + from dataclasses import dataclass, field import fnmatch import json -import logging from pathlib import Path -from typing import Literal import numpy as np from scipy.spatial import ConvexHull, QhullError # type: ignore[import-untyped] -logger = logging.getLogger(__name__) +from dimos.utils.logging_config import setup_logger + +logger = setup_logger() + +PrimitiveFit = dict[str, Any] +OverrideConfig = dict[str, Any] # --------------------------------------------------------------------------- # @@ -131,7 +136,7 @@ class CollisionSpec: sheet_prism_max_scene_prims: int = 2500 #: ``USD-path-glob -> override-dict``. See class docstring. - prim_overrides: dict[str, dict] = field(default_factory=dict) + prim_overrides: dict[str, OverrideConfig] = field(default_factory=dict) @classmethod def from_json(cls, path: Path | str) -> CollisionSpec: @@ -165,7 +170,7 @@ def auto_discover(cls, scene_path: Path | str) -> CollisionSpec: return cls.from_json(sidecar) return cls() - def resolve(self, prim_path: str) -> dict: + def resolve(self, prim_path: str) -> OverrideConfig: """Find the matching override for ``prim_path`` (USD path). Returns a dict with at least ``"type"``. Falls back to @@ -301,7 +306,7 @@ def _quat_z_to(axis: np.ndarray) -> tuple[float, float, float, float]: _SHEET_PRISM_MAX_TRIANGLES = 1024 -def _fit_aabb_box(vertices: np.ndarray) -> dict: +def _fit_aabb_box(vertices: np.ndarray) -> PrimitiveFit: """Axis-aligned bounding box. Identity quat.""" mn, mx = vertices.min(0), vertices.max(0) half_ext = np.maximum((mx - mn) / 2.0, _MIN_SIZE_M) @@ -315,7 +320,7 @@ def _fit_aabb_box(vertices: np.ndarray) -> dict: } -def _fit_obb_box(vertices: np.ndarray) -> dict: +def _fit_obb_box(vertices: np.ndarray) -> PrimitiveFit: """Oriented bounding box via PCA. Tighter than AABB when the prim is rotated relative to world axes (most UE props are world-aligned, so OBB ≈ AABB, but rotated assets benefit).""" @@ -340,7 +345,7 @@ def _fit_obb_box(vertices: np.ndarray) -> dict: } -def _fit_sphere(vertices: np.ndarray) -> dict: +def _fit_sphere(vertices: np.ndarray) -> PrimitiveFit: """Centroid + farthest-vertex. Looser than Welzl/Ritter but fine for fill-ratio comparison.""" centroid = vertices.mean(0) @@ -354,7 +359,7 @@ def _fit_sphere(vertices: np.ndarray) -> dict: } -def _fit_cylinder(vertices: np.ndarray) -> dict: +def _fit_cylinder(vertices: np.ndarray) -> PrimitiveFit: """Cylinder along PCA principal axis.""" centroid = vertices.mean(0) centered = vertices - centroid @@ -377,7 +382,7 @@ def _fit_cylinder(vertices: np.ndarray) -> dict: } -def _fit_capsule(vertices: np.ndarray) -> dict: +def _fit_capsule(vertices: np.ndarray) -> PrimitiveFit: """Capsule along PCA principal axis. MuJoCo capsule half-height is the *cylindrical* portion only; total length = 2*(half_h + r).""" cyl = _fit_cylinder(vertices) @@ -416,7 +421,7 @@ def _best_primitive_fit( vertices: np.ndarray, hull_vol: float, candidates: tuple[str, ...] = ("box", "cylinder", "sphere", "capsule"), -) -> dict | None: +) -> PrimitiveFit | None: """Try every primitive in ``candidates``; return the one with the highest fill ratio. Returns ``None`` if no fit succeeds (e.g. < 4 points).""" @@ -426,7 +431,7 @@ def _best_primitive_fit( "cylinder": _fit_cylinder, "capsule": _fit_capsule, } - fits: list[dict] = [] + fits: list[PrimitiveFit] = [] for kind in candidates: try: f = fitters[kind](vertices) @@ -590,7 +595,7 @@ class PrimDecision: #: For ``"primitive"``: the fit dict (``type``, ``size``, ``pos``, #: ``quat``, ``volume``, ``fill_ratio``). - primitive: dict | None = None + primitive: PrimitiveFit | None = None #: For ``"hulls"``: list of ``(vertices, triangles)`` ready to write. hulls: list[tuple[np.ndarray, np.ndarray]] = field(default_factory=list) @@ -698,15 +703,15 @@ def decide_for_prim( return PrimDecision(mode="skip", reason="degenerate (qhull rejected)", friction=friction) # 4c. Try primitive auto-fit. - fit = _best_primitive_fit(vertices, hull_vol) - if fit is not None and 0.0 < fit["fill_ratio"] <= 1.5: + auto_fit = _best_primitive_fit(vertices, hull_vol) + if auto_fit is not None and 0.0 < auto_fit["fill_ratio"] <= 1.5: # fill_ratio > 1 happens for non-closed hulls; cap to keep this # finite when reporting. Accept if within tolerance. - if fit["fill_ratio"] >= spec.fill_threshold: + if auto_fit["fill_ratio"] >= spec.fill_threshold: return PrimDecision( mode="primitive", - primitive=fit, - reason=f"auto:{fit['type']}({fit['fill_ratio']:.2f})", + primitive=auto_fit, + reason=f"auto:{auto_fit['type']}({auto_fit['fill_ratio']:.2f})", friction=friction, ) @@ -748,8 +753,8 @@ def decide_for_prim( def _resolve_explicit_primitive( vertices: np.ndarray, kind: str, - override: dict, -) -> dict: + override: OverrideConfig, +) -> PrimitiveFit: """Build a primitive fit dict from a sidecar override. If the override supplies ``size`` (and optionally ``pos`` / ``quat``), @@ -800,7 +805,7 @@ def _coacd_decompose( CoACD is imported lazily — it ships its own C library and we don't want every import of ``collision_spec`` to pay that cost. """ - import coacd # type: ignore[import-untyped] + import coacd # type: ignore[import-not-found, import-untyped] # CoACD's C lib prints a lot per invocation; quiet it once per process. if not getattr(_coacd_decompose, "_silenced", False): diff --git a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py index 2b34801471..c8783dcdaf 100644 --- a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -60,6 +60,7 @@ from __future__ import annotations import argparse +from collections.abc import Callable from concurrent.futures import ProcessPoolExecutor, as_completed from dataclasses import asdict, dataclass, replace import hashlib @@ -67,7 +68,7 @@ import os from pathlib import Path import time -from typing import Any +from typing import Any, cast import numpy as np import open3d as o3d # type: ignore[import-untyped] @@ -76,7 +77,11 @@ CollisionSpec, decide_for_prim, ) -from dimos.simulation.mujoco.mesh_scene import SceneMeshAlignment, load_scene_prims +from dimos.simulation.mujoco.mesh_scene import ( + SceneMeshAlignment, + ScenePrimMesh, + load_scene_prims, +) from dimos.utils.logging_config import setup_logger logger = setup_logger() @@ -348,6 +353,14 @@ def load_or_bake( scene_mesh_path = _resolve_existing_file(scene_mesh_path, "scene mesh") robot_mjcf_path = _resolve_existing_file(robot_mjcf_path, "robot MJCF") + load_binary_model = cast( + Callable[[str], Any], + getattr(mujoco.MjModel, "from_binary_path"), + ) + save_model = cast( + Callable[[Any, str], None], + getattr(mujoco, "mj_saveModel"), + ) if not rebake: # Compute the cache key without baking, so we can probe for an @@ -372,7 +385,7 @@ def load_or_bake( ): logger.info(f"load_or_bake: loading compiled binary {mjb}") t0 = time.time() - model = mujoco.MjModel.from_binary_path(str(mjb)) + model = load_binary_model(str(mjb)) logger.info( f" loaded in {time.time() - t0:.1f}s " f"(nbody={model.nbody} ngeom={model.ngeom} nmesh={model.nmesh})" @@ -387,7 +400,7 @@ def load_or_bake( f" compiled in {time.time() - t0:.1f}s " f"(nbody={model.nbody} ngeom={model.ngeom} nmesh={model.nmesh})" ) - mujoco.mj_saveModel(model, str(mjb)) + save_model(model, str(mjb)) logger.info(f" saved compiled binary: {mjb} ({mjb.stat().st_size / 1e6:.1f} MB)") return model, wrapper @@ -410,7 +423,7 @@ def load_or_bake( f"(nbody={model.nbody} ngeom={model.ngeom} nmesh={model.nmesh})" ) mjb = wrapper.with_name("compiled.mjb") - mujoco.mj_saveModel(model, str(mjb)) + save_model(model, str(mjb)) logger.info(f" saved compiled binary: {mjb} ({mjb.stat().st_size / 1e6:.1f} MB)") return model, wrapper @@ -470,7 +483,7 @@ def _cache_hit(wrapper_path: Path) -> bool: def _process_one_prim( - args: tuple[object, Path, CollisionSpec, bool], + args: tuple[ScenePrimMesh, Path, CollisionSpec, bool], ) -> tuple[list[str], list[str], str, str, dict[str, int]]: """Worker entry-point -- must be picklable. @@ -556,7 +569,7 @@ def _process_one_prim( def _bake_prims( - prims: list[Any], + prims: list[ScenePrimMesh], cache_dir: Path, *, spec: CollisionSpec, @@ -650,7 +663,11 @@ def _native_thread_count() -> int: # --------------------------------------------------------------------------- # -def _emit_primitive_geom(prim_name: str, fit: dict | None, friction_attr: str) -> str | None: +def _emit_primitive_geom( + prim_name: str, + fit: dict[str, Any] | None, + friction_attr: str, +) -> str | None: """Render one ``PrimDecision.primitive`` dict to MJCF text. Returns ``None`` if ``fit`` is missing required fields (defensive -- @@ -799,7 +816,7 @@ def _fmt_vec(values: np.ndarray) -> str: return " ".join(f"{float(v):.9g}" for v in values) -def _scene_bounds(prims: list[Any]) -> tuple[np.ndarray, float]: +def _scene_bounds(prims: list[ScenePrimMesh]) -> tuple[np.ndarray, float]: """Return a viewer-friendly center and extent for the aligned scene. MuJoCo's viewer uses ``statistic.center`` / ``statistic.extent`` for From 641f7daa51650aeeda36980bec2b2502e6c50488 Mon Sep 17 00:00:00 2001 From: "autofix-ci[bot]" <114827586+autofix-ci[bot]@users.noreply.github.com> Date: Thu, 14 May 2026 09:52:45 +0000 Subject: [PATCH 28/30] [autofix.ci] apply automated fixes --- dimos/simulation/engines/mujoco_engine.py | 4 ++-- dimos/simulation/mujoco/collision_spec.py | 3 +-- dimos/simulation/mujoco/scene_mesh_to_mjcf.py | 8 ++++---- 3 files changed, 7 insertions(+), 8 deletions(-) diff --git a/dimos/simulation/engines/mujoco_engine.py b/dimos/simulation/engines/mujoco_engine.py index c8027ed091..9bc80e672f 100644 --- a/dimos/simulation/engines/mujoco_engine.py +++ b/dimos/simulation/engines/mujoco_engine.py @@ -170,8 +170,8 @@ def _load_model(self, xml_path: Path, *, meshdir: str | Path | None) -> mujoco.M @staticmethod def _load_binary_model(model_path: Path) -> mujoco.MjModel: load_binary_model = cast( - Callable[[str], mujoco.MjModel], - getattr(mujoco.MjModel, "from_binary_path"), + "Callable[[str], mujoco.MjModel]", + mujoco.MjModel.from_binary_path, ) return load_binary_model(str(model_path)) diff --git a/dimos/simulation/mujoco/collision_spec.py b/dimos/simulation/mujoco/collision_spec.py index 1b04c222d8..fb870328e3 100644 --- a/dimos/simulation/mujoco/collision_spec.py +++ b/dimos/simulation/mujoco/collision_spec.py @@ -41,12 +41,11 @@ from __future__ import annotations -from typing import Any, Literal - from dataclasses import dataclass, field import fnmatch import json from pathlib import Path +from typing import Any, Literal import numpy as np from scipy.spatial import ConvexHull, QhullError # type: ignore[import-untyped] diff --git a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py index c8783dcdaf..8ac4424504 100644 --- a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -354,12 +354,12 @@ def load_or_bake( scene_mesh_path = _resolve_existing_file(scene_mesh_path, "scene mesh") robot_mjcf_path = _resolve_existing_file(robot_mjcf_path, "robot MJCF") load_binary_model = cast( - Callable[[str], Any], - getattr(mujoco.MjModel, "from_binary_path"), + "Callable[[str], Any]", + mujoco.MjModel.from_binary_path, ) save_model = cast( - Callable[[Any, str], None], - getattr(mujoco, "mj_saveModel"), + "Callable[[Any, str], None]", + mujoco.mj_saveModel, ) if not rebake: From 4d0e69b029e72cbf39899013ac819c8e5e0ff520 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 14 May 2026 02:57:22 -0700 Subject: [PATCH 29/30] Prevent MuJoCo binary API autofix --- dimos/simulation/engines/mujoco_engine.py | 3 ++- dimos/simulation/mujoco/scene_mesh_to_mjcf.py | 6 ++++-- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/dimos/simulation/engines/mujoco_engine.py b/dimos/simulation/engines/mujoco_engine.py index 9bc80e672f..5bc24a26fa 100644 --- a/dimos/simulation/engines/mujoco_engine.py +++ b/dimos/simulation/engines/mujoco_engine.py @@ -42,6 +42,7 @@ # Step hook signature: called with the engine instance inside the sim thread. StepHook = Callable[["MujocoEngine"], None] +_MUJOCO_FROM_BINARY_PATH = "from_binary_path" @dataclass @@ -171,7 +172,7 @@ def _load_model(self, xml_path: Path, *, meshdir: str | Path | None) -> mujoco.M def _load_binary_model(model_path: Path) -> mujoco.MjModel: load_binary_model = cast( "Callable[[str], mujoco.MjModel]", - mujoco.MjModel.from_binary_path, + getattr(mujoco.MjModel, _MUJOCO_FROM_BINARY_PATH), ) return load_binary_model(str(model_path)) diff --git a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py index 8ac4424504..0dbab0008c 100644 --- a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -88,6 +88,8 @@ CACHE_DIR = Path.home() / ".cache" / "dimos" / "scene_meshes" +_MUJOCO_FROM_BINARY_PATH = "from_binary_path" +_MUJOCO_SAVE_MODEL = "mj_saveModel" # ```` comes BEFORE ```` so the wrapper's absolute @@ -355,11 +357,11 @@ def load_or_bake( robot_mjcf_path = _resolve_existing_file(robot_mjcf_path, "robot MJCF") load_binary_model = cast( "Callable[[str], Any]", - mujoco.MjModel.from_binary_path, + getattr(mujoco.MjModel, _MUJOCO_FROM_BINARY_PATH), ) save_model = cast( "Callable[[Any, str], None]", - mujoco.mj_saveModel, + getattr(mujoco, _MUJOCO_SAVE_MODEL), ) if not rebake: From bc5e8d9ce2e85519e624914bd848a1734beb3b96 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 14 May 2026 16:01:36 -0700 Subject: [PATCH 30/30] Expand USD point instancers in scene bake --- dimos/simulation/mujoco/mesh_scene.py | 262 ++++++++++++++++-- dimos/simulation/mujoco/scene_mesh_to_mjcf.py | 2 +- dimos/simulation/mujoco/test_mesh_scene.py | 63 +++++ 3 files changed, 297 insertions(+), 30 deletions(-) create mode 100644 dimos/simulation/mujoco/test_mesh_scene.py diff --git a/dimos/simulation/mujoco/mesh_scene.py b/dimos/simulation/mujoco/mesh_scene.py index dc15adff68..cf186ddf22 100644 --- a/dimos/simulation/mujoco/mesh_scene.py +++ b/dimos/simulation/mujoco/mesh_scene.py @@ -387,6 +387,208 @@ class ScenePrimMesh: """``(M, 3)`` int32 vertex indices.""" +def _usd_matrix_to_numpy(matrix: Any) -> np.ndarray: + """Convert a USD row-major transform into column-vector numpy form.""" + return np.asarray(matrix, dtype=np.float64).T + + +def _transform_points(points: np.ndarray, matrix: np.ndarray) -> np.ndarray: + points_h = np.hstack([points, np.ones((len(points), 1), dtype=np.float64)]) + return np.asarray((matrix @ points_h.T).T[:, :3], dtype=np.float64) + + +def _triangulated_usd_mesh(usd_mesh: Any) -> tuple[np.ndarray, np.ndarray] | None: + pts_attr = usd_mesh.GetPointsAttr().Get() + if pts_attr is None or len(pts_attr) == 0: + return None + + face_verts_attr = usd_mesh.GetFaceVertexIndicesAttr().Get() + face_counts_attr = usd_mesh.GetFaceVertexCountsAttr().Get() + if face_verts_attr is None or face_counts_attr is None: + return None + + pts = np.asarray(pts_attr, dtype=np.float64) + face_verts = np.asarray(face_verts_attr, dtype=np.int32) + face_counts = np.asarray(face_counts_attr, dtype=np.int32) + + tris: list[tuple[int, int, int]] = [] + cursor = 0 + for n in face_counts: + if n < 3: + cursor += int(n) + continue + for k in range(1, int(n) - 1): + tris.append( + ( + int(face_verts[cursor]), + int(face_verts[cursor + k]), + int(face_verts[cursor + k + 1]), + ) + ) + cursor += int(n) + + if not tris: + return None + return pts, np.asarray(tris, dtype=np.int32) + + +def _aligned_scene_points( + pts_stage: np.ndarray, + *, + rotation: np.ndarray, + scale: float, + translation: np.ndarray, +) -> np.ndarray: + return np.asarray((rotation @ (scale * pts_stage).T).T + translation, dtype=np.float64) + + +def _clean_scene_name(raw: str) -> str: + return "".join(c if c.isalnum() else "_" for c in raw) + + +def _path_has_prefix(path: Any, prefix: Any) -> bool: + try: + return bool(path.HasPrefix(prefix)) + except AttributeError: + path_str = str(path) + prefix_str = str(prefix).rstrip("/") + return path_str == prefix_str or path_str.startswith(prefix_str + "/") + + +def _point_instancer_prototype_paths(stage: Any, UsdGeom: Any) -> tuple[Any, ...]: + paths: list[Any] = [] + for prim in stage.Traverse(): + if not prim.IsA(UsdGeom.PointInstancer): + continue + paths.extend(UsdGeom.PointInstancer(prim).GetPrototypesRel().GetTargets()) + return tuple(paths) + + +def _is_point_instancer_prototype_mesh(prim: Any, prototype_paths: tuple[Any, ...]) -> bool: + path = prim.GetPath() + return any(_path_has_prefix(path, proto_path) for proto_path in prototype_paths) + + +def _collect_prototype_meshes( + proto_prim: Any, + *, + Usd: Any, + UsdGeom: Any, +) -> list[tuple[str, np.ndarray, np.ndarray]]: + """Return prototype mesh triangles in prototype-root coordinates.""" + time = Usd.TimeCode.Default() + xform_cache = UsdGeom.XformCache(time) + proto_world = _usd_matrix_to_numpy(xform_cache.GetLocalToWorldTransform(proto_prim)) + proto_world_inv = np.linalg.inv(proto_world) + + meshes: list[tuple[str, np.ndarray, np.ndarray]] = [] + for mesh_prim in Usd.PrimRange(proto_prim): + if not mesh_prim.IsA(UsdGeom.Mesh): + continue + triangulated = _triangulated_usd_mesh(UsdGeom.Mesh(mesh_prim)) + if triangulated is None: + continue + pts, tris = triangulated + mesh_world = _usd_matrix_to_numpy(xform_cache.GetLocalToWorldTransform(mesh_prim)) + pts_proto = _transform_points(pts, proto_world_inv @ mesh_world) + mesh_path = str(mesh_prim.GetPath()).lstrip("/") + meshes.append((_clean_scene_name(mesh_path), pts_proto, tris)) + return meshes + + +def _compute_point_instance_transforms(instancer: Any, *, Usd: Any, UsdGeom: Any) -> list[Any]: + time = Usd.TimeCode.Default() + try: + return list( + instancer.ComputeInstanceTransformsAtTime( + time, + time, + UsdGeom.PointInstancer.ExcludeProtoXform, + ) + ) + except TypeError: + return list(instancer.ComputeInstanceTransformsAtTime(time, time)) + + +def _expand_point_instancer( + prim: Any, + *, + Usd: Any, + UsdGeom: Any, + rotation: np.ndarray, + scale: float, + translation: np.ndarray, + start_index: int, +) -> list[ScenePrimMesh]: + instancer = UsdGeom.PointInstancer(prim) + proto_targets = list(instancer.GetPrototypesRel().GetTargets()) + proto_indices_attr = instancer.GetProtoIndicesAttr().Get() + if not proto_targets or proto_indices_attr is None: + return [] + + proto_indices = list(proto_indices_attr) + instance_transforms = _compute_point_instance_transforms( + instancer, + Usd=Usd, + UsdGeom=UsdGeom, + ) + if not instance_transforms: + return [] + + time = Usd.TimeCode.Default() + xform_cache = UsdGeom.XformCache(time) + instancer_world = _usd_matrix_to_numpy(xform_cache.GetLocalToWorldTransform(prim)) + + prototype_cache: dict[str, list[tuple[str, np.ndarray, np.ndarray]]] = {} + prims: list[ScenePrimMesh] = [] + instancer_name = _clean_scene_name(str(prim.GetPath()).lstrip("/")) + + for instance_index, instance_transform in enumerate(instance_transforms): + if instance_index >= len(proto_indices): + continue + proto_index = int(proto_indices[instance_index]) + if proto_index < 0 or proto_index >= len(proto_targets): + continue + + proto_path = proto_targets[proto_index] + proto_prim = prim.GetStage().GetPrimAtPath(proto_path) + if not proto_prim or not proto_prim.IsValid(): + continue + + proto_key = str(proto_path) + if proto_key not in prototype_cache: + prototype_cache[proto_key] = _collect_prototype_meshes( + proto_prim, + Usd=Usd, + UsdGeom=UsdGeom, + ) + prototype_meshes = prototype_cache[proto_key] + if not prototype_meshes: + continue + + instance_matrix = _usd_matrix_to_numpy(instance_transform) + mesh_to_stage = instancer_world @ instance_matrix + for mesh_name, pts_proto, tris in prototype_meshes: + pts_stage = _transform_points(pts_proto, mesh_to_stage) + pts_world = _aligned_scene_points( + pts_stage, + rotation=rotation, + scale=scale, + translation=translation, + ) + prims.append( + ScenePrimMesh( + name=( + f"{instancer_name}_i{instance_index:05d}_" + f"{mesh_name}__{start_index + len(prims)}" + ), + vertices=pts_world.astype(np.float32), + triangles=tris, + ) + ) + return prims + + def _load_glb_prims(path: Path, alignment: SceneMeshAlignment) -> list[ScenePrimMesh]: """Enumerate per-instance prims from a glTF/GLB. @@ -458,7 +660,7 @@ def load_scene_prims( path: str | Path, alignment: SceneMeshAlignment | None = None, ) -> list[ScenePrimMesh]: - """Load a USD/USDZ scene as one ``ScenePrimMesh`` per Mesh prim. + """Load a USD/USDZ scene as one ``ScenePrimMesh`` per placed Mesh prim. Per-prim splitting is what MuJoCo wants for non-trivial scenes: each prim's convex hull approximates the prim well, while the @@ -466,6 +668,11 @@ def load_scene_prims( to a single ScenePrimMesh for non-USD inputs (a single ``.obj`` or ``.glb`` doesn't carry per-part semantics in our loader). + USD ``PointInstancer`` prims are expanded into their concrete + placements. Prototype meshes under the instancer's ``Prototypes`` + scope are skipped during ordinary traversal so they are not also + baked at their authoring origin. + Same alignment rules as ``load_scene_mesh``. """ path = Path(path) @@ -499,53 +706,50 @@ def load_scene_prims( T = np.asarray(align.translation, dtype=np.float64) s = float(align.scale) + prototype_paths = _point_instancer_prototype_paths(stage, UsdGeom) prims: list[ScenePrimMesh] = [] for prim in stage.Traverse(): + if prim.IsA(UsdGeom.PointInstancer): + prims.extend( + _expand_point_instancer( + prim, + Usd=Usd, + UsdGeom=UsdGeom, + rotation=R, + scale=s, + translation=T, + start_index=len(prims), + ) + ) + continue + if not prim.IsA(UsdGeom.Mesh): continue - usd_mesh = UsdGeom.Mesh(prim) - pts_attr = usd_mesh.GetPointsAttr().Get() - if pts_attr is None or len(pts_attr) == 0: + if _is_point_instancer_prototype_mesh(prim, prototype_paths): continue - pts = np.asarray(pts_attr, dtype=np.float64) - face_verts = np.asarray(usd_mesh.GetFaceVertexIndicesAttr().Get(), dtype=np.int32) - face_counts = np.asarray(usd_mesh.GetFaceVertexCountsAttr().Get(), dtype=np.int32) + + triangulated = _triangulated_usd_mesh(UsdGeom.Mesh(prim)) + if triangulated is None: + continue + pts, tris = triangulated # Local → stage-root via the USD prim's accumulated transform. xform = UsdGeom.Xformable(prim).ComputeLocalToWorldTransform(Usd.TimeCode.Default()) - m = np.asarray(xform, dtype=np.float64).T - pts_h = np.hstack([pts, np.ones((len(pts), 1), dtype=np.float64)]) - pts_stage = (m @ pts_h.T).T[:, :3] + pts_stage = _transform_points(pts, _usd_matrix_to_numpy(xform)) # Stage-root → dimos world via SceneMeshAlignment (scale → rot → trans). - pts_world = (R @ (s * pts_stage).T).T + T - - # Triangulate any quads / n-gons (vertex indices are local to this prim now). - tris: list[tuple[int, int, int]] = [] - cursor = 0 - for n in face_counts: - for k in range(1, n - 1): - tris.append( - ( - int(face_verts[cursor]), - int(face_verts[cursor + k]), - int(face_verts[cursor + k + 1]), - ) - ) - cursor += n - if not tris: - continue + pts_world = _aligned_scene_points(pts_stage, rotation=R, scale=s, translation=T) # MJCF asset names: strip the leading slash, swap remaining # path separators / dots for underscores. USD prim paths can # collide on the same leaf; suffix the index so each is unique. raw = str(prim.GetPath()).lstrip("/") - clean = "".join(c if c.isalnum() else "_" for c in raw) + clean = _clean_scene_name(raw) prims.append( ScenePrimMesh( name=f"{clean}__{len(prims)}", vertices=pts_world.astype(np.float32), - triangles=np.asarray(tris, dtype=np.int32), + triangles=tris, ) ) diff --git a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py index 0dbab0008c..540cbc43b4 100644 --- a/dimos/simulation/mujoco/scene_mesh_to_mjcf.py +++ b/dimos/simulation/mujoco/scene_mesh_to_mjcf.py @@ -179,7 +179,7 @@ # affect MJCF emission (new geom kinds, rewritten visual policy, etc.). # This is only a local cache salt; it is not a persisted file format # contract and old cache directories can safely stay on disk. -_CACHE_SCHEMA_VERSION = "dispatcher-v7" +_CACHE_SCHEMA_VERSION = "dispatcher-v8-point-instancer" @dataclass diff --git a/dimos/simulation/mujoco/test_mesh_scene.py b/dimos/simulation/mujoco/test_mesh_scene.py new file mode 100644 index 0000000000..99fb9afcad --- /dev/null +++ b/dimos/simulation/mujoco/test_mesh_scene.py @@ -0,0 +1,63 @@ +# 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 +import pytest + +from dimos.simulation.mujoco.mesh_scene import SceneMeshAlignment, load_scene_prims + +pytest.importorskip("pxr.Usd") +from pxr import Gf, Usd, UsdGeom # type: ignore[import-not-found, import-untyped] + + +def test_load_scene_prims_expands_usd_point_instancers(tmp_path): + scene_path = tmp_path / "instanced.usda" + stage = Usd.Stage.CreateNew(str(scene_path)) + + root = UsdGeom.Xform.Define(stage, "/Root") + root.AddTranslateOp().Set(Gf.Vec3d(10, 0, 0)) + + instancer = UsdGeom.PointInstancer.Define(stage, "/Root/Instancer") + instancer.CreatePositionsAttr([Gf.Vec3f(1, 2, 3), Gf.Vec3f(4, 5, 6)]) + instancer.CreateOrientationsAttr( + [ + Gf.Quath(1, Gf.Vec3h(0, 0, 0)), + Gf.Quath(1, Gf.Vec3h(0, 0, 0)), + ] + ) + instancer.CreateScalesAttr([Gf.Vec3f(1, 1, 1), Gf.Vec3f(2, 1, 1)]) + instancer.CreateProtoIndicesAttr([0, 0]) + + proto = UsdGeom.Xform.Define(stage, "/Root/Instancer/Prototypes/Proto") + mesh = UsdGeom.Mesh.Define(stage, "/Root/Instancer/Prototypes/Proto/Tri") + mesh.CreatePointsAttr( + [ + Gf.Vec3f(0, 0, 0), + Gf.Vec3f(1, 0, 0), + Gf.Vec3f(0, 1, 0), + ] + ) + mesh.CreateFaceVertexCountsAttr([3]) + mesh.CreateFaceVertexIndicesAttr([0, 1, 2]) + instancer.CreatePrototypesRel().SetTargets([proto.GetPath()]) + + stage.Save() + + prims = load_scene_prims(scene_path, SceneMeshAlignment(y_up=False)) + + assert len(prims) == 2 + assert np.allclose(prims[0].vertices.min(axis=0), [11, 2, 3]) + assert np.allclose(prims[0].vertices.max(axis=0), [12, 3, 3]) + assert np.allclose(prims[1].vertices.min(axis=0), [14, 5, 6]) + assert np.allclose(prims[1].vertices.max(axis=0), [16, 6, 6])